-
Notifications
You must be signed in to change notification settings - Fork 65
/
FullCompassCalibrator.vue
240 lines (231 loc) · 7.04 KB
/
FullCompassCalibrator.vue
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
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
<template>
<v-dialog
v-model="dialog"
width="600"
>
<template #activator="{ on, attrs }">
<v-btn
color="primary"
v-bind="attrs"
v-on="on"
>
Full Calibration
</v-btn>
</template>
<v-card>
<v-card-title class="text-h5 grey lighten-2">
Onboard Compass Calibration
</v-card-title>
<v-card-text class="pa-10">
<span v-if="state === states.IDLE">
<p>
<strong> Onboard Compass Calibration</strong> is the regular calibration used
for Ardupilot vehicles.
It requires you to spin the vehicle aroung all axis, which allows it to calibrated the
readings to the expected local magnetic field.
</p>
<p>
A Valid position is <strong>recomended</strong> for Onboard Calibration to estimate the
local world magnetic field.
</p>
</span>
<span v-else-if="state === states.CALIBRATING">
Spin your vehicle around all of its axis until the progress bar completes.
</span>
<auto-coordinate-detector
v-if="state === states.IDLE"
v-model="coordinates"
/>
<compass-mask-picker v-if="state === states.IDLE" v-model="compass_mask" :devices="compasses" />
<v-divider />
<v-alert
v-if="status_text"
:type="status_type"
>
{{ status_text }}
</v-alert>
<v-simple-table v-if="Object.keys(fitness).length">
<thead>
<th>Compass</th>
<th>
Fitness (mGauss)
</th>
</thead>
<tbody>
<tr v-for="(fit, compass) of fitness" :key="compass">
<td>{{ compass }}</td>
<td>
<calibrationQualityIndicator :quality="fit" />
</td>
</tr>
</tbody>
</v-simple-table>
<v-progress-linear
v-if="percent && !all_compasses_calibrated"
v-model="percent"
color="blue-grey"
height="25"
class="mt-5 mb-5"
>
<template #default="{ value }">
<strong>{{ Math.ceil(value) }}%</strong>
</template>
</v-progress-linear>
<StatusTextWatcher :filter="/.*/" :style="`display : ${status_type === 'error' ? 'block' : 'none'};`" />
</v-card-text>
<v-card-actions>
<v-spacer />
<v-btn v-if="state !== states.CALIBRATING" color="primary" :disabled="!compass_mask" @click="calibrate()">
Calibrate
</v-btn>
<v-btn v-if="state === states.DONE" color="primary" @click="dismiss">
Ok
</v-btn>
<v-btn color="red" :disabled="state !== states.CALIBRATING" @click="cancelCalibration()">
Cancel
</v-btn>
</v-card-actions>
</v-card>
</v-dialog>
</template>
<script lang="ts">
import Vue, { PropType } from 'vue'
import mavlink2rest from '@/libs/MAVLink2Rest'
import Listener from '@/libs/MAVLink2Rest/Listener'
import { MavCmd, MAVLinkType, MavResult } from '@/libs/MAVLink2Rest/mavlink2rest-ts/messages/mavlink2rest-enum'
import { Dictionary } from '@/types/common'
import { deviceId } from '@/utils/deviceid_decoder'
import CalibrationQualityIndicator from './CalibrationQualityIndicator.vue'
enum states {
IDLE,
CALIBRATING,
DONE,
FAILED,
}
export default {
name: 'FullCompassCalibrator',
components: {
CalibrationQualityIndicator,
},
props: {
compasses: {
type: Array as PropType<deviceId[]>,
required: true,
},
},
data() {
return {
dialog: false,
coordinates: undefined as { lat: number, lon: number } | undefined,
compass_mask: 0,
status_type: '' as string | undefined,
status_text: '' as string | undefined,
percent: 0,
state: states.IDLE,
progress_listener: undefined as Listener | undefined,
report_listener: undefined as Listener | undefined,
fitness: {} as Dictionary<number>,
}
},
computed: {
states() {
return states
},
compasses_calibrated(): number {
return Object.keys(this.fitness).length
},
all_compasses_calibrated(): boolean {
return this.compasses_calibrated === this.compasses.length
},
},
watch: {
all_compasses_calibrated(newValue) {
if (newValue) {
this.calibrationFinished()
}
},
dialog(newValue) {
if (!newValue) {
this.dismiss()
}
},
},
beforeMount() {
this.state = states.IDLE
this.fitness = {}
this.cleanup()
},
beforeDestroy() {
this.progress_listener?.discard()
},
methods: {
dismiss() {
this.state = states.IDLE
this.dialog = false
this.cleanup()
this.fitness = {}
},
cleanup() {
this.progress_listener?.discard()
this.report_listener?.discard()
this.percent = 0
this.status_type = undefined
this.status_text = undefined
},
calibrationFinished() {
this.status_type = 'success'
this.status_text = 'Calibration finished'
this.state = states.DONE
this.cleanup()
},
calibrationFailed(reason: string) {
this.status_text = `Calibration failed: ${reason}`
this.status_type = 'error'
this.state = states.FAILED
},
async cancelCalibration() {
mavlink2rest.sendCommandLong(MavCmd.MAV_CMD_DO_CANCEL_MAG_CAL)
const ack = await mavlink2rest.waitForAck(MavCmd.MAV_CMD_DO_CANCEL_MAG_CAL)
if (ack.result.type !== MavResult.MAV_RESULT_ACCEPTED) {
throw new Error(`Unexpected response trying to cancel calibration: ${ack.result.type}`)
}
this.percent = 0
this.status_text = 'Calibration cancelled'
this.status_type = 'warning'
this.progress_listener?.discard()
this.state = states.FAILED
},
async calibrate() {
this.fitness = {}
this.status_text = undefined
this.state = states.CALIBRATING
mavlink2rest.sendCommandLong(
MavCmd.MAV_CMD_DO_START_MAG_CAL,
this.compass_mask,
0,
1, // auto-save calibration
)
try {
const ack = await mavlink2rest.waitForAck(MavCmd.MAV_CMD_DO_START_MAG_CAL)
if (ack.result.type !== MavResult.MAV_RESULT_ACCEPTED) {
throw new Error(`Unexpected response: ${ack.result.type}`)
}
this.progress_listener = mavlink2rest.startListening(MAVLinkType.MAG_CAL_PROGRESS).setCallback(
(message) => {
this.percent = Math.max(message.message.completion_pct, 0.01)
},
).setFrequency(0)
this.report_listener = mavlink2rest.startListening(MAVLinkType.MAG_CAL_REPORT).setCallback(
(message) => {
const name = this.compasses[message.message.compass_id].deviceName ?? 'unknown'
// we need to use Vue.set when adding a key to a dict to ensure reactivity...
Vue.set(this.fitness, name, message.message.fitness)
},
).setFrequency(0)
} catch (error) {
this.calibrationFailed(`${error}`)
}
},
},
}
</script>