APM:Libraries
AP_Compass_Calibration.cpp
Go to the documentation of this file.
1 #include <AP_HAL/AP_HAL.h>
2 #include <AP_Notify/AP_Notify.h>
3 #include <GCS_MAVLink/GCS.h>
4 
5 #include "AP_Compass.h"
6 
7 extern AP_HAL::HAL& hal;
8 
9 void
11 {
12  bool running = false;
13 
14  for (uint8_t i=0; i<COMPASS_MAX_INSTANCES; i++) {
15  bool failure;
16  _calibrator[i].update(failure);
17  if (failure) {
19  }
20 
21  if (_calibrator[i].check_for_timeout()) {
24  }
25 
26  if (_calibrator[i].running()) {
27  running = true;
28  } else if (_cal_autosave && !_cal_saved[i] && _calibrator[i].get_status() == COMPASS_CAL_SUCCESS) {
30  }
31  }
32 
34 
35  if (is_calibrating()) {
36  _cal_has_run = true;
37  return;
38  } else if (_cal_has_run && _auto_reboot()) {
39  hal.scheduler->delay(1000);
40  hal.scheduler->reboot(false);
41  }
42 }
43 
44 bool
45 Compass::_start_calibration(uint8_t i, bool retry, float delay)
46 {
47  if (!healthy(i)) {
48  return false;
49  }
50  if (!use_for_yaw(i)) {
51  return false;
52  }
53  if (!is_calibrating()) {
55  }
56  if (i == get_primary() && _state[i].external != 0) {
58  } else {
59  // internal compasses or secondary compasses get twice the
60  // threshold. This is because internal compasses tend to be a
61  // lot noisier
63  }
64  _cal_saved[i] = false;
65  _calibrator[i].start(retry, delay, get_offsets_max());
66 
67  // disable compass learning both for calibration and after completion
68  _learn.set_and_save(0);
69 
70  return true;
71 }
72 
73 bool
74 Compass::_start_calibration_mask(uint8_t mask, bool retry, bool autosave, float delay, bool autoreboot)
75 {
76  _cal_autosave = autosave;
77  _compass_cal_autoreboot = autoreboot;
78 
79  for (uint8_t i=0; i<COMPASS_MAX_INSTANCES; i++) {
80  if ((1<<i) & mask) {
81  if (!_start_calibration(i,retry,delay)) {
83  return false;
84  }
85  }
86  }
87  return true;
88 }
89 
90 void
91 Compass::start_calibration_all(bool retry, bool autosave, float delay, bool autoreboot)
92 {
93  _cal_autosave = autosave;
94  _compass_cal_autoreboot = autoreboot;
95 
96  for (uint8_t i=0; i<COMPASS_MAX_INSTANCES; i++) {
97  // ignore any compasses that fail to start calibrating
98  // start all should only calibrate compasses that are being used
99  _start_calibration(i,retry,delay);
100  }
101 }
102 
103 void
105 {
107 
108  if (_calibrator[i].running() || _calibrator[i].get_status() == COMPASS_CAL_WAITING_TO_START) {
110  }
111  _cal_saved[i] = false;
112  _calibrator[i].clear();
113 }
114 
115 void
117 {
118  for(uint8_t i=0; i<COMPASS_MAX_INSTANCES; i++) {
119  if((1<<i) & mask) {
121  }
122  }
123 }
124 
125 void
127 {
129 }
130 
131 bool
133 {
134  CompassCalibrator& cal = _calibrator[i];
135  uint8_t cal_status = cal.get_status();
136 
137  if (_cal_saved[i] || cal_status == COMPASS_CAL_NOT_STARTED) {
138  return true;
139  } else if (cal_status == COMPASS_CAL_SUCCESS) {
141  _cal_saved[i] = true;
142 
143  Vector3f ofs, diag, offdiag;
144  cal.get_calibration(ofs, diag, offdiag);
145 
146  set_and_save_offsets(i, ofs);
147  set_and_save_diagonals(i,diag);
148  set_and_save_offdiagonals(i,offdiag);
149 
150  if (!is_calibrating()) {
152  }
153  return true;
154  } else {
155  return false;
156  }
157 }
158 
159 bool
161 {
162  bool success = true;
163  for (uint8_t i=0; i<COMPASS_MAX_INSTANCES; i++) {
164  if ((1<<i) & mask) {
165  if (!_accept_calibration(i)) {
166  success = false;
167  }
168  _calibrator[i].clear();
169  }
170  }
171 
172  return success;
173 }
174 
175 void
177 {
178  uint8_t cal_mask = _get_cal_mask();
179 
180  for (uint8_t compass_id=0; compass_id<COMPASS_MAX_INSTANCES; compass_id++) {
181  // ensure we don't try to send with no space available
182  if (!HAVE_PAYLOAD_SPACE(chan, MAG_CAL_PROGRESS)) {
183  return;
184  }
185 
186  auto& calibrator = _calibrator[compass_id];
187  uint8_t cal_status = calibrator.get_status();
188 
189  if (cal_status == COMPASS_CAL_WAITING_TO_START ||
190  cal_status == COMPASS_CAL_RUNNING_STEP_ONE ||
191  cal_status == COMPASS_CAL_RUNNING_STEP_TWO) {
192  uint8_t completion_pct = calibrator.get_completion_percent();
193  auto& completion_mask = calibrator.get_completion_mask();
194  Vector3f direction(0.0f,0.0f,0.0f);
195  uint8_t attempt = _calibrator[compass_id].get_attempt();
196 
197  mavlink_msg_mag_cal_progress_send(
198  chan,
199  compass_id, cal_mask,
200  cal_status, attempt, completion_pct, completion_mask,
201  direction.x, direction.y, direction.z
202  );
203  }
204  }
205 }
206 
207 void Compass::send_mag_cal_report(mavlink_channel_t chan)
208 {
209  uint8_t cal_mask = _get_cal_mask();
210 
211  for (uint8_t compass_id=0; compass_id<COMPASS_MAX_INSTANCES; compass_id++) {
212  // ensure we don't try to send with no space available
213  if (!HAVE_PAYLOAD_SPACE(chan, MAG_CAL_REPORT)) {
214  return;
215  }
216 
217  uint8_t cal_status = _calibrator[compass_id].get_status();
218  if ((cal_status == COMPASS_CAL_SUCCESS ||
219  cal_status == COMPASS_CAL_FAILED)) {
220  float fitness = _calibrator[compass_id].get_fitness();
221  Vector3f ofs, diag, offdiag;
222  _calibrator[compass_id].get_calibration(ofs, diag, offdiag);
223  uint8_t autosaved = _cal_saved[compass_id];
224 
225  mavlink_msg_mag_cal_report_send(
226  chan,
227  compass_id, cal_mask,
228  cal_status, autosaved,
229  fitness,
230  ofs.x, ofs.y, ofs.z,
231  diag.x, diag.y, diag.z,
232  offdiag.x, offdiag.y, offdiag.z
233  );
234  }
235  }
236 }
237 
238 bool
240 {
241  for (uint8_t i=0; i<COMPASS_MAX_INSTANCES; i++) {
242  switch(_calibrator[i].get_status()) {
244  case COMPASS_CAL_SUCCESS:
245  case COMPASS_CAL_FAILED:
246  break;
247  default:
248  return true;
249  }
250  }
251  return false;
252 }
253 
254 uint8_t
256 {
257  uint8_t cal_mask = 0;
258  for (uint8_t i=0; i<COMPASS_MAX_INSTANCES; i++) {
259  if (_calibrator[i].get_status() != COMPASS_CAL_NOT_STARTED) {
260  cal_mask |= 1 << i;
261  }
262  }
263  return cal_mask;
264 }
265 
266 
267 /*
268  handle an incoming MAG_CAL command
269  */
270 MAV_RESULT Compass::handle_mag_cal_command(const mavlink_command_long_t &packet)
271 {
272  MAV_RESULT result = MAV_RESULT_FAILED;
273 
274  switch (packet.command) {
275  case MAV_CMD_DO_START_MAG_CAL: {
276  result = MAV_RESULT_ACCEPTED;
277  if (hal.util->get_soft_armed()) {
278  hal.console->printf("Disarm for compass calibration\n");
279  result = MAV_RESULT_FAILED;
280  break;
281  }
282  if (packet.param1 < 0 || packet.param1 > 255) {
283  result = MAV_RESULT_FAILED;
284  break;
285  }
286 
287  uint8_t mag_mask = packet.param1;
288  bool retry = !is_zero(packet.param2);
289  bool autosave = !is_zero(packet.param3);
290  float delay = packet.param4;
291  bool autoreboot = !is_zero(packet.param5);
292 
293  if (mag_mask == 0) { // 0 means all
294  start_calibration_all(retry, autosave, delay, autoreboot);
295  } else {
296  if (!_start_calibration_mask(mag_mask, retry, autosave, delay, autoreboot)) {
297  result = MAV_RESULT_FAILED;
298  }
299  }
300 
301  break;
302  }
303 
304  case MAV_CMD_DO_ACCEPT_MAG_CAL: {
305  result = MAV_RESULT_ACCEPTED;
306  if(packet.param1 < 0 || packet.param1 > 255) {
307  result = MAV_RESULT_FAILED;
308  break;
309  }
310 
311  uint8_t mag_mask = packet.param1;
312 
313  if (mag_mask == 0) { // 0 means all
314  mag_mask = 0xFF;
315  }
316 
317  if(!_accept_calibration_mask(mag_mask)) {
318  result = MAV_RESULT_FAILED;
319  }
320  break;
321  }
322 
323  case MAV_CMD_DO_CANCEL_MAG_CAL: {
324  result = MAV_RESULT_ACCEPTED;
325  if(packet.param1 < 0 || packet.param1 > 255) {
326  result = MAV_RESULT_FAILED;
327  break;
328  }
329 
330  uint8_t mag_mask = packet.param1;
331 
332  if (mag_mask == 0) { // 0 means all
334  break;
335  }
336 
337  _cancel_calibration_mask(mag_mask);
338  break;
339  }
340  }
341 
342  return result;
343 }
bool _cal_has_run
Definition: AP_Compass.h:365
bool get_soft_armed() const
Definition: Util.h:15
void start(bool retry, float delay, uint16_t offset_max)
bool _start_calibration(uint8_t i, bool retry=false, float delay_sec=0.0f)
AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14
bool _cal_complete_requires_reboot
Definition: AP_Compass.h:364
void set_tolerance(float tolerance)
AP_Int8 _learn
Definition: AP_Compass.h:395
AP_HAL::UARTDriver * console
Definition: HAL.h:110
bool _compass_cal_autoreboot
Definition: AP_Compass.h:363
void set_and_save_offdiagonals(uint8_t i, const Vector3f &diagonals)
bool _cal_saved[COMPASS_MAX_INSTANCES]
Definition: AP_Compass.h:359
Interface definition for the various Ground Control System.
void start_calibration_all(bool retry=false, bool autosave=false, float delay_sec=0.0f, bool autoreboot=false)
bool _cal_autosave
Definition: AP_Compass.h:360
uint8_t get_attempt() const
void set_and_save_offsets(uint8_t i, const Vector3f &offsets)
AP_HAL::Util * util
Definition: HAL.h:115
void cancel_calibration_all()
uint8_t _get_cal_mask() const
const char * result
Definition: Printf.cpp:16
void delay(uint32_t ms)
Definition: system.cpp:91
uint8_t get_primary(void) const
Definition: AP_Compass.h:277
void update(bool &failure)
CompassCalibrator _calibrator[COMPASS_MAX_INSTANCES]
Definition: AP_Compass.h:460
MAV_RESULT handle_mag_cal_command(const mavlink_command_long_t &packet)
float get_fitness() const
virtual void delay(uint16_t ms)=0
bool _accept_calibration(uint8_t i)
void send_mag_cal_report(mavlink_channel_t chan)
#define HAVE_PAYLOAD_SPACE(chan, id)
Definition: GCS.h:28
void set_and_save_diagonals(uint8_t i, const Vector3f &diagonals)
virtual void printf(const char *,...) FMT_PRINTF(2
Definition: BetterStream.cpp:5
void get_calibration(Vector3f &offsets, Vector3f &diagonals, Vector3f &offdiagonals)
enum compass_cal_status_t get_status() const
bool is_zero(const T fVal1)
Definition: AP_Math.h:40
#define f(i)
T y
Definition: vector3.h:67
bool _accept_calibration_mask(uint8_t mask)
bool _auto_reboot()
Definition: AP_Compass.h:352
bool _start_calibration_mask(uint8_t mask, bool retry=false, bool autosave=false, float delay_sec=0.0f, bool autoreboot=false)
T z
Definition: vector3.h:67
uint16_t get_offsets_max(void) const
Definition: AP_Compass.h:327
bool healthy(void) const
Definition: AP_Compass.h:159
AP_Float _calibration_threshold
Definition: AP_Compass.h:468
#define COMPASS_MAX_INSTANCES
Definition: AP_Compass.h:46
virtual void reboot(bool hold_in_bootloader)=0
static struct notify_flags_and_values_type flags
Definition: AP_Notify.h:117
AP_HAL::AnalogSource * chan
Definition: AnalogIn.cpp:8
void _cancel_calibration(uint8_t i)
void _cancel_calibration_mask(uint8_t mask)
bool is_calibrating() const
void send_mag_cal_progress(mavlink_channel_t chan)
static struct notify_events_type events
Definition: AP_Notify.h:118
bool use_for_yaw(void) const
return true if the compass should be used for yaw calculations
struct Compass::mag_state _state[COMPASS_MAX_INSTANCES]
AP_HAL::Scheduler * scheduler
Definition: HAL.h:114
T x
Definition: vector3.h:67