|
#define | LL40LS_BASEADDR 0x62 /* 7-bit address */ |
|
#define | LL40LS_BASEADDR_OLD 0x42 /* previous 7-bit address */ |
|
#define | LL40LS_MEASURE_REG 0x00 /* Measure range register */ |
|
#define | LL40LS_MSRREG_RESET 0x00 /* reset to power on defaults */ |
|
#define | LL40LS_MSRREG_ACQUIRE 0x04 /* Value to initiate a measurement, varies based on sensor revision */ |
|
#define | LL40LS_DISTHIGH_REG 0x0F /* High byte of distance register, auto increment */ |
|
#define | LL40LS_AUTO_INCREMENT 0x80 |
|
#define | LL40LS_HW_VERSION 0x41 |
|
#define | LL40LS_SW_VERSION 0x4f |
|
#define | LL40LS_SIGNAL_STRENGTH_REG 0x0e |
|
#define | LL40LS_PEAK_STRENGTH_REG 0x0c |
|
#define | LL40LS_UNIT_ID_HIGH 0x16 |
|
#define | LL40LS_UNIT_ID_LOW 0x17 |
|
#define | LL40LS_SIG_COUNT_VAL_REG 0x02 /* Maximum acquisition count register */ |
|
#define | LL40LS_SIG_COUNT_VAL_MAX 0xFF /* Maximum acquisition count max value */ |
|
#define | LL40LS_SIGNAL_STRENGTH_LOW 24 |
|
#define | LL40LS_PEAK_STRENGTH_LOW 135 |
|
#define | LL40LS_PEAK_STRENGTH_HIGH 234 |
|
- Author
- Allyson Kreft
Driver for the PulsedLight Lidar-Lite range finders connected via I2C.