CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.

GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_AccelCal/AP_AccelCal.cpp
Views: 1798
1
/*
2
This program is free software: you can redistribute it and/or modify
3
it under the terms of the GNU General Public License as published by
4
the Free Software Foundation, either version 3 of the License, or
5
(at your option) any later version.
6
This program is distributed in the hope that it will be useful,
7
but WITHOUT ANY WARRANTY; without even the implied warranty of
8
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
9
GNU General Public License for more details.
10
You should have received a copy of the GNU General Public License
11
along with this program. If not, see <http://www.gnu.org/licenses/>.
12
*/
13
14
#include "AP_AccelCal.h"
15
16
#if HAL_INS_ACCELCAL_ENABLED
17
18
#include <stdarg.h>
19
#include <AP_HAL/AP_HAL.h>
20
#include <GCS_MAVLink/GCS.h>
21
22
#define AP_ACCELCAL_POSITION_REQUEST_INTERVAL_MS 1000
23
24
#define _printf(fmt, args ...) do { \
25
if (_gcs != nullptr) { \
26
_gcs->send_text(MAV_SEVERITY_CRITICAL, fmt, ## args); \
27
} \
28
} while (0)
29
30
31
const extern AP_HAL::HAL& hal;
32
static bool _start_collect_sample;
33
34
uint8_t AP_AccelCal::_num_clients = 0;
35
AP_AccelCal_Client* AP_AccelCal::_clients[AP_ACCELCAL_MAX_NUM_CLIENTS] {};
36
37
void AP_AccelCal::update()
38
{
39
if (!get_calibrator(0)) {
40
// no calibrators
41
return;
42
}
43
44
if (_started) {
45
update_status();
46
47
uint8_t num_active_calibrators = 0;
48
for(uint8_t i=0; get_calibrator(i) != nullptr; i++) {
49
num_active_calibrators++;
50
}
51
if (num_active_calibrators != _num_active_calibrators) {
52
fail();
53
return;
54
}
55
if(_start_collect_sample) {
56
collect_sample();
57
}
58
AccelCalibrator *cal;
59
switch(_status) {
60
case ACCEL_CAL_NOT_STARTED:
61
fail();
62
return;
63
case ACCEL_CAL_WAITING_FOR_ORIENTATION: {
64
// if we're waiting for orientation, first ensure that all calibrators are on the same step
65
uint8_t step;
66
if ((cal = get_calibrator(0)) == nullptr) {
67
fail();
68
return;
69
}
70
step = cal->get_num_samples_collected()+1;
71
72
for(uint8_t i=1 ; (cal = get_calibrator(i)) ; i++) {
73
if (step != cal->get_num_samples_collected()+1) {
74
fail();
75
return;
76
}
77
}
78
// if we're on a new step, print a message describing the step
79
if (step != _step) {
80
_step = step;
81
82
if(_use_gcs_snoop) {
83
const char *msg;
84
switch (step) {
85
case ACCELCAL_VEHICLE_POS_LEVEL:
86
msg = "level";
87
break;
88
case ACCELCAL_VEHICLE_POS_LEFT:
89
msg = "on its LEFT side";
90
break;
91
case ACCELCAL_VEHICLE_POS_RIGHT:
92
msg = "on its RIGHT side";
93
break;
94
case ACCELCAL_VEHICLE_POS_NOSEDOWN:
95
msg = "nose DOWN";
96
break;
97
case ACCELCAL_VEHICLE_POS_NOSEUP:
98
msg = "nose UP";
99
break;
100
case ACCELCAL_VEHICLE_POS_BACK:
101
msg = "on its BACK";
102
break;
103
default:
104
fail();
105
return;
106
}
107
_printf("Place vehicle %s and press any key.", msg);
108
_waiting_for_mavlink_ack = true;
109
}
110
}
111
112
uint32_t now = AP_HAL::millis();
113
if (now - _last_position_request_ms > AP_ACCELCAL_POSITION_REQUEST_INTERVAL_MS) {
114
_last_position_request_ms = now;
115
_gcs->send_accelcal_vehicle_position(step);
116
}
117
break;
118
}
119
case ACCEL_CAL_COLLECTING_SAMPLE:
120
// check for timeout
121
122
for(uint8_t i=0; (cal = get_calibrator(i)); i++) {
123
cal->check_for_timeout();
124
}
125
126
update_status();
127
128
if (_status == ACCEL_CAL_FAILED) {
129
fail();
130
}
131
return;
132
case ACCEL_CAL_SUCCESS:
133
// save
134
if (_saving) {
135
bool done = true;
136
for(uint8_t i=0; i<_num_clients; i++) {
137
if (client_active(i) && _clients[i]->_acal_get_saving()) {
138
done = false;
139
break;
140
}
141
}
142
if (done) {
143
success();
144
}
145
return;
146
} else {
147
for(uint8_t i=0; i<_num_clients; i++) {
148
if(client_active(i) && _clients[i]->_acal_get_fail()) {
149
fail();
150
return;
151
}
152
}
153
for(uint8_t i=0; i<_num_clients; i++) {
154
if(client_active(i)) {
155
_clients[i]->_acal_save_calibrations();
156
}
157
}
158
_saving = true;
159
}
160
return;
161
default:
162
case ACCEL_CAL_FAILED:
163
fail();
164
return;
165
}
166
} else if (_last_result != ACCEL_CAL_NOT_STARTED) {
167
// only continuously report if we have ever completed a calibration
168
uint32_t now = AP_HAL::millis();
169
if (now - _last_position_request_ms > AP_ACCELCAL_POSITION_REQUEST_INTERVAL_MS) {
170
_last_position_request_ms = now;
171
switch (_last_result) {
172
case ACCEL_CAL_SUCCESS:
173
_gcs->send_accelcal_vehicle_position(ACCELCAL_VEHICLE_POS_SUCCESS);
174
break;
175
case ACCEL_CAL_FAILED:
176
_gcs->send_accelcal_vehicle_position(ACCELCAL_VEHICLE_POS_FAILED);
177
break;
178
default:
179
// should never hit this state
180
break;
181
}
182
}
183
}
184
}
185
186
void AP_AccelCal::start(GCS_MAVLINK *gcs)
187
{
188
if (gcs == nullptr || _started) {
189
return;
190
}
191
_start_collect_sample = false;
192
_num_active_calibrators = 0;
193
194
AccelCalibrator *cal;
195
for(uint8_t i=0; (cal = get_calibrator(i)); i++) {
196
cal->clear();
197
cal->start(ACCEL_CAL_AXIS_ALIGNED_ELLIPSOID, 6, 0.5f);
198
_num_active_calibrators++;
199
}
200
201
_started = true;
202
_saving = false;
203
_gcs = gcs;
204
_use_gcs_snoop = true;
205
_last_position_request_ms = 0;
206
_step = 0;
207
208
_last_result = ACCEL_CAL_NOT_STARTED;
209
210
update_status();
211
}
212
213
void AP_AccelCal::success()
214
{
215
_printf("Calibration successful");
216
217
for(uint8_t i=0 ; i < _num_clients ; i++) {
218
_clients[i]->_acal_event_success();
219
}
220
221
_last_result = ACCEL_CAL_SUCCESS;
222
223
clear();
224
}
225
226
void AP_AccelCal::cancel()
227
{
228
_printf("Calibration cancelled");
229
230
for(uint8_t i=0 ; i < _num_clients ; i++) {
231
_clients[i]->_acal_event_cancellation();
232
}
233
234
_last_result = ACCEL_CAL_NOT_STARTED;
235
236
clear();
237
}
238
239
void AP_AccelCal::fail()
240
{
241
_printf("Calibration FAILED");
242
243
for(uint8_t i=0 ; i < _num_clients ; i++) {
244
_clients[i]->_acal_event_failure();
245
}
246
247
_last_result = ACCEL_CAL_FAILED;
248
249
clear();
250
}
251
252
void AP_AccelCal::clear()
253
{
254
if (!_started) {
255
return;
256
}
257
258
AccelCalibrator *cal;
259
for(uint8_t i=0 ; (cal = get_calibrator(i)) ; i++) {
260
cal->clear();
261
}
262
263
_step = 0;
264
_started = false;
265
_saving = false;
266
267
update_status();
268
}
269
270
void AP_AccelCal::collect_sample()
271
{
272
if (_status != ACCEL_CAL_WAITING_FOR_ORIENTATION) {
273
return;
274
}
275
276
for(uint8_t i=0; i<_num_clients; i++) {
277
if (client_active(i) && !_clients[i]->_acal_get_ready_to_sample()) {
278
_printf("Not ready to sample");
279
return;
280
}
281
}
282
283
AccelCalibrator *cal;
284
for(uint8_t i=0 ; (cal = get_calibrator(i)) ; i++) {
285
cal->collect_sample();
286
}
287
_start_collect_sample = false;
288
update_status();
289
}
290
291
void AP_AccelCal::register_client(AP_AccelCal_Client* client) {
292
if (client == nullptr || _num_clients >= AP_ACCELCAL_MAX_NUM_CLIENTS) {
293
return;
294
}
295
296
297
for(uint8_t i=0; i<_num_clients; i++) {
298
if(_clients[i] == client) {
299
return;
300
}
301
}
302
_clients[_num_clients] = client;
303
_num_clients++;
304
}
305
306
AccelCalibrator* AP_AccelCal::get_calibrator(uint8_t index) {
307
AccelCalibrator* ret;
308
for(uint8_t i=0; i<_num_clients; i++) {
309
for(uint8_t j=0 ; (ret = _clients[i]->_acal_get_calibrator(j)) ; j++) {
310
if (index == 0) {
311
return ret;
312
}
313
index--;
314
}
315
}
316
return nullptr;
317
}
318
319
void AP_AccelCal::update_status() {
320
AccelCalibrator *cal;
321
322
if (!get_calibrator(0)) {
323
// no calibrators
324
_status = ACCEL_CAL_NOT_STARTED;
325
return;
326
}
327
328
for(uint8_t i=0 ; (cal = get_calibrator(i)) ; i++) {
329
if (cal->get_status() == ACCEL_CAL_FAILED) {
330
_status = ACCEL_CAL_FAILED; //fail if even one of the calibration has
331
return;
332
}
333
}
334
335
for(uint8_t i=0 ; (cal = get_calibrator(i)) ; i++) {
336
if (cal->get_status() == ACCEL_CAL_COLLECTING_SAMPLE) {
337
_status = ACCEL_CAL_COLLECTING_SAMPLE; // move to Collecting sample state if all the callibrators have
338
return;
339
}
340
}
341
342
for(uint8_t i=0 ; (cal = get_calibrator(i)) ; i++) {
343
if (cal->get_status() == ACCEL_CAL_WAITING_FOR_ORIENTATION) {
344
_status = ACCEL_CAL_WAITING_FOR_ORIENTATION; // move to waiting for user ack for orientation confirmation
345
return;
346
}
347
}
348
349
for(uint8_t i=0 ; (cal = get_calibrator(i)) ; i++) {
350
if (cal->get_status() == ACCEL_CAL_NOT_STARTED) {
351
_status = ACCEL_CAL_NOT_STARTED; // we haven't started if all the calibrators haven't
352
return;
353
}
354
}
355
356
_status = ACCEL_CAL_SUCCESS; // we have succeeded calibration if all the calibrators have
357
return;
358
}
359
360
bool AP_AccelCal::client_active(uint8_t client_num)
361
{
362
return (bool)_clients[client_num]->_acal_get_calibrator(0);
363
}
364
365
#if HAL_GCS_ENABLED
366
void AP_AccelCal::handle_command_ack(const mavlink_command_ack_t &packet)
367
{
368
if (!_waiting_for_mavlink_ack) {
369
return;
370
}
371
// this is support for the old, non-accelcal-specific calibration.
372
// The GCS is expected to send back a COMMAND_ACK when the vehicle
373
// is posed, but we placed no constraints on the result code or
374
// the command field in the ack packet. That meant that any ACK
375
// would move the cal process forward - and since we don't even
376
// check the source system/component here the process could easily
377
// fail due to other ACKs floating around the mavlink network.
378
// GCSs should be moved to using the non-gcs-snoop method. As a
379
// round-up:
380
// MAVProxy: command=1-6 depending on pose, result=1
381
// QGC: command=0, result=1
382
// MissionPlanner: uses new ACCELCAL_VEHICLE_POS
383
if (packet.command > 6) {
384
// not an acknowledgement for a vehicle position
385
return;
386
}
387
if (packet.result != MAV_RESULT_TEMPORARILY_REJECTED) {
388
// not an acknowledgement for a vehicle position
389
return;
390
}
391
_waiting_for_mavlink_ack = false;
392
_start_collect_sample = true;
393
}
394
395
bool AP_AccelCal::gcs_vehicle_position(float position)
396
{
397
_use_gcs_snoop = false;
398
399
if (_status == ACCEL_CAL_WAITING_FOR_ORIENTATION && is_equal((float) _step, position)) {
400
_start_collect_sample = true;
401
return true;
402
}
403
404
return false;
405
}
406
#endif
407
408
// true if we are in a calibration process
409
bool AP_AccelCal::running(void) const
410
{
411
return _status == ACCEL_CAL_WAITING_FOR_ORIENTATION || _status == ACCEL_CAL_COLLECTING_SAMPLE;
412
}
413
#endif //HAL_INS_ACCELCAL_ENABLED
414
415