AP_Proximity_RPLidarA2.cpp 16 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448
  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. This program is distributed in the hope that it will be useful,
  7. but WITHOUT ANY WARRANTY; without even the implied warranty of
  8. MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  9. GNU General Public License for more details.
  10. You should have received a copy of the GNU General Public License
  11. along with this program. If not, see <http://www.gnu.org/licenses/>.
  12. */
  13. /*
  14. * ArduPilot device driver for SLAMTEC RPLIDAR A2 (16m range version)
  15. *
  16. * ALL INFORMATION REGARDING PROTOCOL WAS DERIVED FROM RPLIDAR DATASHEET:
  17. *
  18. * https://www.slamtec.com/en/Lidar
  19. * http://bucket.download.slamtec.com/63ac3f0d8c859d3a10e51c6b3285fcce25a47357/LR001_SLAMTEC_rplidar_protocol_v1.0_en.pdf
  20. *
  21. * Author: Steven Josefs, IAV GmbH
  22. * Based on the LightWare SF40C ArduPilot device driver from Randy Mackay
  23. *
  24. */
  25. #include <AP_HAL/AP_HAL.h>
  26. #include "AP_Proximity_RPLidarA2.h"
  27. #include <AP_SerialManager/AP_SerialManager.h>
  28. #include <ctype.h>
  29. #include <stdio.h>
  30. #define RP_DEBUG_LEVEL 0
  31. #if RP_DEBUG_LEVEL
  32. #include <GCS_MAVLink/GCS.h>
  33. #define Debug(level, fmt, args ...) do { if (level <= RP_DEBUG_LEVEL) { gcs().send_text(MAV_SEVERITY_INFO, fmt, ## args); } } while (0)
  34. #else
  35. #define Debug(level, fmt, args ...)
  36. #endif
  37. #define COMM_ACTIVITY_TIMEOUT_MS 200
  38. #define RESET_RPA2_WAIT_MS 8
  39. #define RESYNC_TIMEOUT 5000
  40. // Commands
  41. //-----------------------------------------
  42. // Commands without payload and response
  43. #define RPLIDAR_PREAMBLE 0xA5
  44. #define RPLIDAR_CMD_STOP 0x25
  45. #define RPLIDAR_CMD_SCAN 0x20
  46. #define RPLIDAR_CMD_FORCE_SCAN 0x21
  47. #define RPLIDAR_CMD_RESET 0x40
  48. // Commands without payload but have response
  49. #define RPLIDAR_CMD_GET_DEVICE_INFO 0x50
  50. #define RPLIDAR_CMD_GET_DEVICE_HEALTH 0x52
  51. // Commands with payload and have response
  52. #define RPLIDAR_CMD_EXPRESS_SCAN 0x82
  53. extern const AP_HAL::HAL& hal;
  54. /*
  55. The constructor also initialises the proximity sensor. Note that this
  56. constructor is not called until detect() returns true, so we
  57. already know that we should setup the proximity sensor
  58. */
  59. AP_Proximity_RPLidarA2::AP_Proximity_RPLidarA2(AP_Proximity &_frontend,
  60. AP_Proximity::Proximity_State &_state,
  61. AP_SerialManager &serial_manager) :
  62. AP_Proximity_Backend(_frontend, _state)
  63. {
  64. _uart = serial_manager.find_serial(AP_SerialManager::SerialProtocol_Lidar360, 0);
  65. if (_uart != nullptr) {
  66. _uart->begin(serial_manager.find_baudrate(AP_SerialManager::SerialProtocol_Lidar360, 0));
  67. }
  68. _cnt = 0 ;
  69. _sync_error = 0 ;
  70. _byte_count = 0;
  71. }
  72. // detect if a RPLidarA2 proximity sensor is connected by looking for a configured serial port
  73. bool AP_Proximity_RPLidarA2::detect(AP_SerialManager &serial_manager)
  74. {
  75. return serial_manager.find_serial(AP_SerialManager::SerialProtocol_Lidar360, 0) != nullptr;
  76. }
  77. // update the _rp_state of the sensor
  78. void AP_Proximity_RPLidarA2::update(void)
  79. {
  80. if (_uart == nullptr) {
  81. return;
  82. }
  83. // initialise sensor if necessary
  84. if (!_initialised) {
  85. _initialised = initialise(); //returns true if everything initialized properly
  86. }
  87. // if LIDAR in known state
  88. if (_initialised) {
  89. get_readings();
  90. }
  91. // check for timeout and set health status
  92. if ((_last_distance_received_ms == 0) || (AP_HAL::millis() - _last_distance_received_ms > COMM_ACTIVITY_TIMEOUT_MS)) {
  93. set_status(AP_Proximity::Proximity_NoData);
  94. Debug(1, "LIDAR NO DATA");
  95. } else {
  96. set_status(AP_Proximity::Proximity_Good);
  97. }
  98. }
  99. // get maximum distance (in meters) of sensor
  100. float AP_Proximity_RPLidarA2::distance_max() const
  101. {
  102. return 16.0f; //16m max range RPLIDAR2, if you want to support the 8m version this is the only line to change
  103. }
  104. // get minimum distance (in meters) of sensor
  105. float AP_Proximity_RPLidarA2::distance_min() const
  106. {
  107. return 0.20f; //20cm min range RPLIDAR2
  108. }
  109. bool AP_Proximity_RPLidarA2::initialise()
  110. {
  111. // initialise sectors
  112. if (!_sector_initialised) {
  113. init_sectors();
  114. return false;
  115. }
  116. if (!_initialised) {
  117. reset_rplidar(); // set to a known state
  118. Debug(1, "LIDAR initialised");
  119. return true;
  120. }
  121. return true;
  122. }
  123. void AP_Proximity_RPLidarA2::reset_rplidar()
  124. {
  125. if (_uart == nullptr) {
  126. return;
  127. }
  128. uint8_t tx_buffer[2] = {RPLIDAR_PREAMBLE, RPLIDAR_CMD_RESET};
  129. _uart->write(tx_buffer, 2);
  130. _resetted = true; ///< be aware of extra 63 bytes coming after reset containing FW information
  131. Debug(1, "LIDAR reset");
  132. // To-Do: ensure delay of 8m after sending reset request
  133. _last_reset_ms = AP_HAL::millis();
  134. _rp_state = rp_resetted;
  135. }
  136. // initialise sector angles using user defined ignore areas, left same as SF40C
  137. void AP_Proximity_RPLidarA2::init_sectors()
  138. {
  139. // use defaults if no ignore areas defined
  140. const uint8_t ignore_area_count = get_ignore_area_count();
  141. if (ignore_area_count == 0) {
  142. _sector_initialised = true;
  143. return;
  144. }
  145. uint8_t sector = 0;
  146. for (uint8_t i=0; i<ignore_area_count; i++) {
  147. // get ignore area info
  148. uint16_t ign_area_angle;
  149. uint8_t ign_area_width;
  150. if (get_ignore_area(i, ign_area_angle, ign_area_width)) {
  151. // calculate how many degrees of space we have between this end of this ignore area and the start of the end
  152. int16_t start_angle, end_angle;
  153. get_next_ignore_start_or_end(1, ign_area_angle, start_angle);
  154. get_next_ignore_start_or_end(0, start_angle, end_angle);
  155. int16_t degrees_to_fill = wrap_360(end_angle - start_angle);
  156. // divide up the area into sectors
  157. while ((degrees_to_fill > 0) && (sector < PROXIMITY_SECTORS_MAX)) {
  158. uint16_t sector_size;
  159. if (degrees_to_fill >= 90) {
  160. // set sector to maximum of 45 degrees
  161. sector_size = 45;
  162. } else if (degrees_to_fill > 45) {
  163. // use half the remaining area to optimise size of this sector and the next
  164. sector_size = degrees_to_fill / 2.0f;
  165. } else {
  166. // 45 degrees or less are left so put it all into the next sector
  167. sector_size = degrees_to_fill;
  168. }
  169. // record the sector middle and width
  170. _sector_middle_deg[sector] = wrap_360(start_angle + sector_size / 2.0f);
  171. _sector_width_deg[sector] = sector_size;
  172. // move onto next sector
  173. start_angle += sector_size;
  174. sector++;
  175. degrees_to_fill -= sector_size;
  176. }
  177. }
  178. }
  179. // set num sectors
  180. _num_sectors = sector;
  181. // re-initialise boundary because sector locations have changed
  182. init_boundary();
  183. // record success
  184. _sector_initialised = true;
  185. }
  186. // set Lidar into SCAN mode
  187. void AP_Proximity_RPLidarA2::set_scan_mode()
  188. {
  189. if (_uart == nullptr) {
  190. return;
  191. }
  192. uint8_t tx_buffer[2] = {RPLIDAR_PREAMBLE, RPLIDAR_CMD_SCAN};
  193. _uart->write(tx_buffer, 2);
  194. _last_request_ms = AP_HAL::millis();
  195. Debug(1, "LIDAR SCAN MODE ACTIVATED");
  196. _rp_state = rp_responding;
  197. }
  198. // send request for sensor health
  199. void AP_Proximity_RPLidarA2::send_request_for_health() //not called yet
  200. {
  201. if (_uart == nullptr) {
  202. return;
  203. }
  204. uint8_t tx_buffer[2] = {RPLIDAR_PREAMBLE, RPLIDAR_CMD_GET_DEVICE_HEALTH};
  205. _uart->write(tx_buffer, 2);
  206. _last_request_ms = AP_HAL::millis();
  207. _rp_state = rp_health;
  208. }
  209. void AP_Proximity_RPLidarA2::get_readings()
  210. {
  211. if (_uart == nullptr) {
  212. return;
  213. }
  214. Debug(2, " CURRENT STATE: %d ", _rp_state);
  215. uint32_t nbytes = _uart->available();
  216. while (nbytes-- > 0) {
  217. uint8_t c = _uart->read();
  218. Debug(2, "UART READ %x <%c>", c, c); //show HEX values
  219. STATE:
  220. switch(_rp_state){
  221. case rp_resetted:
  222. Debug(3, " BYTE_COUNT %d", _byte_count);
  223. if ((c == 0x52 || _information_data) && _byte_count < 62) {
  224. if (c == 0x52) {
  225. _information_data = true;
  226. }
  227. _rp_systeminfo[_byte_count] = c;
  228. Debug(3, "_rp_systeminfo[%d]=%x",_byte_count,_rp_systeminfo[_byte_count]);
  229. _byte_count++;
  230. break;
  231. } else {
  232. if (_information_data) {
  233. Debug(1, "GOT RPLIDAR INFORMATION");
  234. _information_data = false;
  235. _byte_count = 0;
  236. set_scan_mode();
  237. break;
  238. }
  239. if (_cnt>5) {
  240. _rp_state = rp_unknown;
  241. _cnt=0;
  242. break;
  243. }
  244. _cnt++;
  245. break;
  246. }
  247. break;
  248. case rp_responding:
  249. Debug(2, "RESPONDING");
  250. if (c == RPLIDAR_PREAMBLE || _descriptor_data) {
  251. _descriptor_data = true;
  252. _descriptor[_byte_count] = c;
  253. _byte_count++;
  254. // descriptor packet has 7 byte in total
  255. if (_byte_count == sizeof(_descriptor)) {
  256. Debug(2,"LIDAR DESCRIPTOR CATCHED");
  257. _response_type = ResponseType_Descriptor;
  258. // identify the payload data after the descriptor
  259. parse_response_descriptor();
  260. _byte_count = 0;
  261. }
  262. } else {
  263. _rp_state = rp_unknown;
  264. }
  265. break;
  266. case rp_measurements:
  267. if (_sync_error) {
  268. // out of 5-byte sync mask -> catch new revolution
  269. Debug(1, " OUT OF SYNC");
  270. // on first revolution bit 1 = 1, bit 2 = 0 of the first byte
  271. if ((c & 0x03) == 0x01) {
  272. _sync_error = 0;
  273. Debug(1, " RESYNC");
  274. } else {
  275. if (AP_HAL::millis() - _last_distance_received_ms > RESYNC_TIMEOUT) {
  276. reset_rplidar();
  277. }
  278. break;
  279. }
  280. }
  281. Debug(3, "READ PAYLOAD");
  282. payload[_byte_count] = c;
  283. _byte_count++;
  284. if (_byte_count == _payload_length) {
  285. Debug(2, "LIDAR MEASUREMENT CATCHED");
  286. parse_response_data();
  287. _byte_count = 0;
  288. }
  289. break;
  290. case rp_health:
  291. Debug(1, "state: HEALTH");
  292. break;
  293. case rp_unknown:
  294. Debug(1, "state: UNKNOWN");
  295. if (c == RPLIDAR_PREAMBLE) {
  296. _rp_state = rp_responding;
  297. goto STATE;
  298. break;
  299. }
  300. _cnt++;
  301. if (_cnt>10) {
  302. reset_rplidar();
  303. _rp_state = rp_resetted;
  304. _cnt=0;
  305. }
  306. break;
  307. default:
  308. Debug(1, "UNKNOWN LIDAR STATE");
  309. break;
  310. }
  311. }
  312. }
  313. void AP_Proximity_RPLidarA2::parse_response_descriptor()
  314. {
  315. // check if descriptor packet is valid
  316. if (_descriptor[0] == RPLIDAR_PREAMBLE && _descriptor[1] == 0x5A) {
  317. if (_descriptor[2] == 0x05 && _descriptor[3] == 0x00 && _descriptor[4] == 0x00 && _descriptor[5] == 0x40 && _descriptor[6] == 0x81) {
  318. // payload is SCAN measurement data
  319. _payload_length = sizeof(payload.sensor_scan);
  320. static_assert(sizeof(payload.sensor_scan) == 5, "Unexpected payload.sensor_scan data structure size");
  321. _response_type = ResponseType_SCAN;
  322. Debug(2, "Measurement response detected");
  323. _last_distance_received_ms = AP_HAL::millis();
  324. _rp_state = rp_measurements;
  325. }
  326. if (_descriptor[2] == 0x03 && _descriptor[3] == 0x00 && _descriptor[4] == 0x00 && _descriptor[5] == 0x00 && _descriptor[6] == 0x06) {
  327. // payload is health data
  328. _payload_length = sizeof(payload.sensor_health);
  329. static_assert(sizeof(payload.sensor_health) == 3, "Unexpected payload.sensor_health data structure size");
  330. _response_type = ResponseType_Health;
  331. _last_distance_received_ms = AP_HAL::millis();
  332. _rp_state= rp_health;
  333. }
  334. return;
  335. }
  336. Debug(1, "Invalid response descriptor");
  337. _rp_state = rp_unknown;
  338. }
  339. void AP_Proximity_RPLidarA2::parse_response_data()
  340. {
  341. switch (_response_type){
  342. case ResponseType_SCAN:
  343. Debug(2, "UART %02x %02x%02x %02x%02x", payload[0], payload[2], payload[1], payload[4], payload[3]); //show HEX values
  344. // check if valid SCAN packet: a valid packet starts with startbits which are complementary plus a checkbit in byte+1
  345. if ((payload.sensor_scan.startbit == !payload.sensor_scan.not_startbit) && payload.sensor_scan.checkbit) {
  346. const float angle_sign = (frontend.get_orientation(state.instance) == 1) ? -1.0f : 1.0f;
  347. const float angle_deg = wrap_360(payload.sensor_scan.angle_q6/64.0f * angle_sign + frontend.get_yaw_correction(state.instance));
  348. const float distance_m = (payload.sensor_scan.distance_q2/4000.0f);
  349. #if RP_DEBUG_LEVEL >= 2
  350. const float quality = payload.sensor_scan.quality;
  351. Debug(2, " D%02.2f A%03.1f Q%02d", distance_m, angle_deg, quality);
  352. #endif
  353. _last_distance_received_ms = AP_HAL::millis();
  354. uint8_t sector;
  355. if (convert_angle_to_sector(angle_deg, sector)) {
  356. if (distance_m > distance_min()) {
  357. if (_last_sector == sector) {
  358. if (_distance_m_last > distance_m) {
  359. _distance_m_last = distance_m;
  360. _angle_deg_last = angle_deg;
  361. }
  362. } else {
  363. // a new sector started, the previous one can be updated now
  364. _angle[_last_sector] = _angle_deg_last;
  365. _distance[_last_sector] = _distance_m_last;
  366. _distance_valid[_last_sector] = true;
  367. // update boundary used for avoidance
  368. update_boundary_for_sector(_last_sector, true);
  369. // initialize the new sector
  370. _last_sector = sector;
  371. _distance_m_last = distance_m;
  372. _angle_deg_last = angle_deg;
  373. }
  374. } else {
  375. _distance_valid[sector] = false;
  376. }
  377. }
  378. } else {
  379. // not valid payload packet
  380. Debug(1, "Invalid Payload");
  381. _sync_error++;
  382. }
  383. break;
  384. case ResponseType_Health:
  385. // health issue if status is "3" ->HW error
  386. if (payload.sensor_health.status == 3) {
  387. Debug(1, "LIDAR Error");
  388. }
  389. break;
  390. default:
  391. // no valid payload packets recognized: return payload data=0
  392. Debug(1, "Unknown LIDAR packet");
  393. break;
  394. }
  395. }