AP_AccelCal.h 2.5 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293
  1. #pragma once
  2. #include <GCS_MAVLink/GCS_MAVLink.h>
  3. #include "AccelCalibrator.h"
  4. #define AP_ACCELCAL_MAX_NUM_CLIENTS 4
  5. class GCS_MAVLINK;
  6. class AP_AccelCal_Client;
  7. class AP_AccelCal {
  8. public:
  9. AP_AccelCal():
  10. _use_gcs_snoop(true),
  11. _started(false),
  12. _saving(false)
  13. { update_status(); }
  14. // start all the registered calibrations
  15. void start(GCS_MAVLINK *gcs);
  16. // called on calibration cancellation
  17. void cancel();
  18. // Run an iteration of all registered calibrations
  19. void update();
  20. // get the status of the calibrator server as a whole
  21. accel_cal_status_t get_status() { return _status; }
  22. // Set vehicle position sent by the GCS
  23. bool gcs_vehicle_position(float position);
  24. // interface to the clients for registration
  25. static void register_client(AP_AccelCal_Client* client);
  26. void handleMessage(const mavlink_message_t &msg);
  27. private:
  28. GCS_MAVLINK *_gcs;
  29. bool _use_gcs_snoop;
  30. bool _waiting_for_mavlink_ack = false;
  31. uint32_t _last_position_request_ms;
  32. uint8_t _step;
  33. accel_cal_status_t _status;
  34. accel_cal_status_t _last_result;
  35. static uint8_t _num_clients;
  36. static AP_AccelCal_Client* _clients[AP_ACCELCAL_MAX_NUM_CLIENTS];
  37. // called on calibration success
  38. void success();
  39. // called on calibration failure
  40. void fail();
  41. // reset all the calibrators to there pre calibration stage so as to make them ready for next calibration request
  42. void clear();
  43. // proceed through the collection step for each of the registered calibrators
  44. void collect_sample();
  45. // update the state of the Accel calibrator server
  46. void update_status();
  47. // checks if no new sample has been received for considerable amount of time
  48. bool check_for_timeout();
  49. // check if client's calibrator is active
  50. bool client_active(uint8_t client_num);
  51. bool _started;
  52. bool _saving;
  53. uint8_t _num_active_calibrators;
  54. AccelCalibrator* get_calibrator(uint8_t i);
  55. };
  56. class AP_AccelCal_Client {
  57. friend class AP_AccelCal;
  58. private:
  59. // getters
  60. virtual bool _acal_get_saving() { return false; }
  61. virtual bool _acal_get_ready_to_sample() { return true; }
  62. virtual bool _acal_get_fail() { return false; }
  63. virtual AccelCalibrator* _acal_get_calibrator(uint8_t instance) = 0;
  64. // events
  65. virtual void _acal_save_calibrations() = 0;
  66. virtual void _acal_event_success() {};
  67. virtual void _acal_event_cancellation() {};
  68. virtual void _acal_event_failure() {};
  69. };