AP_RangeFinder_PulsedLightLRF.h 2.0 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859
  1. #pragma once
  2. #include "RangeFinder.h"
  3. #include "RangeFinder_Backend.h"
  4. #include <AP_HAL/I2CDevice.h>
  5. /* Connection diagram
  6. *
  7. * ------------------------------------------------------------------------------------
  8. * | J2-1(LED) J2-2(5V) J2-3(Enable) J2-4(Ref Clk) J2-5(GND) J2-6(GND) |
  9. * | |
  10. * | |
  11. * | J1-3(I2C Clk) J1-2(I2C Data) J1-1(GND) |
  12. * ------------------------------------------------------------------------------------
  13. */
  14. class AP_RangeFinder_PulsedLightLRF : public AP_RangeFinder_Backend
  15. {
  16. public:
  17. // static detection function
  18. static AP_RangeFinder_Backend *detect(uint8_t bus,
  19. RangeFinder::RangeFinder_State &_state,
  20. AP_RangeFinder_Params &_params,
  21. RangeFinder::RangeFinder_Type rftype);
  22. // update state
  23. void update(void) override {}
  24. protected:
  25. virtual MAV_DISTANCE_SENSOR _get_mav_distance_sensor_type() const override {
  26. return MAV_DISTANCE_SENSOR_LASER;
  27. }
  28. private:
  29. // constructor
  30. AP_RangeFinder_PulsedLightLRF(uint8_t bus,
  31. RangeFinder::RangeFinder_State &_state,
  32. AP_RangeFinder_Params &_params,
  33. RangeFinder::RangeFinder_Type rftype);
  34. // start a reading
  35. bool init(void);
  36. void timer(void);
  37. bool lidar_transfer(const uint8_t *send, unsigned send_len, uint8_t *recv, unsigned recv_len);
  38. AP_HAL::OwnPtr<AP_HAL::I2CDevice> _dev;
  39. uint8_t sw_version;
  40. uint8_t hw_version;
  41. uint8_t check_reg_counter;
  42. bool v2_hardware;
  43. bool v3hp_hardware;
  44. uint16_t last_distance_cm;
  45. RangeFinder::RangeFinder_Type rftype;
  46. enum { PHASE_MEASURE, PHASE_COLLECT } phase;
  47. };