PX4 Firmware
PX4 Autopilot Software http://px4.io
|
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} |
Definition at line 89 of file vl53lxx.cpp.
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().
|
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().
|
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().
|
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().
|
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().
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().
|
overrideprotectedvirtual |
Definition at line 358 of file vl53lxx.cpp.
References sensorInit().
|
virtual |
Definition at line 369 of file vl53lxx.cpp.
References _measure_interval, _reports, collect(), and measure().
Referenced by vl53lxx::test().
|
private |
Definition at line 426 of file vl53lxx.cpp.
References _comms_errors, and perf_count().
Referenced by measure(), sensorInit(), singleRefCalibration(), and spadCalculations().
|
private |
Definition at line 449 of file vl53lxx.cpp.
References _comms_errors, and perf_count().
Referenced by spadCalculations().
|
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().
|
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().
|
private |
Definition at line 626 of file vl53lxx.cpp.
References writeRegister().
Referenced by spadCalculations().
|
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().
|
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().
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().
void VL53LXX::stop | ( | ) |
Stop the automatic measurement state machine.
Definition at line 742 of file vl53lxx.cpp.
Referenced by vl53lxx::reset(), and ~VL53LXX().
|
private |
Definition at line 748 of file vl53lxx.cpp.
References _comms_errors, and perf_count().
Referenced by measure(), sensorInit(), sensorTuning(), singleRefCalibration(), and spadCalculations().
|
private |
Definition at line 766 of file vl53lxx.cpp.
References _comms_errors, DEVICE_LOG, and perf_count().
Referenced by sensorInit(), and spadCalculations().
|
private |
Definition at line 152 of file vl53lxx.cpp.
Referenced by collect(), init(), and ~VL53LXX().
|
private |
Definition at line 148 of file vl53lxx.cpp.
|
private |
Definition at line 161 of file vl53lxx.cpp.
Referenced by collect(), measure(), print_info(), readRegister(), readRegisterMulti(), writeRegister(), writeRegisterMulti(), and ~VL53LXX().
|
private |
Definition at line 159 of file vl53lxx.cpp.
Referenced by collect(), init(), and ~VL53LXX().
|
private |
Definition at line 153 of file vl53lxx.cpp.
Referenced by print_info(), read(), and Run().
|
private |
Definition at line 149 of file vl53lxx.cpp.
Referenced by measure().
|
private |
Definition at line 150 of file vl53lxx.cpp.
|
private |
Definition at line 154 of file vl53lxx.cpp.
|
private |
Definition at line 164 of file vl53lxx.cpp.
Referenced by collect(), init(), print_info(), read(), start(), and ~VL53LXX().
|
private |
Definition at line 156 of file vl53lxx.cpp.
Referenced by collect().
|
private |
Definition at line 162 of file vl53lxx.cpp.
Referenced by collect(), print_info(), and ~VL53LXX().
|
private |
Definition at line 157 of file vl53lxx.cpp.
Referenced by measure(), and sensorInit().