AP_Proximity_RangeFinder.h 1.2 KB

1234567891011121314151617181920212223242526272829303132333435
  1. #pragma once
  2. #include "AP_Proximity.h"
  3. #include "AP_Proximity_Backend.h"
  4. #define PROXIMITY_RANGEFIDER_TIMEOUT_MS 200 // requests timeout after 0.2 seconds
  5. class AP_Proximity_RangeFinder : public AP_Proximity_Backend
  6. {
  7. public:
  8. // constructor
  9. AP_Proximity_RangeFinder(AP_Proximity &_frontend, AP_Proximity::Proximity_State &_state);
  10. // update state
  11. void update(void) override;
  12. // get maximum and minimum distances (in meters) of sensor
  13. float distance_max() const override { return _distance_max; }
  14. float distance_min() const override { return _distance_min; }
  15. // get distance upwards in meters. returns true on success
  16. bool get_upward_distance(float &distance) const override;
  17. private:
  18. // horizontal distance support
  19. uint32_t _last_update_ms; // system time of last RangeFinder reading
  20. float _distance_max; // max range of sensor in meters
  21. float _distance_min; // min range of sensor in meters
  22. // upward distance support
  23. uint32_t _last_upward_update_ms; // system time of last update distance
  24. float _distance_upward; // upward distance in meters, negative if the last reading was out of range
  25. };