PX4 Firmware
PX4 Autopilot Software http://px4.io
vl53lxx.cpp File Reference
#include <stdlib.h>
#include <string.h>
#include <containers/Array.hpp>
#include <drivers/device/i2c.h>
#include <drivers/device/ringbuffer.h>
#include <drivers/drv_hrt.h>
#include <drivers/drv_range_finder.h>
#include <perf/perf_counter.h>
#include <px4_platform_common/getopt.h>
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
#include <uORB/topics/distance_sensor.h>
Include dependency graph for vl53lxx.cpp:

Go to the source code of this file.

Classes

class  VL53LXX
 

Namespaces

 vl53lxx
 Local functions in support of the shell command.
 

Macros

#define VL53LXX_BUS_DEFAULT   PX4_I2C_BUS_EXPANSION
 
#define VL53LXX_BASEADDR   0x29
 
#define VL53LXX_DEVICE_PATH   "/dev/vl53lxx"
 
#define VHV_CONFIG_PAD_SCL_SDA_EXTSUP_HW_REG   0x89
 
#define MSRC_CONFIG_CONTROL_REG   0x60
 
#define FINAL_RANGE_CONFIG_MIN_COUNT_RATE_RTN_LIMIT_REG   0x44
 
#define SYSTEM_SEQUENCE_CONFIG_REG   0x01
 
#define DYNAMIC_SPAD_REF_EN_START_OFFSET_REG   0x4F
 
#define DYNAMIC_SPAD_NUM_REQUESTED_REF_SPAD_REG   0x4E
 
#define GLOBAL_CONFIG_REF_EN_START_SELECT_REG   0xB6
 
#define GLOBAL_CONFIG_SPAD_ENABLES_REF_0_REG   0xB0
 
#define SYSTEM_INTERRUPT_CONFIG_GPIO_REG   0x0A
 
#define SYSTEM_SEQUENCE_CONFIG_REG   0x01
 
#define SYSRANGE_START_REG   0x00
 
#define RESULT_INTERRUPT_STATUS_REG   0x13
 
#define SYSTEM_INTERRUPT_CLEAR_REG   0x0B
 
#define GLOBAL_CONFIG_SPAD_ENABLES_REF_0_REG   0xB0
 
#define GPIO_HV_MUX_ACTIVE_HIGH_REG   0x84
 
#define SYSTEM_INTERRUPT_CLEAR_REG   0x0B
 
#define RESULT_RANGE_STATUS_REG   0x14
 
#define VL53LXX_RA_IDENTIFICATION_MODEL_ID   0xC0
 
#define VL53LXX_IDENTIFICATION_MODEL_ID   0xEEAA
 
#define VL53LXX_US   1000
 
#define VL53LXX_SAMPLE_RATE   50000
 
#define VL53LXX_MAX_RANGING_DISTANCE   2.0f
 
#define VL53LXX_MIN_RANGING_DISTANCE   0.0f
 
#define VL53LXX_BUS_CLOCK   400000
 

Functions

int vl53lxx::reset ()
 Reset the driver. More...
 
int vl53lxx::start (const uint8_t rotation)
 Attempt to start driver on all available I2C busses. More...
 
int vl53lxx::start_bus (const uint8_t rotation, const int i2c_bus)
 Start the driver on a specific bus. More...
 
int vl53lxx::status ()
 Print the driver status. More...
 
int vl53lxx::stop ()
 Stop the driver. More...
 
int vl53lxx::test ()
 Perform some basic functional tests on the driver; make sure we can collect data from the sensor in polled and automatic modes. More...
 
int vl53lxx::usage ()
 Prints info about the driver argument usage. More...
 
__EXPORT int vl53lxx_main (int argc, char *argv[])
 Driver 'main' command. More...
 

Variables

VL53LXXvl53lxx::g_dev
 

Detailed Description

Author
Daniele Pettenuzzo

Driver for the vl53lxx ToF Sensor from ST Microelectronics connected via I2C.

Definition in file vl53lxx.cpp.

Macro Definition Documentation

◆ DYNAMIC_SPAD_NUM_REQUESTED_REF_SPAD_REG

#define DYNAMIC_SPAD_NUM_REQUESTED_REF_SPAD_REG   0x4E

Definition at line 66 of file vl53lxx.cpp.

Referenced by VL53LXX::spadCalculations().

◆ DYNAMIC_SPAD_REF_EN_START_OFFSET_REG

#define DYNAMIC_SPAD_REF_EN_START_OFFSET_REG   0x4F

Definition at line 65 of file vl53lxx.cpp.

Referenced by VL53LXX::spadCalculations().

◆ FINAL_RANGE_CONFIG_MIN_COUNT_RATE_RTN_LIMIT_REG

#define FINAL_RANGE_CONFIG_MIN_COUNT_RATE_RTN_LIMIT_REG   0x44

Definition at line 63 of file vl53lxx.cpp.

Referenced by VL53LXX::sensorInit().

◆ GLOBAL_CONFIG_REF_EN_START_SELECT_REG

#define GLOBAL_CONFIG_REF_EN_START_SELECT_REG   0xB6

Definition at line 67 of file vl53lxx.cpp.

Referenced by VL53LXX::spadCalculations().

◆ GLOBAL_CONFIG_SPAD_ENABLES_REF_0_REG [1/2]

#define GLOBAL_CONFIG_SPAD_ENABLES_REF_0_REG   0xB0

Definition at line 74 of file vl53lxx.cpp.

Referenced by VL53LXX::spadCalculations().

◆ GLOBAL_CONFIG_SPAD_ENABLES_REF_0_REG [2/2]

#define GLOBAL_CONFIG_SPAD_ENABLES_REF_0_REG   0xB0

Definition at line 74 of file vl53lxx.cpp.

◆ GPIO_HV_MUX_ACTIVE_HIGH_REG

#define GPIO_HV_MUX_ACTIVE_HIGH_REG   0x84

Definition at line 75 of file vl53lxx.cpp.

Referenced by VL53LXX::spadCalculations().

◆ MSRC_CONFIG_CONTROL_REG

#define MSRC_CONFIG_CONTROL_REG   0x60

Definition at line 62 of file vl53lxx.cpp.

Referenced by VL53LXX::sensorInit().

◆ RESULT_INTERRUPT_STATUS_REG

#define RESULT_INTERRUPT_STATUS_REG   0x13

Definition at line 72 of file vl53lxx.cpp.

Referenced by VL53LXX::measure(), and VL53LXX::singleRefCalibration().

◆ RESULT_RANGE_STATUS_REG

#define RESULT_RANGE_STATUS_REG   0x14

Definition at line 77 of file vl53lxx.cpp.

Referenced by VL53LXX::measure().

◆ SYSRANGE_START_REG

#define SYSRANGE_START_REG   0x00

Definition at line 71 of file vl53lxx.cpp.

Referenced by VL53LXX::measure(), and VL53LXX::singleRefCalibration().

◆ SYSTEM_INTERRUPT_CLEAR_REG [1/2]

#define SYSTEM_INTERRUPT_CLEAR_REG   0x0B

Definition at line 76 of file vl53lxx.cpp.

Referenced by VL53LXX::singleRefCalibration(), and VL53LXX::spadCalculations().

◆ SYSTEM_INTERRUPT_CLEAR_REG [2/2]

#define SYSTEM_INTERRUPT_CLEAR_REG   0x0B

Definition at line 76 of file vl53lxx.cpp.

◆ SYSTEM_INTERRUPT_CONFIG_GPIO_REG

#define SYSTEM_INTERRUPT_CONFIG_GPIO_REG   0x0A

Definition at line 69 of file vl53lxx.cpp.

Referenced by VL53LXX::spadCalculations().

◆ SYSTEM_SEQUENCE_CONFIG_REG [1/2]

#define SYSTEM_SEQUENCE_CONFIG_REG   0x01

Definition at line 70 of file vl53lxx.cpp.

Referenced by VL53LXX::sensorInit(), and VL53LXX::spadCalculations().

◆ SYSTEM_SEQUENCE_CONFIG_REG [2/2]

#define SYSTEM_SEQUENCE_CONFIG_REG   0x01

Definition at line 70 of file vl53lxx.cpp.

◆ VHV_CONFIG_PAD_SCL_SDA_EXTSUP_HW_REG

#define VHV_CONFIG_PAD_SCL_SDA_EXTSUP_HW_REG   0x89

Definition at line 61 of file vl53lxx.cpp.

Referenced by VL53LXX::sensorInit().

◆ VL53LXX_BASEADDR

#define VL53LXX_BASEADDR   0x29

Definition at line 57 of file vl53lxx.cpp.

Referenced by VL53LXX::init().

◆ VL53LXX_BUS_CLOCK

#define VL53LXX_BUS_CLOCK   400000

Definition at line 87 of file vl53lxx.cpp.

◆ VL53LXX_BUS_DEFAULT

#define VL53LXX_BUS_DEFAULT   PX4_I2C_BUS_EXPANSION

Definition at line 55 of file vl53lxx.cpp.

Referenced by vl53lxx::usage(), and vl53lxx_main().

◆ VL53LXX_DEVICE_PATH

#define VL53LXX_DEVICE_PATH   "/dev/vl53lxx"

Definition at line 58 of file vl53lxx.cpp.

Referenced by vl53lxx::test().

◆ VL53LXX_IDENTIFICATION_MODEL_ID

#define VL53LXX_IDENTIFICATION_MODEL_ID   0xEEAA

Definition at line 79 of file vl53lxx.cpp.

◆ VL53LXX_MAX_RANGING_DISTANCE

#define VL53LXX_MAX_RANGING_DISTANCE   2.0f

Definition at line 84 of file vl53lxx.cpp.

Referenced by VL53LXX::collect().

◆ VL53LXX_MIN_RANGING_DISTANCE

#define VL53LXX_MIN_RANGING_DISTANCE   0.0f

Definition at line 85 of file vl53lxx.cpp.

Referenced by VL53LXX::collect().

◆ VL53LXX_RA_IDENTIFICATION_MODEL_ID

#define VL53LXX_RA_IDENTIFICATION_MODEL_ID   0xC0

Definition at line 78 of file vl53lxx.cpp.

◆ VL53LXX_SAMPLE_RATE

#define VL53LXX_SAMPLE_RATE   50000

Definition at line 82 of file vl53lxx.cpp.

◆ VL53LXX_US

#define VL53LXX_US   1000

Definition at line 81 of file vl53lxx.cpp.

Referenced by VL53LXX::measure().

Function Documentation

◆ vl53lxx_main()

__EXPORT int vl53lxx_main ( int  argc,
char *  argv[] 
)

Driver 'main' command.

Definition at line 961 of file vl53lxx.cpp.

References vl53lxx::reset(), vl53lxx::start(), vl53lxx::start_bus(), vl53lxx::status(), vl53lxx::stop(), vl53lxx::test(), vl53lxx::usage(), and VL53LXX_BUS_DEFAULT.

Here is the call graph for this function: