AP_Proximity_MAV.h 1.2 KB

123456789101112131415161718192021222324252627282930313233343536373839
  1. #pragma once
  2. #include "AP_Proximity.h"
  3. #include "AP_Proximity_Backend.h"
  4. class AP_Proximity_MAV : public AP_Proximity_Backend
  5. {
  6. public:
  7. // constructor
  8. AP_Proximity_MAV(AP_Proximity &_frontend, AP_Proximity::Proximity_State &_state);
  9. // update state
  10. void update(void) override;
  11. // get maximum and minimum distances (in meters) of sensor
  12. float distance_max() const override { return _distance_max; }
  13. float distance_min() const override { return _distance_min; };
  14. // get distance upwards in meters. returns true on success
  15. bool get_upward_distance(float &distance) const override;
  16. // handle mavlink DISTANCE_SENSOR messages
  17. void handle_msg(const mavlink_message_t &msg) override;
  18. private:
  19. // initialise sensor (returns true if sensor is succesfully initialised)
  20. bool initialise();
  21. // horizontal distance support
  22. uint32_t _last_update_ms; // system time of last DISTANCE_SENSOR message received
  23. float _distance_max; // max range of sensor in meters
  24. float _distance_min; // min range of sensor in meters
  25. // upward distance support
  26. uint32_t _last_upward_update_ms; // system time of last update distance
  27. float _distance_upward; // upward distance in meters
  28. };