-
Notifications
You must be signed in to change notification settings - Fork 64
/
calibration.ts
149 lines (134 loc) · 4.17 KB
/
calibration.ts
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
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
}
}).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)
switch (this.calibrationStatus) {
case MavResult.MAV_RESULT_ACCEPTED:
this.calibrationStatus = undefined
yield 'Calibration done.'
return
case MavResult.MAV_RESULT_IN_PROGRESS:
this.calibrationStatus = undefined
yield 'In progress..'
continue
case MavResult.MAV_RESULT_CANCELLED:
case MavResult.MAV_RESULT_DENIED:
case MavResult.MAV_RESULT_FAILED:
case MavResult.MAV_RESULT_TEMPORARILY_REJECTED:
case MavResult.MAV_RESULT_UNSUPPORTED:
yield `Calibration failed with status: ${this.calibrationStatus}`
this.calibrationStatus = undefined
return
default:
// Handle any other potential cases if needed
yield 'Waiting for vehicle..'
}
// Check for timeout
if (Date.now() - startTime > timeout * 1000) {
yield `Calibration timed out after ${timeout} seconds.`
return
}
}
}
}
const calibrator = Calibrator.getInstance()
export { calibrator, PreflightCalibration }