AP_RangeFinder_uLanding.h 922 B

12345678910111213141516171819202122232425262728293031323334353637383940
  1. #pragma once
  2. #include "RangeFinder.h"
  3. #include "RangeFinder_Backend.h"
  4. class AP_RangeFinder_uLanding : public AP_RangeFinder_Backend
  5. {
  6. public:
  7. // constructor
  8. AP_RangeFinder_uLanding(RangeFinder::RangeFinder_State &_state,
  9. AP_RangeFinder_Params &_params,
  10. uint8_t serial_instance);
  11. // static detection function
  12. static bool detect(uint8_t serial_instance);
  13. // update state
  14. void update(void) override;
  15. protected:
  16. MAV_DISTANCE_SENSOR _get_mav_distance_sensor_type() const override {
  17. return MAV_DISTANCE_SENSOR_RADAR;
  18. }
  19. private:
  20. // detect uLanding Firmware Version
  21. bool detect_version(void);
  22. // get a reading
  23. bool get_reading(uint16_t &reading_cm);
  24. AP_HAL::UARTDriver *uart;
  25. uint8_t _linebuf[6];
  26. uint8_t _linebuf_len;
  27. bool _version_known;
  28. uint8_t _header;
  29. uint8_t _version;
  30. };