AP_RangeFinder_VL53L0X.h 2.5 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576777879808182
  1. #pragma once
  2. #include "RangeFinder.h"
  3. #include "RangeFinder_Backend.h"
  4. #include <AP_HAL/I2CDevice.h>
  5. class AP_RangeFinder_VL53L0X : public AP_RangeFinder_Backend
  6. {
  7. public:
  8. // static detection function
  9. static AP_RangeFinder_Backend *detect(RangeFinder::RangeFinder_State &_state, AP_RangeFinder_Params &_params, AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev);
  10. // update state
  11. void update(void) override;
  12. protected:
  13. virtual MAV_DISTANCE_SENSOR _get_mav_distance_sensor_type() const override {
  14. return MAV_DISTANCE_SENSOR_LASER;
  15. }
  16. private:
  17. // constructor
  18. AP_RangeFinder_VL53L0X(RangeFinder::RangeFinder_State &_state, AP_RangeFinder_Params &_params, AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev);
  19. bool init();
  20. void timer();
  21. // check sensor ID
  22. bool check_id(void);
  23. // get a reading
  24. bool get_reading(uint16_t &reading_cm);
  25. AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev;
  26. uint8_t read_register(uint8_t reg);
  27. uint16_t read_register16(uint8_t reg);
  28. void write_register(uint8_t reg, uint8_t value);
  29. void write_register16(uint8_t reg, uint16_t value);
  30. struct SequenceStepEnables {
  31. bool tcc:1, msrc:1, dss:1, pre_range:1, final_range:1;
  32. };
  33. struct SequenceStepTimeouts {
  34. uint16_t pre_range_vcsel_period_pclks, final_range_vcsel_period_pclks;
  35. uint16_t msrc_dss_tcc_mclks, pre_range_mclks, final_range_mclks;
  36. uint32_t msrc_dss_tcc_us, pre_range_us, final_range_us;
  37. };
  38. struct RegData {
  39. uint8_t reg;
  40. uint8_t value;
  41. };
  42. static const RegData tuning_data[];
  43. enum vcselPeriodType { VcselPeriodPreRange, VcselPeriodFinalRange };
  44. bool get_SPAD_info(uint8_t * count, bool *type_is_aperture);
  45. void getSequenceStepEnables(SequenceStepEnables * enables);
  46. uint32_t getMeasurementTimingBudget(void);
  47. void getSequenceStepTimeouts(SequenceStepEnables const * enables, SequenceStepTimeouts * timeouts);
  48. uint8_t getVcselPulsePeriod(vcselPeriodType type);
  49. uint32_t timeoutMclksToMicroseconds(uint16_t timeout_period_mclks, uint8_t vcsel_period_pclks);
  50. uint16_t decodeTimeout(uint16_t reg_val);
  51. bool setMeasurementTimingBudget(uint32_t budget_us);
  52. uint32_t timeoutMicrosecondsToMclks(uint32_t timeout_period_us, uint8_t vcsel_period_pclks);
  53. uint16_t encodeTimeout(uint16_t timeout_mclks);
  54. bool performSingleRefCalibration(uint8_t vhv_init_byte);
  55. void start_continuous(void);
  56. uint8_t stop_variable;
  57. uint32_t measurement_timing_budget_us;
  58. uint32_t start_ms;
  59. uint32_t sum_mm;
  60. uint32_t counter;
  61. };