APM:Libraries
AP_RangeFinder_VL53L0X.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 
8 {
9 
10 public:
11  // static detection function
13 
14  // update state
15  void update(void);
16 
17 protected:
18 
19  virtual MAV_DISTANCE_SENSOR _get_mav_distance_sensor_type() const override {
20  return MAV_DISTANCE_SENSOR_LASER;
21  }
22 
23 private:
24  // constructor
26 
27  void init();
28  void timer();
29 
30  // check sensor ID
31  bool check_id(void);
32 
33  // get a reading
34  bool get_reading(uint16_t &reading_cm);
36 
37  uint8_t read_register(uint8_t reg);
38  uint16_t read_register16(uint8_t reg);
39 
40  void write_register(uint8_t reg, uint8_t value);
41  void write_register16(uint8_t reg, uint16_t value);
42 
44  bool tcc:1, msrc:1, dss:1, pre_range:1, final_range:1;
45  };
46 
48  uint16_t pre_range_vcsel_period_pclks, final_range_vcsel_period_pclks;
49 
50  uint16_t msrc_dss_tcc_mclks, pre_range_mclks, final_range_mclks;
51  uint32_t msrc_dss_tcc_us, pre_range_us, final_range_us;
52  };
53 
54  struct RegData {
55  uint8_t reg;
56  uint8_t value;
57  };
58 
59  static const RegData tuning_data[];
60 
62 
63  bool get_SPAD_info(uint8_t * count, bool *type_is_aperture);
65  uint32_t getMeasurementTimingBudget(void);
66  void getSequenceStepTimeouts(SequenceStepEnables const * enables, SequenceStepTimeouts * timeouts);
68  uint32_t timeoutMclksToMicroseconds(uint16_t timeout_period_mclks, uint8_t vcsel_period_pclks);
69  uint16_t decodeTimeout(uint16_t reg_val);
70  bool setMeasurementTimingBudget(uint32_t budget_us);
71  uint32_t timeoutMicrosecondsToMclks(uint32_t timeout_period_us, uint8_t vcsel_period_pclks);
72  uint16_t encodeTimeout(uint16_t timeout_mclks);
73  bool performSingleRefCalibration(uint8_t vhv_init_byte);
74  void start_continuous(void);
75 
76  uint8_t stop_variable;
78  uint32_t start_ms;
79 
80  uint32_t sum_mm;
81  uint32_t counter;
82 };
RangeFinder::RangeFinder_Type type() const
void write_register(uint8_t reg, uint8_t value)
uint16_t read_register16(uint8_t reg)
AP_HAL::OwnPtr< AP_HAL::I2CDevice > dev
static AP_RangeFinder_Backend * detect(RangeFinder::RangeFinder_State &_state, AP_HAL::OwnPtr< AP_HAL::I2CDevice > dev)
bool get_reading(uint16_t &reading_cm)
bool get_SPAD_info(uint8_t *count, bool *type_is_aperture)
uint8_t getVcselPulsePeriod(vcselPeriodType type)
bool performSingleRefCalibration(uint8_t vhv_init_byte)
uint16_t decodeTimeout(uint16_t reg_val)
static const RegData tuning_data[]
virtual MAV_DISTANCE_SENSOR _get_mav_distance_sensor_type() const override
uint32_t timeoutMicrosecondsToMclks(uint32_t timeout_period_us, uint8_t vcsel_period_pclks)
AP_RangeFinder_VL53L0X(RangeFinder::RangeFinder_State &_state, AP_HAL::OwnPtr< AP_HAL::I2CDevice > dev)
uint16_t encodeTimeout(uint16_t timeout_mclks)
uint32_t timeoutMclksToMicroseconds(uint16_t timeout_period_mclks, uint8_t vcsel_period_pclks)
void getSequenceStepEnables(SequenceStepEnables *enables)
bool setMeasurementTimingBudget(uint32_t budget_us)
void getSequenceStepTimeouts(SequenceStepEnables const *enables, SequenceStepTimeouts *timeouts)
float value
void write_register16(uint8_t reg, uint16_t value)
uint8_t read_register(uint8_t reg)