Skip to content

Commit

Permalink
wip
Browse files Browse the repository at this point in the history
Signed-off-by: Patrick José Pereira <patrickelectric@gmail.com>
  • Loading branch information
patrickelectric committed Jan 24, 2024
1 parent b2f5427 commit a608f5a
Show file tree
Hide file tree
Showing 3 changed files with 234 additions and 1 deletion.
3 changes: 2 additions & 1 deletion core/frontend/src/components/vehiclesetup/Configure.vue
Expand Up @@ -28,6 +28,7 @@
import Vue from 'vue'
import { calibrator, PreflightCalibration } from './calibration'
import BaroCalib from './overview/BaroCalib.vue'
import ParamSets from './overview/ParamSets.vue'
export interface Item {
Expand All @@ -48,7 +49,7 @@ export default Vue.extend({
{ title: 'Parameters', component: ParamSets },
{ title: 'Accelerometer', component: undefined },
{ title: 'Compass', component: undefined },
{ title: 'Baro', component: undefined },
{ title: 'Baro', component: BaroCalib },
{ title: 'Gripper', component: undefined },
{ title: 'Lights', component: undefined },
{ title: 'Camera Mount', component: undefined },
Expand Down
153 changes: 153 additions & 0 deletions core/frontend/src/components/vehiclesetup/calibration.ts
@@ -0,0 +1,153 @@
import mavlink2rest from '@/libs/MAVLink2Rest'
import {
MavCmd, MAVLinkType, MavResult,
} from '@/libs/MAVLink2Rest/mavlink2rest-ts/messages/mavlink2rest-enum'
import autopilot_data from '@/store/autopilot'
import { sleep } from '@/utils/helper_functions'

enum PreflightCalibration {
GYROSCOPE,
GYROSCOPE_TEMPERATURE,
MAGNETOMETER,
PRESSURE,
RC,
RC_TRIM,
ACCELEROMETER,
BOARD_LEVEL,
ACCELEROMETER_TEMPERATURE,
SIMPLE_ACCELEROMETER,
COMPASS_MOTOR_INTERFERENCE,
AIRPSEED,
ESC,
BAROMETER_TEMPERATURE,
}

class Calibrator {
private static instance: Calibrator

private calibrating: PreflightCalibration | undefined

private calibrationStatus: MavResult | undefined

constructor() {
mavlink2rest.startListening(MAVLinkType.COMMAND_ACK).setCallback((content) => {
const { header, message } = content
if (header.system_id !== autopilot_data.system_id || header.component_id !== 1) {
return
}
if (message.command.type === MavCmd.MAV_CMD_PREFLIGHT_CALIBRATION) {
this.calibrationStatus = message.result.type
console.log('Got!')
}
}).setFrequency(0)
}

/**
* Singleton access
* @returns Calibrator
*/
public static getInstance(): Calibrator {
if (!Calibrator.instance) {
Calibrator.instance = new Calibrator()
}
return Calibrator.instance
}

/**
* Start calibration process
* @param {PreflightCalibration} type
*/
private static start(type: PreflightCalibration): void {
mavlink2rest.sendMessage({
header: {
system_id: 255,
component_id: 0,
sequence: 0,
},
message: {
type: MAVLinkType.COMMAND_LONG,
param1: {
[PreflightCalibration.GYROSCOPE]: 1,
[PreflightCalibration.GYROSCOPE_TEMPERATURE]: 3,
}[type] || 0,
param2: type === PreflightCalibration.MAGNETOMETER ? 1 : 0,
param3: type === PreflightCalibration.PRESSURE ? 1 : 0,
param4: {
[PreflightCalibration.RC]: 1,
[PreflightCalibration.RC_TRIM]: 2,
}[type] || 0,
param5: {
[PreflightCalibration.ACCELEROMETER]: 1,
[PreflightCalibration.BOARD_LEVEL]: 2,
[PreflightCalibration.ACCELEROMETER_TEMPERATURE]: 3,
[PreflightCalibration.SIMPLE_ACCELEROMETER]: 4,
}[type] || 0,
param6: {
[PreflightCalibration.COMPASS_MOTOR_INTERFERENCE]: 1,
[PreflightCalibration.AIRPSEED]: 2,
}[type] || 0,
param7: {
[PreflightCalibration.ESC]: 1,
[PreflightCalibration.BAROMETER_TEMPERATURE]: 3,
}[type] || 0,
command: {
type: MavCmd.MAV_CMD_PREFLIGHT_CALIBRATION,
},
target_system: autopilot_data.system_id,
target_component: 1,
confirmation: 0,
},
})
}

/**
* Generator function for calibration status with timeout
* @param {PreflightCaliration} type
* @param {number} timeout in seconds
*/
public async* calibrate(type: PreflightCalibration, timeout = 6): AsyncGenerator<MavResult | string> {
const startTime = Date.now()
Calibrator.start(type)

while (true) {
await sleep(200)

if (this.calibrationStatus !== undefined) {
yield this.calibrationStatus
if (this.calibrationStatus === MavResult.MAV_RESULT_IN_PROGRESS) {
this.calibrationStatus = undefined
yield 'TODO in progress'
return
}
return
}

yield 'Waiting for vehicle..'

// Check for timeout
if (Date.now() - startTime > timeout * 1000) {
yield `Calibration timed out after ${timeout} seconds.`
return
}

// Add some delay here if you want to poll at a certain interval
// For example, you can use setTimeout or setImmediate in a Node.js environment
}
}
}

const calibrator = Calibrator.getInstance()
export { calibrator, PreflightCalibration }

/*
switch (Calibrator.calibrationStatus) {
case MavResult.MAV_RESULT_ACCEPTED: console.log('good'); break
case MavResult.MAV_RESULT_TEMPORARILY_REJECTED: console.log('TEMPORARILY_REJECTED'); break
case MavResult.MAV_RESULT_DENIED: console.log('DENIED'); break
case MavResult.MAV_RESULT_UNSUPPORTED: console.log('UNSUPPORTED'); break
case MavResult.MAV_RESULT_FAILED: console.log('FAILED'); break
case MavResult.MAV_RESULT_IN_PROGRESS: console.log('IN_PROGRESS'); break
case MavResult.MAV_RESULT_CANCELLED: console.log('CANCELLED'); break
default: console.error(`Unreachable type for calibration: ${message.result.type}`)
}
*/
79 changes: 79 additions & 0 deletions core/frontend/src/components/vehiclesetup/overview/BaroCalib.vue
@@ -0,0 +1,79 @@
<template>
<v-card class="ma-2 pa-2">
<v-card-title class="align-center">
Calibrate Barometer
</v-card-title>
<!--v-card-text>
<v-btn
color="primary"
@click="calibrate"
>
Calibrate
</v-btn>
</v-card-text-->
<v-card-text>
<v-simple-table dense>
<template #default>
<thead>
<tr>
<th class="text-left">
Sensor
</th>
<th class="text-left">
Type
</th>
<th class="text-left">
Bus
</th>
<th class="text-left">
Address
</th>
<th class="text-left">
Status
</th>
<th class="text-left">
Calibrate
</th>
</tr>
</thead>
<tbody>
<tr
v-for="baro in baros"
:key="baro.param"
>
<td><b>{{ baro.deviceName ?? 'UNKNOWN' }}</b></td>
<td v-tooltip="'Used to estimate altitude/depth'">
{{ get_pressure_type[baro.param] }} Pressure
</td>
<td>{{ baro.busType }} {{ baro.bus }}</td>
<td>{{ `0x${baro.address}` }}</td>
<td>{{ baro_status[baro.param] }}</td>
</tr>
</tbody>
</template>
</v-simple-table>
</v-card-text>
</v-card>
</template>

<script lang="ts">
import Vue from 'vue'

import { calibrator, PreflightCalibration } from '../calibration'

export default Vue.extend({
name: 'BaroCalibrate',
methods: {
async calibrate() {
for await (const value of calibrator.calibrate(PreflightCalibration.PRESSURE)) {
console.log(`value: ${value}`)
}
},
},
})
</script>
<style scoped>
button {
margin: 10px;
}
</style>

0 comments on commit a608f5a

Please sign in to comment.