APM:Libraries
AP_RangeFinder_PulsedLightLRF.cpp
Go to the documentation of this file.
1 /*
2  This program is free software: you can redistribute it and/or modify
3  it under the terms of the GNU General Public License as published by
4  the Free Software Foundation, either version 3 of the License, or
5  (at your option) any later version.
6 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
16 
17 #include <utility>
18 #include <stdio.h>
19 
20 #include <AP_HAL/AP_HAL.h>
22 
23 extern const AP_HAL::HAL& hal;
24 
25 /* LL40LS Registers addresses */
26 #define LL40LS_MEASURE_REG 0x00 /* Measure range register */
27 #define LL40LS_DISTHIGH_REG 0x0F /* High byte of distance register, auto increment */
28 #define LL40LS_COUNT 0x11
29 #define LL40LS_HW_VERSION 0x41
30 #define LL40LS_INTERVAL 0x45
31 #define LL40LS_SW_VERSION 0x4f
32 
33 // bit values
34 #define LL40LS_MSRREG_RESET 0x00 /* reset to power on defaults */
35 #define LL40LS_AUTO_INCREMENT 0x80
36 #define LL40LS_COUNT_CONTINUOUS 0xff
37 #define LL40LS_MSRREG_ACQUIRE 0x04 /* Value to initiate a measurement, varies based on sensor revision */
38 
39 // i2c address
40 #define LL40LS_ADDR 0x62
41 
42 /*
43  The constructor also initializes the rangefinder. Note that this
44  constructor is not called until detect() returns true, so we
45  already know that we should setup the rangefinder
46 */
50  : AP_RangeFinder_Backend(_state)
51  , _dev(hal.i2c_mgr->get_device(bus, LL40LS_ADDR))
52  , rftype(_rftype)
53 {
54 }
55 
56 /*
57  detect if a PulsedLight rangefinder is connected. We'll detect by
58  look for the version registers
59 */
63 {
65  = new AP_RangeFinder_PulsedLightLRF(bus, _state, rftype);
66  if (!sensor ||
67  !sensor->init()) {
68  delete sensor;
69  return nullptr;
70  }
71  return sensor;
72 }
73 
74 /*
75  called at 50Hz
76  */
78 {
79  if (check_reg_counter++ == 10) {
81  if (!_dev->check_next_register()) {
82  // re-send the acquire. this handles the case of power
83  // cycling while running in continuous mode
85  }
86  }
87 
88  switch (phase) {
89  case PHASE_MEASURE:
92  }
93  break;
94 
95  case PHASE_COLLECT: {
96  be16_t val;
97  // read the high and low byte distance registers
98  if (_dev->read_registers(LL40LS_DISTHIGH_REG | LL40LS_AUTO_INCREMENT, (uint8_t*)&val, sizeof(val))) {
99  uint16_t _distance_cm = be16toh(val);
100  // remove momentary spikes
101  if (abs(_distance_cm - last_distance_cm) < 100) {
102  state.distance_cm = _distance_cm;
103  update_status();
104  }
105  last_distance_cm = _distance_cm;
106  } else {
108  }
109  if (!v2_hardware) {
110  // for v2 hw we use continuous mode
112  }
113  break;
114  }
115  }
116 }
117 
118 
119 /*
120  a table of settings for a lidar
121  */
123  uint8_t reg;
124  uint8_t value;
125 };
126 
127 /*
128  register setup table for V1 Lidar
129  */
130 static const struct settings_table settings_v1[] = {
132 };
133 
134 /*
135  register setup table for V2 Lidar
136  */
137 static const struct settings_table settings_v2[] = {
138  { LL40LS_INTERVAL, 0x28 }, // 0x28 == 50Hz
141 };
142 
143 /*
144  initialise the sensor to required settings
145  */
147 {
149  return false;
150  }
151  _dev->set_retries(3);
152 
153  // LidarLite needs split transfers
154  _dev->set_split_transfers(true);
155 
157  v2_hardware = true;
158  } else {
159  // auto-detect v1 vs v2
161  hw_version > 0 &&
163  sw_version > 0)) {
164  printf("PulsedLightI2C: bad version 0x%02x 0x%02x\n", (unsigned)hw_version, (unsigned)sw_version);
165  // invalid version information
166  goto failed;
167  }
168  v2_hardware = (hw_version >= 0x15);
169  }
170 
171  const struct settings_table *table;
172  uint8_t num_settings;
173 
174  if (v2_hardware) {
175  table = settings_v2;
176  num_settings = sizeof(settings_v2) / sizeof(settings_table);
178  } else {
179  table = settings_v1;
180  num_settings = sizeof(settings_v1) / sizeof(settings_table);
181  phase = PHASE_MEASURE;
182  }
183 
184  _dev->setup_checked_registers(num_settings);
185 
186  for (uint8_t i = 0; i < num_settings; i++) {
187  if (!_dev->write_register(table[i].reg, table[i].value, true)) {
188  goto failed;
189  }
190  }
191 
192  printf("Found LidarLite device=0x%x v2=%d\n", _dev->get_bus_id(), (int)v2_hardware);
193 
194  _dev->get_semaphore()->give();
195 
198  return true;
199 
200 failed:
201  _dev->get_semaphore()->give();
202  return false;
203 }
204 
int printf(const char *fmt,...)
Definition: stdio.c:113
virtual Device::PeriodicHandle register_periodic_callback(uint32_t period_usec, Device::PeriodicCb) override=0
uint32_t get_bus_id(void) const
Definition: Device.h:60
static AP_RangeFinder_Backend * detect(uint8_t bus, RangeFinder::RangeFinder_State &_state, RangeFinder::RangeFinder_Type rftype)
virtual void set_retries(uint8_t retries)
Definition: Device.h:260
virtual Semaphore * get_semaphore() override=0
#define LL40LS_MEASURE_REG
AP_HAL::OwnPtr< AP_HAL::Device > get_device(const char *name)
Definition: BusTest.cpp:22
#define LL40LS_SW_VERSION
#define HAL_SEMAPHORE_BLOCK_FOREVER
Definition: Semaphores.h:5
virtual bool take(uint32_t timeout_ms) WARN_IF_UNUSED=0
static const struct settings_table settings_v1[]
#define LL40LS_MSRREG_ACQUIRE
virtual void set_split_transfers(bool set)
Definition: I2CDevice.h:69
bool setup_checked_registers(uint8_t num_regs, uint8_t frequency=10)
Definition: Device.cpp:39
#define LL40LS_COUNT_CONTINUOUS
static const struct settings_table settings_v2[]
static uint16_t be16toh(be16_t value)
Definition: sparse-endian.h:83
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
RangeFinder::RangeFinder_Type rftype
#define LL40LS_DISTHIGH_REG
virtual bool give()=0
#define LL40LS_MSRREG_RESET
#define LL40LS_AUTO_INCREMENT
AP_HAL::OwnPtr< AP_HAL::I2CDevice > _dev
AP_RangeFinder_PulsedLightLRF(uint8_t bus, RangeFinder::RangeFinder_State &_state, RangeFinder::RangeFinder_Type rftype)
#define LL40LS_HW_VERSION
bool check_next_register(void)
Definition: Device.cpp:85
bool read_registers(uint8_t first_reg, uint8_t *recv, uint32_t recv_len)
Definition: Device.h:113
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
Definition: functor.h:31
#define LL40LS_INTERVAL
void set_status(RangeFinder::RangeFinder_Status status)
RangeFinder::RangeFinder_State & state
enum AP_RangeFinder_PulsedLightLRF::@176 phase
bool write_register(uint8_t reg, uint8_t val, bool checked=false)
Definition: Device.h:125
uint16_t __ap_bitwise be16_t
Definition: sparse-endian.h:36
#define LL40LS_COUNT