AP_RangeFinder_MaxsonarI2CXL.h 1.2 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243
  1. #pragma once
  2. #include "RangeFinder.h"
  3. #include "RangeFinder_Backend.h"
  4. #include <AP_HAL/I2CDevice.h>
  5. #define AP_RANGE_FINDER_MAXSONARI2CXL_DEFAULT_ADDR 0x70
  6. #define AP_RANGE_FINDER_MAXSONARI2CXL_COMMAND_TAKE_RANGE_READING 0x51
  7. class AP_RangeFinder_MaxsonarI2CXL : public AP_RangeFinder_Backend
  8. {
  9. public:
  10. // static detection function
  11. static AP_RangeFinder_Backend *detect(RangeFinder::RangeFinder_State &_state,
  12. AP_RangeFinder_Params &_params,
  13. AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev);
  14. // update state
  15. void update(void) override;
  16. protected:
  17. MAV_DISTANCE_SENSOR _get_mav_distance_sensor_type() const override {
  18. return MAV_DISTANCE_SENSOR_ULTRASOUND;
  19. }
  20. private:
  21. // constructor
  22. AP_RangeFinder_MaxsonarI2CXL(RangeFinder::RangeFinder_State &_state,
  23. AP_RangeFinder_Params &_params,
  24. AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev);
  25. bool _init(void);
  26. void _timer(void);
  27. uint16_t distance;
  28. bool new_distance;
  29. // start a reading
  30. bool start_reading(void);
  31. bool get_reading(uint16_t &reading_cm);
  32. AP_HAL::OwnPtr<AP_HAL::I2CDevice> _dev;
  33. };