PX4 Firmware
PX4 Autopilot Software http://px4.io
|
#include <LidarLiteI2C.h>
Public Member Functions | |
LidarLiteI2C (const int bus, const uint8_t rotation=distance_sensor_s::ROTATION_DOWNWARD_FACING, const int address=LL40LS_BASEADDR) | |
virtual | ~LidarLiteI2C () |
int | init () override |
void | print_registers () override |
Print sensor registers to console for debugging. More... | |
void | start () override |
Initialise the automatic measurement state machine and start it. More... | |
void | stop () override |
Stop the automatic measurement state machine. More... | |
Public Member Functions inherited from LidarLite | |
LidarLite (const uint8_t rotation=distance_sensor_s::ROTATION_DOWNWARD_FACING) | |
virtual | ~LidarLite () |
void | print_info () |
Diagnostics - print some basic information about the driver. More... | |
Protected Member Functions | |
int | measure () override |
int | reset_sensor () override |
Reset the sensor to power on defaults plus additional configurations. More... | |
int | probe () override |
int | read_reg (const uint8_t reg, uint8_t &val) |
int | write_reg (const uint8_t reg, const uint8_t &val) |
Protected Member Functions inherited from LidarLite | |
uint32_t | get_measure_interval () const |
Private Member Functions | |
int | collect () override |
int | lidar_transfer (const uint8_t *send, const unsigned send_len, uint8_t *recv, const unsigned recv_len) |
LidarLite specific transfer function. More... | |
int | probe_address (const uint8_t address) |
Test whether the device supported by the driver is present at a specific address. More... | |
void | Run () override |
Perform a poll cycle; collect from the previous measurement and start a new one. More... | |
Private Attributes | |
bool | _collect_phase {false} |
bool | _is_v3hp {false} |
bool | _pause_measurements {false} |
uint8_t | _hw_version {0} |
uint8_t | _sw_version {0} |
uint16_t | _unit_id {0} |
uint16_t | _zero_counter {0} |
uint64_t | _acquire_time_usec {0} |
Additional Inherited Members | |
Protected Attributes inherited from LidarLite | |
PX4Rangefinder | _px4_rangefinder |
perf_counter_t | _comms_errors {perf_alloc(PC_COUNT, "ll40ls: comms errors")} |
perf_counter_t | _sample_perf {perf_alloc(PC_ELAPSED, "ll40ls: read")} |
perf_counter_t | _sensor_resets {perf_alloc(PC_COUNT, "ll40ls: resets")} |
perf_counter_t | _sensor_zero_resets {perf_alloc(PC_COUNT, "ll40ls: zero resets")} |
Definition at line 81 of file LidarLiteI2C.h.
LidarLiteI2C::LidarLiteI2C | ( | const int | bus, |
const uint8_t | rotation = distance_sensor_s::ROTATION_DOWNWARD_FACING , |
||
const int | address = LL40LS_BASEADDR |
||
) |
Definition at line 44 of file LidarLiteI2C.cpp.
|
virtual |
Definition at line 53 of file LidarLiteI2C.cpp.
References stop().
|
overrideprivatevirtual |
Implements LidarLite.
Definition at line 272 of file LidarLiteI2C.cpp.
References _acquire_time_usec, LidarLite::_comms_errors, _is_v3hp, LidarLite::_px4_rangefinder, LidarLite::_sample_perf, LidarLite::_sensor_resets, LidarLite::_sensor_zero_resets, _zero_counter, DEVICE_DEBUG, f(), hrt_absolute_time(), hrt_abstime, hrt_elapsed_time(), lidar_transfer(), LL40LS_AUTO_INCREMENT, LL40LS_CONVERSION_TIMEOUT, LL40LS_DISTHIGH_REG, LL40LS_MIN_DISTANCE, LL40LS_PEAK_STRENGTH_HIGH, LL40LS_PEAK_STRENGTH_LOW, LL40LS_PEAK_STRENGTH_REG, LL40LS_SIGNAL_STRENGTH_LOW, LL40LS_SIGNAL_STRENGTH_MAX_V3HP, LL40LS_SIGNAL_STRENGTH_MIN_V3HP, LL40LS_SIGNAL_STRENGTH_REG, math::max(), OK, perf_begin(), perf_count(), perf_end(), perf_event_count(), reset_sensor(), and PX4Rangefinder::update().
Referenced by Run().
|
overridevirtual |
Implements LidarLite.
Definition at line 59 of file LidarLiteI2C.cpp.
References ToneAlarmInterface::init().
|
private |
LidarLite specific transfer function.
This is needed to avoid a stop transition with SCL high
send | Pointer to bytes to send. |
send_len | Number of bytes to send. |
recv | Pointer to buffer for bytes received. |
recv_len | Number of bytes to receive. |
Definition at line 83 of file LidarLiteI2C.cpp.
Referenced by collect(), print_registers(), and read_reg().
|
overrideprotectedvirtual |
Implements LidarLite.
Definition at line 168 of file LidarLiteI2C.cpp.
References _acquire_time_usec, LidarLite::_comms_errors, _pause_measurements, LidarLite::_sensor_resets, hrt_absolute_time(), LL40LS_MEASURE_REG, LL40LS_MSRREG_ACQUIRE, OK, perf_count(), perf_event_count(), reset_sensor(), and write_reg().
Referenced by Run().
|
overridevirtual |
Print sensor registers to console for debugging.
Reimplemented from LidarLite.
Definition at line 244 of file LidarLiteI2C.cpp.
References _pause_measurements, lidar_transfer(), and OK.
|
overrideprotected |
The probing is divided into different cases. One to detect v2, one for v3 and v1 and one for v3HP. The reason for this is that registers are not consistent between different versions. The v3HP doesn't have the HW VERSION (or at least no version is specified), v1 and v3 don't have the unit id register while v2 has both. It would be better if we had a proper WHOAMI register.
Definition at line 101 of file LidarLiteI2C.cpp.
References _hw_version, _is_v3hp, LidarLite::_px4_rangefinder, _sw_version, _unit_id, LL40LS_BASEADDR, LL40LS_BASEADDR_OLD, LL40LS_HW_VERSION, LL40LS_MAX_DISTANCE_V2, LL40LS_SW_VERSION, LL40LS_UNIT_ID_HIGH, LL40LS_UNIT_ID_LOW, OK, read_reg(), and PX4Rangefinder::set_max_distance().
|
private |
Test whether the device supported by the driver is present at a specific address.
address | The I2C bus address to probe. |
|
protected |
Definition at line 70 of file LidarLiteI2C.cpp.
References lidar_transfer().
Referenced by probe(), and reset_sensor().
|
overrideprotectedvirtual |
Reset the sensor to power on defaults plus additional configurations.
Reimplemented from LidarLite.
Definition at line 202 of file LidarLiteI2C.cpp.
References LL40LS_MEASURE_REG, LL40LS_MSRREG_RESET, LL40LS_SIG_COUNT_VAL_DEFAULT, LL40LS_SIG_COUNT_VAL_MAX, LL40LS_SIG_COUNT_VAL_REG, OK, read_reg(), and write_reg().
Referenced by collect(), and measure().
|
overrideprivate |
Perform a poll cycle; collect from the previous measurement and start a new one.
Definition at line 448 of file LidarLiteI2C.cpp.
References _acquire_time_usec, _collect_phase, collect(), LidarLite::get_measure_interval(), hrt_elapsed_time(), LL40LS_CONVERSION_INTERVAL, LL40LS_CONVERSION_TIMEOUT, measure(), and OK.
|
overridevirtual |
Initialise the automatic measurement state machine and start it.
Implements LidarLite.
Definition at line 434 of file LidarLiteI2C.cpp.
References _collect_phase.
|
overridevirtual |
Stop the automatic measurement state machine.
Implements LidarLite.
Definition at line 443 of file LidarLiteI2C.cpp.
Referenced by ~LidarLiteI2C().
|
protected |
Definition at line 76 of file LidarLiteI2C.cpp.
Referenced by measure(), and reset_sensor().
|
private |
Definition at line 165 of file LidarLiteI2C.h.
|
private |
Definition at line 155 of file LidarLiteI2C.h.
|
private |
Definition at line 159 of file LidarLiteI2C.h.
Referenced by probe().
|
private |
Definition at line 156 of file LidarLiteI2C.h.
|
private |
Definition at line 157 of file LidarLiteI2C.h.
Referenced by measure(), and print_registers().
|
private |
Definition at line 160 of file LidarLiteI2C.h.
Referenced by probe().
|
private |
Definition at line 162 of file LidarLiteI2C.h.
Referenced by probe().
|
private |
Definition at line 163 of file LidarLiteI2C.h.
Referenced by collect().