AP_RangeFinder_MAVLink.h 871 B

123456789101112131415161718192021222324252627282930313233343536373839
  1. #pragma once
  2. #include "RangeFinder.h"
  3. #include "RangeFinder_Backend.h"
  4. // Data timeout
  5. #define AP_RANGEFINDER_MAVLINK_TIMEOUT_MS 500
  6. class AP_RangeFinder_MAVLink : public AP_RangeFinder_Backend
  7. {
  8. public:
  9. // constructor
  10. AP_RangeFinder_MAVLink(RangeFinder::RangeFinder_State &_state, AP_RangeFinder_Params &_params);
  11. // static detection function
  12. static bool detect();
  13. // update state
  14. void update(void) override;
  15. // Get update from mavlink
  16. void handle_msg(const mavlink_message_t &msg) override;
  17. protected:
  18. MAV_DISTANCE_SENSOR _get_mav_distance_sensor_type() const override {
  19. return sensor_type;
  20. }
  21. private:
  22. uint16_t distance_cm;
  23. // start a reading
  24. static bool start_reading(void);
  25. static bool get_reading(uint16_t &reading_cm);
  26. MAV_DISTANCE_SENSOR sensor_type = MAV_DISTANCE_SENSOR_UNKNOWN;
  27. };