APM:Libraries
AP_AccelCal.cpp
Go to the documentation of this file.
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 #include <stdarg.h>
16 #include <GCS_MAVLink/GCS.h>
18 #include <AP_HAL/AP_HAL.h>
19 
20 #define AP_ACCELCAL_POSITION_REQUEST_INTERVAL_MS 1000
21 
22 const extern AP_HAL::HAL& hal;
24 
25 uint8_t AP_AccelCal::_num_clients = 0;
27 
29 {
30  if (!get_calibrator(0)) {
31  // no calibrators
32  return;
33  }
34 
35  if (_started) {
36  update_status();
37 
38  AccelCalibrator *cal;
39  uint8_t num_active_calibrators = 0;
40  for(uint8_t i=0; (cal = get_calibrator(i)); i++) {
41  num_active_calibrators++;
42  }
43  if (num_active_calibrators != _num_active_calibrators) {
44  fail();
45  return;
46  }
49  }
50  switch(_status) {
52  fail();
53  return;
55  // if we're waiting for orientation, first ensure that all calibrators are on the same step
56  uint8_t step;
57  if ((cal = get_calibrator(0)) == nullptr) {
58  fail();
59  return;
60  }
61  step = cal->get_num_samples_collected()+1;
62 
63  for(uint8_t i=1 ; (cal = get_calibrator(i)) ; i++) {
64  if (step != cal->get_num_samples_collected()+1) {
65  fail();
66  return;
67  }
68  }
69  // if we're on a new step, print a message describing the step
70  if (step != _step) {
71  _step = step;
72 
73  if(_use_gcs_snoop) {
74  const char *msg;
75  switch (step) {
76  case ACCELCAL_VEHICLE_POS_LEVEL:
77  msg = "level";
78  break;
79  case ACCELCAL_VEHICLE_POS_LEFT:
80  msg = "on its LEFT side";
81  break;
82  case ACCELCAL_VEHICLE_POS_RIGHT:
83  msg = "on its RIGHT side";
84  break;
85  case ACCELCAL_VEHICLE_POS_NOSEDOWN:
86  msg = "nose DOWN";
87  break;
88  case ACCELCAL_VEHICLE_POS_NOSEUP:
89  msg = "nose UP";
90  break;
91  case ACCELCAL_VEHICLE_POS_BACK:
92  msg = "on its BACK";
93  break;
94  default:
95  fail();
96  return;
97  }
98  _printf("Place vehicle %s and press any key.", msg);
100  }
101  }
102 
103  uint32_t now = AP_HAL::millis();
107  }
108  break;
109  }
111  // check for timeout
112 
113  for(uint8_t i=0; (cal = get_calibrator(i)); i++) {
114  cal->check_for_timeout();
115  }
116 
117  update_status();
118 
119  if (_status == ACCEL_CAL_FAILED) {
120  fail();
121  }
122  return;
123  case ACCEL_CAL_SUCCESS:
124  // save
125  if (_saving) {
126  bool done = true;
127  for(uint8_t i=0; i<_num_clients; i++) {
128  if (client_active(i) && _clients[i]->_acal_get_saving()) {
129  done = false;
130  break;
131  }
132  }
133  if (done) {
134  success();
135  }
136  return;
137  } else {
138  for(uint8_t i=0; i<_num_clients; i++) {
139  if(client_active(i) && _clients[i]->_acal_get_fail()) {
140  fail();
141  return;
142  }
143  }
144  for(uint8_t i=0; i<_num_clients; i++) {
145  if(client_active(i)) {
147  }
148  }
149  _saving = true;
150  }
151  return;
152  default:
153  case ACCEL_CAL_FAILED:
154  fail();
155  return;
156  }
157  } else if (_last_result != ACCEL_CAL_NOT_STARTED) {
158  // only continuously report if we have ever completed a calibration
159  uint32_t now = AP_HAL::millis();
162  switch (_last_result) {
163  case ACCEL_CAL_SUCCESS:
164  _gcs->send_accelcal_vehicle_position(ACCELCAL_VEHICLE_POS_SUCCESS);
165  break;
166  case ACCEL_CAL_FAILED:
167  _gcs->send_accelcal_vehicle_position(ACCELCAL_VEHICLE_POS_FAILED);
168  break;
169  default:
170  // should never hit this state
171  break;
172  }
173  }
174  }
175 }
176 
178 {
179  if (gcs == nullptr || _started) {
180  return;
181  }
182  _start_collect_sample = false;
184 
185  AccelCalibrator *cal;
186  for(uint8_t i=0; (cal = get_calibrator(i)); i++) {
187  cal->clear();
190  }
191 
192  _started = true;
193  _saving = false;
194  _gcs = gcs;
195  _use_gcs_snoop = true;
197  _step = 0;
198 
200 
201  update_status();
202 }
203 
205 {
206  _printf("Calibration successful");
207 
208  for(uint8_t i=0 ; i < _num_clients ; i++) {
210  }
211 
213 
214  clear();
215 }
216 
218 {
219  _printf("Calibration cancelled");
220 
221  for(uint8_t i=0 ; i < _num_clients ; i++) {
223  }
224 
226 
227  clear();
228 }
229 
231 {
232  _printf("Calibration FAILED");
233 
234  for(uint8_t i=0 ; i < _num_clients ; i++) {
236  }
237 
239 
240  clear();
241 }
242 
244 {
245  if (!_started) {
246  return;
247  }
248 
249  AccelCalibrator *cal;
250  for(uint8_t i=0 ; (cal = get_calibrator(i)) ; i++) {
251  cal->clear();
252  }
253 
254  _step = 0;
255  _started = false;
256  _saving = false;
257 
258  update_status();
259 }
260 
262 {
264  return;
265  }
266 
267  for(uint8_t i=0; i<_num_clients; i++) {
268  if (client_active(i) && !_clients[i]->_acal_get_ready_to_sample()) {
269  _printf("Not ready to sample");
270  return;
271  }
272  }
273 
274  AccelCalibrator *cal;
275  for(uint8_t i=0 ; (cal = get_calibrator(i)) ; i++) {
276  cal->collect_sample();
277  }
278  _start_collect_sample = false;
279  update_status();
280 }
281 
283  if (client == nullptr || _num_clients >= AP_ACCELCAL_MAX_NUM_CLIENTS) {
284  return;
285  }
286 
287 
288  for(uint8_t i=0; i<_num_clients; i++) {
289  if(_clients[i] == client) {
290  return;
291  }
292  }
293  _clients[_num_clients] = client;
294  _num_clients++;
295 }
296 
298  AccelCalibrator* ret;
299  for(uint8_t i=0; i<_num_clients; i++) {
300  for(uint8_t j=0 ; (ret = _clients[i]->_acal_get_calibrator(j)) ; j++) {
301  if (index == 0) {
302  return ret;
303  }
304  index--;
305  }
306  }
307  return nullptr;
308 }
309 
311  AccelCalibrator *cal;
312 
313  if (!get_calibrator(0)) {
314  // no calibrators
316  return;
317  }
318 
319  for(uint8_t i=0 ; (cal = get_calibrator(i)) ; i++) {
320  if (cal->get_status() == ACCEL_CAL_FAILED) {
321  _status = ACCEL_CAL_FAILED; //fail if even one of the calibration has
322  return;
323  }
324  }
325 
326  for(uint8_t i=0 ; (cal = get_calibrator(i)) ; i++) {
327  if (cal->get_status() == ACCEL_CAL_COLLECTING_SAMPLE) {
328  _status = ACCEL_CAL_COLLECTING_SAMPLE; // move to Collecting sample state if all the callibrators have
329  return;
330  }
331  }
332 
333  for(uint8_t i=0 ; (cal = get_calibrator(i)) ; i++) {
335  _status = ACCEL_CAL_WAITING_FOR_ORIENTATION; // move to waiting for user ack for orientation confirmation
336  return;
337  }
338  }
339 
340  for(uint8_t i=0 ; (cal = get_calibrator(i)) ; i++) {
341  if (cal->get_status() == ACCEL_CAL_NOT_STARTED) {
342  _status = ACCEL_CAL_NOT_STARTED; // we haven't started if all the calibrators haven't
343  return;
344  }
345  }
346 
347  _status = ACCEL_CAL_SUCCESS; // we have succeeded calibration if all the calibrators have
348  return;
349 }
350 
351 bool AP_AccelCal::client_active(uint8_t client_num)
352 {
353  return (bool)_clients[client_num]->_acal_get_calibrator(0);
354 }
355 
356 void AP_AccelCal::handleMessage(const mavlink_message_t* msg)
357 {
359  return;
360  }
361  _waiting_for_mavlink_ack = false;
362  if (msg->msgid == MAVLINK_MSG_ID_COMMAND_ACK) {
363  _start_collect_sample = true;
364  }
365 }
366 
368 {
369  _use_gcs_snoop = false;
370 
371  if (_status == ACCEL_CAL_WAITING_FOR_ORIENTATION && is_equal((float) _step, position)) {
372  _start_collect_sample = true;
373  return true;
374  }
375 
376  return false;
377 }
378 
379 void AP_AccelCal::_printf(const char* fmt, ...)
380 {
381  if (!_gcs) {
382  return;
383  }
384  char msg[50];
385  va_list ap;
386  va_start(ap, fmt);
387  hal.util->vsnprintf(msg, sizeof(msg), fmt, ap);
388  va_end(ap);
389  if (msg[strlen(msg)-1] == '\n') {
390  // STATUSTEXT messages should not add linefeed
391  msg[strlen(msg)-1] = 0;
392  }
393  AP_HAL::UARTDriver *uart = _gcs->get_uart();
394  /*
395  * to ensure these messages get to the user we need to wait for the
396  * port send buffer to have enough room
397  */
398  while (uart->txspace() < MAVLINK_NUM_NON_PAYLOAD_BYTES+MAVLINK_MSG_ID_STATUSTEXT_LEN) {
399  hal.scheduler->delay(1);
400  }
401 
402 #if !APM_BUILD_TYPE(APM_BUILD_Replay)
403  _gcs->send_text(MAV_SEVERITY_CRITICAL, msg);
404 #endif
405 }
void _printf(const char *,...)
Interface definition for the various Ground Control System.
void start(enum accel_cal_fit_type_t fit_type=ACCEL_CAL_AXIS_ALIGNED_ELLIPSOID, uint8_t num_samples=6, float sample_time=0.5f)
AP_HAL::Util * util
Definition: HAL.h:115
virtual uint32_t txspace()=0
GCS & gcs()
accel_cal_status_t _status
Definition: AP_AccelCal.h:44
static uint8_t _num_clients
Definition: AP_AccelCal.h:47
GCS_MAVLINK * _gcs
Definition: AP_AccelCal.h:39
static void register_client(AP_AccelCal_Client *client)
uint8_t get_num_samples_collected() const
virtual void delay(uint16_t ms)=0
void collect_sample()
const AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14
int vsnprintf(char *str, size_t size, const char *format, va_list ap)
Definition: Util.cpp:53
bool _started
Definition: AP_AccelCal.h:71
#define AP_ACCELCAL_POSITION_REQUEST_INTERVAL_MS
Definition: AP_AccelCal.cpp:20
void update_status()
#define f(i)
const char * fmt
Definition: Printf.cpp:14
bool _saving
Definition: AP_AccelCal.h:72
virtual void _acal_event_success()
Definition: AP_AccelCal.h:91
uint32_t millis()
Definition: system.cpp:157
void handleMessage(const mavlink_message_t *msg)
#define AP_ACCELCAL_MAX_NUM_CLIENTS
Definition: AP_AccelCal.h:6
uint8_t _step
Definition: AP_AccelCal.h:43
bool gcs_vehicle_position(float position)
virtual AccelCalibrator * _acal_get_calibrator(uint8_t instance)=0
void update()
Definition: AP_AccelCal.cpp:28
static bool _start_collect_sample
Definition: AP_AccelCal.cpp:23
virtual void _acal_save_calibrations()=0
enum accel_cal_status_t get_status() const
bool _waiting_for_mavlink_ack
Definition: AP_AccelCal.h:41
std::enable_if< std::is_integral< typename std::common_type< Arithmetic1, Arithmetic2 >::type >::value,bool >::type is_equal(const Arithmetic1 v_1, const Arithmetic2 v_2)
Definition: AP_Math.cpp:12
AccelCalibrator * get_calibrator(uint8_t i)
virtual void _acal_event_failure()
Definition: AP_AccelCal.h:93
uint8_t _num_active_calibrators
Definition: AP_AccelCal.h:74
static AP_AccelCal_Client * _clients[AP_ACCELCAL_MAX_NUM_CLIENTS]
Definition: AP_AccelCal.h:48
virtual void _acal_event_cancellation()
Definition: AP_AccelCal.h:92
bool _use_gcs_snoop
Definition: AP_AccelCal.h:40
bool client_active(uint8_t client_num)
void success()
void start(GCS_MAVLINK *gcs)
uint32_t _last_position_request_ms
Definition: AP_AccelCal.h:42
AP_HAL::Scheduler * scheduler
Definition: HAL.h:114
accel_cal_status_t _last_result
Definition: AP_AccelCal.h:45