APM:Libraries
AP_RangeFinder_PulsedLightLRF.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include "RangeFinder.h"
4 #include "RangeFinder_Backend.h"
5 #include <AP_HAL/I2CDevice.h>
6 
7 /* Connection diagram
8  *
9  * ------------------------------------------------------------------------------------
10  * | J2-1(LED) J2-2(5V) J2-3(Enable) J2-4(Ref Clk) J2-5(GND) J2-6(GND) |
11  * | |
12  * | |
13  * | J1-3(I2C Clk) J1-2(I2C Data) J1-1(GND) |
14  * ------------------------------------------------------------------------------------
15  */
16 
18 {
19 
20 public:
21  // static detection function
22  static AP_RangeFinder_Backend *detect(uint8_t bus,
25 
26  // update state
27  void update(void) override {}
28 
29 protected:
30 
31  virtual MAV_DISTANCE_SENSOR _get_mav_distance_sensor_type() const override {
32  return MAV_DISTANCE_SENSOR_LASER;
33  }
34 
35 private:
36  // constructor
40 
41  // start a reading
42  bool init(void);
43  void timer(void);
44  bool lidar_transfer(const uint8_t *send, unsigned send_len, uint8_t *recv, unsigned recv_len);
45 
47 
48  uint8_t sw_version;
49  uint8_t hw_version;
52  uint16_t last_distance_cm;
54 
56 };
virtual MAV_DISTANCE_SENSOR _get_mav_distance_sensor_type() const override
static AP_RangeFinder_Backend * detect(uint8_t bus, RangeFinder::RangeFinder_State &_state, RangeFinder::RangeFinder_Type rftype)
bool lidar_transfer(const uint8_t *send, unsigned send_len, uint8_t *recv, unsigned recv_len)
RangeFinder::RangeFinder_Type rftype
AP_HAL::OwnPtr< AP_HAL::I2CDevice > _dev
AP_RangeFinder_PulsedLightLRF(uint8_t bus, RangeFinder::RangeFinder_State &_state, RangeFinder::RangeFinder_Type rftype)
enum AP_RangeFinder_PulsedLightLRF::@176 phase