APM:Libraries
AP_AccelCal.h
Go to the documentation of this file.
1 #pragma once
2 
4 #include "AccelCalibrator.h"
5 
6 #define AP_ACCELCAL_MAX_NUM_CLIENTS 4
7 class GCS_MAVLINK;
9 
10 class AP_AccelCal {
11 public:
13  _use_gcs_snoop(true),
14  _started(false),
15  _saving(false)
16  { update_status(); }
17 
18  // start all the registered calibrations
19  void start(GCS_MAVLINK *gcs);
20 
21  // called on calibration cancellation
22  void cancel();
23 
24  // Run an iteration of all registered calibrations
25  void update();
26 
27  // get the status of the calibrator server as a whole
29 
30  // Set vehicle position sent by the GCS
31  bool gcs_vehicle_position(float position);
32 
33  // interface to the clients for registration
34  static void register_client(AP_AccelCal_Client* client);
35 
36  void handleMessage(const mavlink_message_t * msg);
37 
38 private:
43  uint8_t _step;
46 
47  static uint8_t _num_clients;
49 
50  // called on calibration success
51  void success();
52 
53  // called on calibration failure
54  void fail();
55 
56  // reset all the calibrators to there pre calibration stage so as to make them ready for next calibration request
57  void clear();
58 
59  // proceed through the collection step for each of the registered calibrators
60  void collect_sample();
61 
62  // update the state of the Accel calibrator server
63  void update_status();
64 
65  // checks if no new sample has been received for considerable amount of time
66  bool check_for_timeout();
67 
68  // check if client's calibrator is active
69  bool client_active(uint8_t client_num);
70 
71  bool _started;
72  bool _saving;
73 
75 
76  AccelCalibrator* get_calibrator(uint8_t i);
77  void _printf(const char*, ...);
78 };
79 
81 friend class AP_AccelCal;
82 private:
83  // getters
84  virtual bool _acal_get_saving() { return false; }
85  virtual bool _acal_get_ready_to_sample() { return true; }
86  virtual bool _acal_get_fail() { return false; }
87  virtual AccelCalibrator* _acal_get_calibrator(uint8_t instance) = 0;
88 
89  // events
90  virtual void _acal_save_calibrations() = 0;
91  virtual void _acal_event_success() {};
92  virtual void _acal_event_cancellation() {};
93  virtual void _acal_event_failure() {};
94 };
void _printf(const char *,...)
virtual bool _acal_get_fail()
Definition: AP_AccelCal.h:86
accel_cal_status_t
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)
void collect_sample()
virtual bool _acal_get_saving()
Definition: AP_AccelCal.h:84
bool check_for_timeout()
accel_cal_status_t get_status()
Definition: AP_AccelCal.h:28
bool _started
Definition: AP_AccelCal.h:71
void update_status()
bool _saving
Definition: AP_AccelCal.h:72
virtual void _acal_event_success()
Definition: AP_AccelCal.h:91
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)
void update()
Definition: AP_AccelCal.cpp:28
bool _waiting_for_mavlink_ack
Definition: AP_AccelCal.h:41
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
accel_cal_status_t _last_result
Definition: AP_AccelCal.h:45
virtual bool _acal_get_ready_to_sample()
Definition: AP_AccelCal.h:85