APM:Libraries
AP_Proximity_RPLidarA2.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  */
15 
16 /*
17  * ArduPilot device driver for SLAMTEC RPLIDAR A2 (16m range version)
18  *
19  * ALL INFORMATION REGARDING PROTOCOL WAS DERIVED FROM RPLIDAR DATASHEET:
20  *
21  * https://www.slamtec.com/en/Lidar
22  * http://bucket.download.slamtec.com/63ac3f0d8c859d3a10e51c6b3285fcce25a47357/LR001_SLAMTEC_rplidar_protocol_v1.0_en.pdf
23  *
24  * Author: Steven Josefs, IAV GmbH
25  * Based on the LightWare SF40C ArduPilot device driver from Randy Mackay
26  *
27  */
28 
29 #include <AP_HAL/AP_HAL.h>
30 #include "AP_Proximity_RPLidarA2.h"
32 #include <ctype.h>
33 #include <stdio.h>
34 
35 #define RP_DEBUG_LEVEL 0
36 
37 #if RP_DEBUG_LEVEL
38  #include <GCS_MAVLink/GCS.h>
39  #define Debug(level, fmt, args ...) do { if (level <= RP_DEBUG_LEVEL) { gcs().send_text(MAV_SEVERITY_INFO, fmt, ## args); } } while (0)
40 #else
41  #define Debug(level, fmt, args ...)
42 #endif
43 
44 #define COMM_ACTIVITY_TIMEOUT_MS 200
45 #define RESET_RPA2_WAIT_MS 8
46 #define RESYNC_TIMEOUT 5000
47 
48 // Commands
49 //-----------------------------------------
50 
51 // Commands without payload and response
52 #define RPLIDAR_PREAMBLE 0xA5
53 #define RPLIDAR_CMD_STOP 0x25
54 #define RPLIDAR_CMD_SCAN 0x20
55 #define RPLIDAR_CMD_FORCE_SCAN 0x21
56 #define RPLIDAR_CMD_RESET 0x40
57 
58 // Commands without payload but have response
59 #define RPLIDAR_CMD_GET_DEVICE_INFO 0x50
60 #define RPLIDAR_CMD_GET_DEVICE_HEALTH 0x52
61 
62 // Commands with payload and have response
63 #define RPLIDAR_CMD_EXPRESS_SCAN 0x82
64 
65 extern const AP_HAL::HAL& hal;
66 
67 /*
68  The constructor also initialises the proximity sensor. Note that this
69  constructor is not called until detect() returns true, so we
70  already know that we should setup the proximity sensor
71  */
75  AP_Proximity_Backend(_frontend, _state)
76 {
78  if (_uart != nullptr) {
80  }
81  _cnt = 0 ;
82  _sync_error = 0 ;
83  _byte_count = 0;
84 }
85 
86 // detect if a RPLidarA2 proximity sensor is connected by looking for a configured serial port
88 {
89  return serial_manager.find_serial(AP_SerialManager::SerialProtocol_Lidar360, 0) != nullptr;
90 }
91 
92 // update the _rp_state of the sensor
94 {
95  if (_uart == nullptr) {
96  return;
97  }
98 
99  // initialise sensor if necessary
100  if (!_initialised) {
101  _initialised = initialise(); //returns true if everything initialized properly
102  }
103 
104  // if LIDAR in known state
105  if (_initialised) {
106  get_readings();
107  }
108 
109  // check for timeout and set health status
112  Debug(1, "LIDAR NO DATA");
113  } else {
115  }
116 }
117 
118 // get maximum distance (in meters) of sensor
120 {
121  return 16.0f; //16m max range RPLIDAR2, if you want to support the 8m version this is the only line to change
122 }
123 
124 // get minimum distance (in meters) of sensor
126 {
127  return 0.20f; //20cm min range RPLIDAR2
128 }
129 
131 {
132  // initialise sectors
133  if (!_sector_initialised) {
134  init_sectors();
135  return false;
136  }
137  if (!_initialised) {
138  reset_rplidar(); // set to a known state
139  Debug(1, "LIDAR initialised");
140  return true;
141  }
142 
143  return true;
144 }
145 
147 {
148  if (_uart == nullptr) {
149  return;
150  }
151  uint8_t tx_buffer[2] = {RPLIDAR_PREAMBLE, RPLIDAR_CMD_RESET};
152  _uart->write(tx_buffer, 2);
153  _resetted = true;
154  Debug(1, "LIDAR reset");
155  // To-Do: ensure delay of 8m after sending reset request
158 
159 }
160 
161 // initialise sector angles using user defined ignore areas, left same as SF40C
163 {
164  // use defaults if no ignore areas defined
165  const uint8_t ignore_area_count = get_ignore_area_count();
166  if (ignore_area_count == 0) {
167  _sector_initialised = true;
168  return;
169  }
170 
171  uint8_t sector = 0;
172  for (uint8_t i=0; i<ignore_area_count; i++) {
173 
174  // get ignore area info
175  uint16_t ign_area_angle;
176  uint8_t ign_area_width;
177  if (get_ignore_area(i, ign_area_angle, ign_area_width)) {
178 
179  // calculate how many degrees of space we have between this end of this ignore area and the start of the end
180  int16_t start_angle, end_angle;
181  get_next_ignore_start_or_end(1, ign_area_angle, start_angle);
182  get_next_ignore_start_or_end(0, start_angle, end_angle);
183  int16_t degrees_to_fill = wrap_360(end_angle - start_angle);
184 
185  // divide up the area into sectors
186  while ((degrees_to_fill > 0) && (sector < PROXIMITY_SECTORS_MAX)) {
187  uint16_t sector_size;
188  if (degrees_to_fill >= 90) {
189  // set sector to maximum of 45 degrees
190  sector_size = 45;
191  } else if (degrees_to_fill > 45) {
192  // use half the remaining area to optimise size of this sector and the next
193  sector_size = degrees_to_fill / 2.0f;
194  } else {
195  // 45 degrees or less are left so put it all into the next sector
196  sector_size = degrees_to_fill;
197  }
198  // record the sector middle and width
199  _sector_middle_deg[sector] = wrap_360(start_angle + sector_size / 2.0f);
200  _sector_width_deg[sector] = sector_size;
201 
202  // move onto next sector
203  start_angle += sector_size;
204  sector++;
205  degrees_to_fill -= sector_size;
206  }
207  }
208  }
209 
210  // set num sectors
211  _num_sectors = sector;
212 
213  // re-initialise boundary because sector locations have changed
214  init_boundary();
215 
216  // record success
217  _sector_initialised = true;
218 }
219 
220 // set Lidar into SCAN mode
222 {
223  if (_uart == nullptr) {
224  return;
225  }
226  uint8_t tx_buffer[2] = {RPLIDAR_PREAMBLE, RPLIDAR_CMD_SCAN};
227  _uart->write(tx_buffer, 2);
229  Debug(1, "LIDAR SCAN MODE ACTIVATED");
231 }
232 
233 // send request for sensor health
235 {
236  if (_uart == nullptr) {
237  return;
238  }
239  uint8_t tx_buffer[2] = {RPLIDAR_PREAMBLE, RPLIDAR_CMD_GET_DEVICE_HEALTH};
240  _uart->write(tx_buffer, 2);
243 }
244 
246 {
247  if (_uart == nullptr) {
248  return;
249  }
250  Debug(2, " CURRENT STATE: %d ", _rp_state);
251  uint32_t nbytes = _uart->available();
252 
253  while (nbytes-- > 0) {
254 
255  uint8_t c = _uart->read();
256  Debug(2, "UART READ %x <%c>", c, c); //show HEX values
257 
258  STATE:
259  switch(_rp_state){
260 
261  case rp_resetted:
262  Debug(3, " BYTE_COUNT %d", _byte_count);
263  if ((c == 0x52 || _information_data) && _byte_count < 62) {
264  if (c == 0x52) {
265  _information_data = true;
266  }
268  Debug(3, "_rp_systeminfo[%d]=%x",_byte_count,_rp_systeminfo[_byte_count]);
269  _byte_count++;
270  break;
271  } else {
272 
273  if (_information_data) {
274  Debug(1, "GOT RPLIDAR INFORMATION");
275  _information_data = false;
276  _byte_count = 0;
277  set_scan_mode();
278  break;
279  }
280 
281  if (_cnt>5) {
283  _cnt=0;
284  break;
285  }
286  _cnt++;
287  break;
288  }
289  break;
290 
291  case rp_responding:
292  Debug(2, "RESPONDING");
293  if (c == RPLIDAR_PREAMBLE || _descriptor_data) {
294  _descriptor_data = true;
296  _byte_count++;
297  // descriptor packet has 7 byte in total
298  if (_byte_count == sizeof(_descriptor)) {
299  Debug(2,"LIDAR DESCRIPTOR CATCHED");
301  // identify the payload data after the descriptor
303  _byte_count = 0;
304  }
305  } else {
307  }
308  break;
309 
310  case rp_measurements:
311  if (_sync_error) {
312  // out of 5-byte sync mask -> catch new revolution
313  Debug(1, " OUT OF SYNC");
314  // on first revolution bit 1 = 1, bit 2 = 0 of the first byte
315  if ((c & 0x03) == 0x01) {
316  _sync_error = 0;
317  Debug(1, " RESYNC");
318  } else {
320  reset_rplidar();
321  }
322  break;
323  }
324  }
325  Debug(3, "READ PAYLOAD");
326  payload[_byte_count] = c;
327  _byte_count++;
328 
329  if (_byte_count == _payload_length) {
330  Debug(2, "LIDAR MEASUREMENT CATCHED");
332  _byte_count = 0;
333  }
334  break;
335 
336  case rp_health:
337  Debug(1, "state: HEALTH");
338  break;
339 
340  case rp_unknown:
341  Debug(1, "state: UNKNOWN");
342  if (c == RPLIDAR_PREAMBLE) {
344  goto STATE;
345  break;
346  }
347  _cnt++;
348  if (_cnt>10) {
349  reset_rplidar();
351  _cnt=0;
352  }
353  break;
354 
355  default:
356  Debug(1, "UNKNOWN LIDAR STATE");
357  break;
358  }
359  }
360 }
361 
363 {
364  // check if descriptor packet is valid
365  if (_descriptor[0] == RPLIDAR_PREAMBLE && _descriptor[1] == 0x5A) {
366 
367  if (_descriptor[2] == 0x05 && _descriptor[3] == 0x00 && _descriptor[4] == 0x00 && _descriptor[5] == 0x40 && _descriptor[6] == 0x81) {
368  // payload is SCAN measurement data
370  static_assert(sizeof(payload.sensor_scan) == 5, "Unexpected payload.sensor_scan data structure size");
372  Debug(2, "Measurement response detected");
375  }
376  if (_descriptor[2] == 0x03 && _descriptor[3] == 0x00 && _descriptor[4] == 0x00 && _descriptor[5] == 0x00 && _descriptor[6] == 0x06) {
377  // payload is health data
379  static_assert(sizeof(payload.sensor_health) == 3, "Unexpected payload.sensor_health data structure size");
383  }
384  return;
385  }
386  Debug(1, "Invalid response descriptor");
388 }
389 
391 {
392  switch (_response_type){
393  case ResponseType_SCAN:
394  Debug(2, "UART %02x %02x%02x %02x%02x", payload[0], payload[2], payload[1], payload[4], payload[3]); //show HEX values
395  // check if valid SCAN packet: a valid packet starts with startbits which are complementary plus a checkbit in byte+1
397  const float angle_deg = payload.sensor_scan.angle_q6/64.0f;
398  const float distance_m = (payload.sensor_scan.distance_q2/4000.0f);
399 #if RP_DEBUG_LEVEL >= 2
400  const float quality = payload.sensor_scan.quality;
401  Debug(2, " D%02.2f A%03.1f Q%02d", distance_m, angle_deg, quality);
402 #endif
404  uint8_t sector;
405  if (convert_angle_to_sector(angle_deg, sector)) {
406  if (distance_m > distance_min()) {
407  if (_last_sector == sector) {
408  if (_distance_m_last > distance_m) {
409  _distance_m_last = distance_m;
410  _angle_deg_last = angle_deg;
411  }
412  } else {
413  // a new sector started, the previous one can be updated now
417  // update boundary used for avoidance
419  // initialize the new sector
420  _last_sector = sector;
421  _distance_m_last = distance_m;
422  _angle_deg_last = angle_deg;
423  }
424  } else {
425  _distance_valid[sector] = false;
426  }
427  }
428  } else {
429  // not valid payload packet
430  Debug(1, "Invalid Payload");
431  _sync_error++;
432  }
433  break;
434 
435  case ResponseType_Health:
436  // health issue if status is "3" ->HW error
437  if (payload.sensor_health.status == 3) {
438  Debug(1, "LIDAR Error");
439  }
440  break;
441 
442  default:
443  // no valid payload packets recognized: return payload data=0
444  Debug(1, "Unknown LIDAR packet");
445  break;
446  }
447 }
static AP_SerialManager serial_manager
Definition: AHRS_Test.cpp:24
bool _distance_valid[PROXIMITY_SECTORS_MAX]
uint32_t _last_distance_received_ms
system time of last distance measurement received from sensor
#define RESYNC_TIMEOUT
union AP_Proximity_RPLidarA2::PACKED payload
float _angle[PROXIMITY_SECTORS_MAX]
virtual void begin(uint32_t baud)=0
AP_HAL::UARTDriver * _uart
Interface definition for the various Ground Control System.
uint8_t status
status definition: 0 good, 1 warning, 2 error
#define Debug(level, fmt, args ...)
uint16_t _sector_middle_deg[PROXIMITY_SECTORS_MAX]
uint8_t quality
Related the reflected laser pulse strength.
uint16_t angle_q6
Actual heading = angle_q6/64.0 Degree.
uint8_t startbit
on the first revolution 1 else 0
void set_status(AP_Proximity::Proximity_Status status)
uint32_t find_baudrate(enum SerialProtocol protocol, uint8_t instance) const
bool convert_angle_to_sector(float angle_degrees, uint8_t &sector) const
uint8_t get_ignore_area_count() const
#define RPLIDAR_CMD_SCAN
AP_Proximity_RPLidarA2(AP_Proximity &_frontend, AP_Proximity::Proximity_State &_state, AP_SerialManager &serial_manager)
float wrap_360(const T angle, float unit_mod)
Definition: AP_Math.cpp:123
float _distance[PROXIMITY_SECTORS_MAX]
#define f(i)
virtual size_t write(uint8_t)=0
uint32_t millis()
Definition: system.cpp:157
uint32_t _last_request_ms
system time of last request
virtual int16_t read()=0
virtual uint32_t available()=0
static bool detect(AP_SerialManager &serial_manager)
uint8_t _last_sector
last sector requested
uint8_t not_startbit
complementary to startbit
#define RPLIDAR_CMD_GET_DEVICE_HEALTH
uint16_t distance_q2
Actual Distance = distance_q2/4.0 mm.
bool get_next_ignore_start_or_end(uint8_t start_or_end, int16_t start_angle, int16_t &ignore_start) const
uint8_t _sector_width_deg[PROXIMITY_SECTORS_MAX]
bool get_ignore_area(uint8_t index, uint16_t &angle_deg, uint8_t &width_deg) const
void update_boundary_for_sector(uint8_t sector)
#define PROXIMITY_SECTORS_MAX
DEFINE_BYTE_ARRAY_METHODS _sensor_scan sensor_scan
#define RPLIDAR_CMD_RESET
#define RPLIDAR_PREAMBLE
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
enum ResponseType _response_type
response from the lidar
AP_HAL::UARTDriver * find_serial(enum SerialProtocol protocol, uint8_t instance) const
#define COMM_ACTIVITY_TIMEOUT_MS