|
| 1 | +import mavlink2rest from '@/libs/MAVLink2Rest' |
| 2 | +import { |
| 3 | + MavCmd, MAVLinkType, MavResult, |
| 4 | +} from '@/libs/MAVLink2Rest/mavlink2rest-ts/messages/mavlink2rest-enum' |
| 5 | +import autopilot_data from '@/store/autopilot' |
| 6 | +import { sleep } from '@/utils/helper_functions' |
| 7 | + |
| 8 | +enum PreflightCalibration { |
| 9 | + GYROSCOPE, |
| 10 | + GYROSCOPE_TEMPERATURE, |
| 11 | + MAGNETOMETER, |
| 12 | + PRESSURE, |
| 13 | + RC, |
| 14 | + RC_TRIM, |
| 15 | + ACCELEROMETER, |
| 16 | + BOARD_LEVEL, |
| 17 | + ACCELEROMETER_TEMPERATURE, |
| 18 | + SIMPLE_ACCELEROMETER, |
| 19 | + COMPASS_MOTOR_INTERFERENCE, |
| 20 | + AIRPSEED, |
| 21 | + ESC, |
| 22 | + BAROMETER_TEMPERATURE, |
| 23 | +} |
| 24 | + |
| 25 | +class Calibrator { |
| 26 | + private static instance: Calibrator |
| 27 | + |
| 28 | + private calibrating: PreflightCalibration | undefined |
| 29 | + |
| 30 | + private calibrationStatus: MavResult | undefined |
| 31 | + |
| 32 | + constructor() { |
| 33 | + mavlink2rest.startListening(MAVLinkType.COMMAND_ACK).setCallback((content) => { |
| 34 | + const { header, message } = content |
| 35 | + if (header.system_id !== autopilot_data.system_id || header.component_id !== 1) { |
| 36 | + return |
| 37 | + } |
| 38 | + if (message.command.type === MavCmd.MAV_CMD_PREFLIGHT_CALIBRATION) { |
| 39 | + this.calibrationStatus = message.result.type |
| 40 | + } |
| 41 | + }).setFrequency(0) |
| 42 | + } |
| 43 | + |
| 44 | + /** |
| 45 | + * Singleton access |
| 46 | + * @returns Calibrator |
| 47 | + */ |
| 48 | + public static getInstance(): Calibrator { |
| 49 | + if (!Calibrator.instance) { |
| 50 | + Calibrator.instance = new Calibrator() |
| 51 | + } |
| 52 | + return Calibrator.instance |
| 53 | + } |
| 54 | + |
| 55 | + /** |
| 56 | + * Start calibration process |
| 57 | + * @param {PreflightCalibration} type |
| 58 | + */ |
| 59 | + private static start(type: PreflightCalibration): void { |
| 60 | + mavlink2rest.sendMessage({ |
| 61 | + header: { |
| 62 | + system_id: 255, |
| 63 | + component_id: 0, |
| 64 | + sequence: 0, |
| 65 | + }, |
| 66 | + message: { |
| 67 | + type: MAVLinkType.COMMAND_LONG, |
| 68 | + param1: { |
| 69 | + [PreflightCalibration.GYROSCOPE]: 1, |
| 70 | + [PreflightCalibration.GYROSCOPE_TEMPERATURE]: 3, |
| 71 | + }[type] || 0, |
| 72 | + param2: type === PreflightCalibration.MAGNETOMETER ? 1 : 0, |
| 73 | + param3: type === PreflightCalibration.PRESSURE ? 1 : 0, |
| 74 | + param4: { |
| 75 | + [PreflightCalibration.RC]: 1, |
| 76 | + [PreflightCalibration.RC_TRIM]: 2, |
| 77 | + }[type] || 0, |
| 78 | + param5: { |
| 79 | + [PreflightCalibration.ACCELEROMETER]: 1, |
| 80 | + [PreflightCalibration.BOARD_LEVEL]: 2, |
| 81 | + [PreflightCalibration.ACCELEROMETER_TEMPERATURE]: 3, |
| 82 | + [PreflightCalibration.SIMPLE_ACCELEROMETER]: 4, |
| 83 | + }[type] || 0, |
| 84 | + param6: { |
| 85 | + [PreflightCalibration.COMPASS_MOTOR_INTERFERENCE]: 1, |
| 86 | + [PreflightCalibration.AIRPSEED]: 2, |
| 87 | + }[type] || 0, |
| 88 | + param7: { |
| 89 | + [PreflightCalibration.ESC]: 1, |
| 90 | + [PreflightCalibration.BAROMETER_TEMPERATURE]: 3, |
| 91 | + }[type] || 0, |
| 92 | + command: { |
| 93 | + type: MavCmd.MAV_CMD_PREFLIGHT_CALIBRATION, |
| 94 | + }, |
| 95 | + target_system: autopilot_data.system_id, |
| 96 | + target_component: 1, |
| 97 | + confirmation: 0, |
| 98 | + }, |
| 99 | + }) |
| 100 | + } |
| 101 | + |
| 102 | + /** |
| 103 | + * Generator function for calibration status with timeout |
| 104 | + * @param {PreflightCaliration} type |
| 105 | + * @param {number} timeout in seconds |
| 106 | + */ |
| 107 | + public async* calibrate(type: PreflightCalibration, timeout = 6): AsyncGenerator<MavResult | string> { |
| 108 | + const startTime = Date.now() |
| 109 | + Calibrator.start(type) |
| 110 | + |
| 111 | + while (true) { |
| 112 | + await sleep(200) |
| 113 | + |
| 114 | + switch (this.calibrationStatus) { |
| 115 | + case MavResult.MAV_RESULT_ACCEPTED: |
| 116 | + this.calibrationStatus = undefined |
| 117 | + yield 'Calibration done.' |
| 118 | + return |
| 119 | + |
| 120 | + case MavResult.MAV_RESULT_IN_PROGRESS: |
| 121 | + this.calibrationStatus = undefined |
| 122 | + yield 'In progress..' |
| 123 | + continue |
| 124 | + |
| 125 | + case MavResult.MAV_RESULT_CANCELLED: |
| 126 | + case MavResult.MAV_RESULT_DENIED: |
| 127 | + case MavResult.MAV_RESULT_FAILED: |
| 128 | + case MavResult.MAV_RESULT_TEMPORARILY_REJECTED: |
| 129 | + case MavResult.MAV_RESULT_UNSUPPORTED: |
| 130 | + yield `Calibration failed with status: ${this.calibrationStatus}` |
| 131 | + this.calibrationStatus = undefined |
| 132 | + return |
| 133 | + |
| 134 | + default: |
| 135 | + // Handle any other potential cases if needed |
| 136 | + yield 'Waiting for vehicle..' |
| 137 | + } |
| 138 | + |
| 139 | + // Check for timeout |
| 140 | + if (Date.now() - startTime > timeout * 1000) { |
| 141 | + yield `Calibration timed out after ${timeout} seconds.` |
| 142 | + return |
| 143 | + } |
| 144 | + } |
| 145 | + } |
| 146 | +} |
| 147 | + |
| 148 | +const calibrator = Calibrator.getInstance() |
| 149 | +export { calibrator, PreflightCalibration } |
0 commit comments