PX4 Firmware
PX4 Autopilot Software http://px4.io
VL53LXX Class Reference
Inheritance diagram for VL53LXX:
Collaboration diagram for VL53LXX:

Public Member Functions

 VL53LXX (uint8_t rotation=distance_sensor_s::ROTATION_DOWNWARD_FACING, int bus=VL53LXX_BUS_DEFAULT, int address=VL53LXX_BASEADDR)
 
virtual ~VL53LXX ()
 
virtual int init () override
 
void print_info ()
 Diagnostics - print some basic information about the driver. More...
 
virtual ssize_t read (device::file_t *file_pointer, char *buffer, size_t buflen)
 
void start ()
 Initialise the automatic measurement state machine and start it. More...
 
void stop ()
 Stop the automatic measurement state machine. More...
 

Protected Member Functions

virtual int probe () override
 

Private Member Functions

int collect ()
 Collects the most recent sensor measurement data from the i2c bus. More...
 
int measure ()
 Sends an i2c measure command to the sensor. More...
 
void Run () override
 Perform a poll cycle; collect from the previous measurement and start a new one. More...
 
int readRegister (const uint8_t reg_address, uint8_t &value)
 
int readRegisterMulti (const uint8_t reg_address, uint8_t *value, const uint8_t length)
 
int writeRegister (const uint8_t reg_address, const uint8_t value)
 
int writeRegisterMulti (const uint8_t reg_address, const uint8_t *value, const uint8_t length)
 
int sensorInit ()
 
int sensorTuning ()
 
int singleRefCalibration (const uint8_t byte)
 
int spadCalculations ()
 

Private Attributes

bool _collect_phase {false}
 
bool _measurement_started {false}
 
bool _new_measurement {true}
 
int _class_instance {-1}
 
int _measure_interval {VL53LXX_SAMPLE_RATE}
 
int _orb_class_instance {-1}
 
uint8_t _rotation {0}
 
uint8_t _stop_variable {0}
 
orb_advert_t _distance_sensor_topic {nullptr}
 
perf_counter_t _comms_errors {perf_alloc(PC_COUNT, "vl53lxx_com_err")}
 
perf_counter_t _sample_perf {perf_alloc(PC_ELAPSED, "vl53lxx_read")}
 
ringbuffer::RingBuffer * _reports {nullptr}
 

Detailed Description

Definition at line 89 of file vl53lxx.cpp.

Constructor & Destructor Documentation

◆ VL53LXX()

VL53LXX::VL53LXX ( uint8_t  rotation = distance_sensor_s::ROTATION_DOWNWARD_FACING,
int  bus = VL53LXX_BUS_DEFAULT,
int  address = VL53LXX_BASEADDR 
)

Definition at line 168 of file vl53lxx.cpp.

Referenced by vl53lxx::start_bus().

Here is the caller graph for this function:

◆ ~VL53LXX()

VL53LXX::~VL53LXX ( )
virtual

Definition at line 177 of file vl53lxx.cpp.

References _class_instance, _comms_errors, _distance_sensor_topic, _reports, _sample_perf, orb_unadvertise(), perf_free(), RANGE_FINDER_BASE_DEVICE_PATH, and stop().

Here is the call graph for this function:

Member Function Documentation

◆ collect()

int VL53LXX::collect ( )
private

Collects the most recent sensor measurement data from the i2c bus.

Definition at line 202 of file vl53lxx.cpp.

References _class_instance, _collect_phase, _comms_errors, _distance_sensor_topic, _orb_class_instance, _reports, _rotation, _sample_perf, CLASS_DEVICE_PRIMARY, distance_sensor_s::current_distance, DEVICE_LOG, hrt_absolute_time(), distance_sensor_s::id, distance_sensor_s::max_distance, distance_sensor_s::min_distance, ORB_ID, ORB_PRIO_DEFAULT, orb_publish_auto(), distance_sensor_s::orientation, perf_begin(), perf_count(), perf_end(), distance_sensor_s::signal_quality, distance_sensor_s::timestamp, distance_sensor_s::type, distance_sensor_s::variance, VL53LXX_MAX_RANGING_DISTANCE, and VL53LXX_MIN_RANGING_DISTANCE.

Referenced by read(), and Run().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ init()

int VL53LXX::init ( )
overridevirtual

Definition at line 249 of file vl53lxx.cpp.

References _class_instance, _distance_sensor_topic, _orb_class_instance, _reports, ToneAlarmInterface::init(), OK, orb_advertise_multi(), ORB_ID, ORB_PRIO_DEFAULT, RANGE_FINDER_BASE_DEVICE_PATH, and VL53LXX_BASEADDR.

Referenced by vl53lxx::start_bus().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ measure()

int VL53LXX::measure ( )
private

Sends an i2c measure command to the sensor.

Definition at line 281 of file vl53lxx.cpp.

References _collect_phase, _comms_errors, _measurement_started, _new_measurement, _stop_variable, DEVICE_LOG, perf_count(), readRegister(), RESULT_INTERRUPT_STATUS_REG, RESULT_RANGE_STATUS_REG, SYSRANGE_START_REG, VL53LXX_US, and writeRegister().

Referenced by read(), and Run().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ print_info()

void VL53LXX::print_info ( )

Diagnostics - print some basic information about the driver.

Definition at line 349 of file vl53lxx.cpp.

References _comms_errors, _measure_interval, _reports, _sample_perf, and perf_print_counter().

Referenced by vl53lxx::status().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ probe()

int VL53LXX::probe ( )
overrideprotectedvirtual

Definition at line 358 of file vl53lxx.cpp.

References sensorInit().

Here is the call graph for this function:

◆ read()

ssize_t VL53LXX::read ( device::file_t file_pointer,
char *  buffer,
size_t  buflen 
)
virtual

Definition at line 369 of file vl53lxx.cpp.

References _measure_interval, _reports, collect(), and measure().

Referenced by vl53lxx::test().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ readRegister()

int VL53LXX::readRegister ( const uint8_t  reg_address,
uint8_t &  value 
)
private

Definition at line 426 of file vl53lxx.cpp.

References _comms_errors, and perf_count().

Referenced by measure(), sensorInit(), singleRefCalibration(), and spadCalculations().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ readRegisterMulti()

int VL53LXX::readRegisterMulti ( const uint8_t  reg_address,
uint8_t *  value,
const uint8_t  length 
)
private

Definition at line 449 of file vl53lxx.cpp.

References _comms_errors, and perf_count().

Referenced by spadCalculations().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ Run()

void VL53LXX::Run ( )
overrideprivate

Perform a poll cycle; collect from the previous measurement and start a new one.

Definition at line 471 of file vl53lxx.cpp.

References _collect_phase, _measure_interval, _new_measurement, collect(), and measure().

Here is the call graph for this function:

◆ sensorInit()

int VL53LXX::sensorInit ( )
private

Definition at line 576 of file vl53lxx.cpp.

References _stop_variable, FINAL_RANGE_CONFIG_MIN_COUNT_RATE_RTN_LIMIT_REG, MSRC_CONFIG_CONTROL_REG, readRegister(), spadCalculations(), SYSTEM_SEQUENCE_CONFIG_REG, VHV_CONFIG_PAD_SCL_SDA_EXTSUP_HW_REG, writeRegister(), and writeRegisterMulti().

Referenced by probe().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ sensorTuning()

int VL53LXX::sensorTuning ( )
private

Definition at line 626 of file vl53lxx.cpp.

References writeRegister().

Referenced by spadCalculations().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ singleRefCalibration()

int VL53LXX::singleRefCalibration ( const uint8_t  byte)
private

Definition at line 714 of file vl53lxx.cpp.

References readRegister(), RESULT_INTERRUPT_STATUS_REG, SYSRANGE_START_REG, SYSTEM_INTERRUPT_CLEAR_REG, and writeRegister().

Referenced by spadCalculations().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ spadCalculations()

int VL53LXX::spadCalculations ( )
private

Definition at line 487 of file vl53lxx.cpp.

References DYNAMIC_SPAD_NUM_REQUESTED_REF_SPAD_REG, DYNAMIC_SPAD_REF_EN_START_OFFSET_REG, GLOBAL_CONFIG_REF_EN_START_SELECT_REG, GLOBAL_CONFIG_SPAD_ENABLES_REF_0_REG, GPIO_HV_MUX_ACTIVE_HIGH_REG, OK, readRegister(), readRegisterMulti(), sensorTuning(), singleRefCalibration(), SYSTEM_INTERRUPT_CLEAR_REG, SYSTEM_INTERRUPT_CONFIG_GPIO_REG, SYSTEM_SEQUENCE_CONFIG_REG, writeRegister(), and writeRegisterMulti().

Referenced by sensorInit().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ start()

void VL53LXX::start ( )

Initialise the automatic measurement state machine and start it.

Definition at line 732 of file vl53lxx.cpp.

References _reports.

Referenced by vl53lxx::reset(), and vl53lxx::start_bus().

Here is the caller graph for this function:

◆ stop()

void VL53LXX::stop ( )

Stop the automatic measurement state machine.

Definition at line 742 of file vl53lxx.cpp.

Referenced by vl53lxx::reset(), and ~VL53LXX().

Here is the caller graph for this function:

◆ writeRegister()

int VL53LXX::writeRegister ( const uint8_t  reg_address,
const uint8_t  value 
)
private

Definition at line 748 of file vl53lxx.cpp.

References _comms_errors, and perf_count().

Referenced by measure(), sensorInit(), sensorTuning(), singleRefCalibration(), and spadCalculations().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ writeRegisterMulti()

int VL53LXX::writeRegisterMulti ( const uint8_t  reg_address,
const uint8_t *  value,
const uint8_t  length 
)
private

Definition at line 766 of file vl53lxx.cpp.

References _comms_errors, DEVICE_LOG, and perf_count().

Referenced by sensorInit(), and spadCalculations().

Here is the call graph for this function:
Here is the caller graph for this function:

Member Data Documentation

◆ _class_instance

int VL53LXX::_class_instance {-1}
private

Definition at line 152 of file vl53lxx.cpp.

Referenced by collect(), init(), and ~VL53LXX().

◆ _collect_phase

bool VL53LXX::_collect_phase {false}
private

Definition at line 148 of file vl53lxx.cpp.

Referenced by collect(), measure(), and Run().

◆ _comms_errors

perf_counter_t VL53LXX::_comms_errors {perf_alloc(PC_COUNT, "vl53lxx_com_err")}
private

◆ _distance_sensor_topic

orb_advert_t VL53LXX::_distance_sensor_topic {nullptr}
private

Definition at line 159 of file vl53lxx.cpp.

Referenced by collect(), init(), and ~VL53LXX().

◆ _measure_interval

int VL53LXX::_measure_interval {VL53LXX_SAMPLE_RATE}
private

Definition at line 153 of file vl53lxx.cpp.

Referenced by print_info(), read(), and Run().

◆ _measurement_started

bool VL53LXX::_measurement_started {false}
private

Definition at line 149 of file vl53lxx.cpp.

Referenced by measure().

◆ _new_measurement

bool VL53LXX::_new_measurement {true}
private

Definition at line 150 of file vl53lxx.cpp.

Referenced by measure(), and Run().

◆ _orb_class_instance

int VL53LXX::_orb_class_instance {-1}
private

Definition at line 154 of file vl53lxx.cpp.

Referenced by collect(), and init().

◆ _reports

ringbuffer::RingBuffer* VL53LXX::_reports {nullptr}
private

Definition at line 164 of file vl53lxx.cpp.

Referenced by collect(), init(), print_info(), read(), start(), and ~VL53LXX().

◆ _rotation

uint8_t VL53LXX::_rotation {0}
private

Definition at line 156 of file vl53lxx.cpp.

Referenced by collect().

◆ _sample_perf

perf_counter_t VL53LXX::_sample_perf {perf_alloc(PC_ELAPSED, "vl53lxx_read")}
private

Definition at line 162 of file vl53lxx.cpp.

Referenced by collect(), print_info(), and ~VL53LXX().

◆ _stop_variable

uint8_t VL53LXX::_stop_variable {0}
private

Definition at line 157 of file vl53lxx.cpp.

Referenced by measure(), and sensorInit().


The documentation for this class was generated from the following file: