20 return MAV_DISTANCE_SENSOR_LASER;
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)
uint32_t getMeasurementTimingBudget(void)
bool get_reading(uint16_t &reading_cm)
bool get_SPAD_info(uint8_t *count, bool *type_is_aperture)
uint8_t getVcselPulsePeriod(vcselPeriodType type)
void start_continuous(void)
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)
uint32_t measurement_timing_budget_us
void write_register16(uint8_t reg, uint16_t value)
uint16_t pre_range_vcsel_period_pclks
uint8_t read_register(uint8_t reg)