PX4 Firmware
PX4 Autopilot Software http://px4.io
LidarLiteI2C Class Reference

#include <LidarLiteI2C.h>

Inheritance diagram for LidarLiteI2C:
Collaboration diagram for LidarLiteI2C:

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")}
 

Detailed Description

Definition at line 81 of file LidarLiteI2C.h.

Constructor & Destructor Documentation

◆ LidarLiteI2C()

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.

◆ ~LidarLiteI2C()

LidarLiteI2C::~LidarLiteI2C ( )
virtual

Definition at line 53 of file LidarLiteI2C.cpp.

References stop().

Here is the call graph for this function:

Member Function Documentation

◆ collect()

int LidarLiteI2C::collect ( )
overrideprivatevirtual

◆ init()

int LidarLiteI2C::init ( )
overridevirtual

Implements LidarLite.

Definition at line 59 of file LidarLiteI2C.cpp.

References ToneAlarmInterface::init().

Here is the call graph for this function:

◆ lidar_transfer()

int LidarLiteI2C::lidar_transfer ( const uint8_t *  send,
const unsigned  send_len,
uint8_t *  recv,
const unsigned  recv_len 
)
private

LidarLite specific transfer function.

This is needed to avoid a stop transition with SCL high

Parameters
sendPointer to bytes to send.
send_lenNumber of bytes to send.
recvPointer to buffer for bytes received.
recv_lenNumber of bytes to receive.
Returns
OK if the transfer was successful, -errno otherwise.

Definition at line 83 of file LidarLiteI2C.cpp.

Referenced by collect(), print_registers(), and read_reg().

Here is the caller graph for this function:

◆ measure()

int LidarLiteI2C::measure ( )
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().

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

◆ print_registers()

void LidarLiteI2C::print_registers ( )
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.

Here is the call graph for this function:

◆ probe()

int LidarLiteI2C::probe ( )
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().

Here is the call graph for this function:

◆ probe_address()

int LidarLiteI2C::probe_address ( const uint8_t  address)
private

Test whether the device supported by the driver is present at a specific address.

Parameters
addressThe I2C bus address to probe.
Returns
True if the device is present.

◆ read_reg()

int LidarLiteI2C::read_reg ( const uint8_t  reg,
uint8_t &  val 
)
protected

Definition at line 70 of file LidarLiteI2C.cpp.

References lidar_transfer().

Referenced by probe(), and reset_sensor().

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

◆ reset_sensor()

int LidarLiteI2C::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().

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

◆ Run()

void LidarLiteI2C::Run ( )
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.

Here is the call graph for this function:

◆ start()

void LidarLiteI2C::start ( )
overridevirtual

Initialise the automatic measurement state machine and start it.

Note
This function is called at open and error time. It might make sense to make it more aggressive about resetting the bus in case of errors.

Implements LidarLite.

Definition at line 434 of file LidarLiteI2C.cpp.

References _collect_phase.

◆ stop()

void LidarLiteI2C::stop ( )
overridevirtual

Stop the automatic measurement state machine.

Implements LidarLite.

Definition at line 443 of file LidarLiteI2C.cpp.

Referenced by ~LidarLiteI2C().

Here is the caller graph for this function:

◆ write_reg()

int LidarLiteI2C::write_reg ( const uint8_t  reg,
const uint8_t &  val 
)
protected

Definition at line 76 of file LidarLiteI2C.cpp.

Referenced by measure(), and reset_sensor().

Here is the caller graph for this function:

Member Data Documentation

◆ _acquire_time_usec

uint64_t LidarLiteI2C::_acquire_time_usec {0}
private

Definition at line 165 of file LidarLiteI2C.h.

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

◆ _collect_phase

bool LidarLiteI2C::_collect_phase {false}
private

Definition at line 155 of file LidarLiteI2C.h.

Referenced by Run(), and start().

◆ _hw_version

uint8_t LidarLiteI2C::_hw_version {0}
private

Definition at line 159 of file LidarLiteI2C.h.

Referenced by probe().

◆ _is_v3hp

bool LidarLiteI2C::_is_v3hp {false}
private

Definition at line 156 of file LidarLiteI2C.h.

Referenced by collect(), and probe().

◆ _pause_measurements

bool LidarLiteI2C::_pause_measurements {false}
private

Definition at line 157 of file LidarLiteI2C.h.

Referenced by measure(), and print_registers().

◆ _sw_version

uint8_t LidarLiteI2C::_sw_version {0}
private

Definition at line 160 of file LidarLiteI2C.h.

Referenced by probe().

◆ _unit_id

uint16_t LidarLiteI2C::_unit_id {0}
private

Definition at line 162 of file LidarLiteI2C.h.

Referenced by probe().

◆ _zero_counter

uint16_t LidarLiteI2C::_zero_counter {0}
private

Definition at line 163 of file LidarLiteI2C.h.

Referenced by collect().


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