rplidar_driver.cpp
Go to the documentation of this file.
1 /*
2  * RPLIDAR SDK
3  *
4  * Copyright (c) 2009 - 2014 RoboPeak Team
5  * http://www.robopeak.com
6  * Copyright (c) 2014 - 2019 Shanghai Slamtec Co., Ltd.
7  * http://www.slamtec.com
8  *
9  */
10 /*
11  * Redistribution and use in source and binary forms, with or without
12  * modification, are permitted provided that the following conditions are met:
13  *
14  * 1. Redistributions of source code must retain the above copyright notice,
15  * this list of conditions and the following disclaimer.
16  *
17  * 2. Redistributions in binary form must reproduce the above copyright notice,
18  * this list of conditions and the following disclaimer in the documentation
19  * and/or other materials provided with the distribution.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
22  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO,
23  * THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
24  * PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
25  * CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL,
26  * EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO,
27  * PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS;
28  * OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY,
29  * WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR
30  * OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE,
31  * EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
32  *
33  */
34 
35 #include "sdkcommon.h"
36 
37 #include "hal/abs_rxtx.h"
38 #include "hal/thread.h"
39 #include "hal/types.h"
40 #include "hal/assert.h"
41 #include "hal/locker.h"
42 #include "hal/socket.h"
43 #include "hal/event.h"
44 #include "rplidar_driver_impl.h"
45 #include "rplidar_driver_serial.h"
46 #include "rplidar_driver_TCP.h"
47 
48 #include <algorithm>
49 
50 #ifndef min
51 #define min(a,b) (((a) < (b)) ? (a) : (b))
52 #endif
53 
54 namespace rp { namespace standalone{ namespace rplidar {
55 
56 #define DEPRECATED_WARN(fn, replacement) do { \
57  static bool __shown__ = false; \
58  if (!__shown__) { \
59  printDeprecationWarn(fn, replacement); \
60  __shown__ = true; \
61  } \
62  } while (0)
63 
64  static void printDeprecationWarn(const char* fn, const char* replacement)
65  {
66  fprintf(stderr, "*WARN* YOU ARE USING DEPRECATED API: %s, PLEASE MOVE TO %s\n", fn, replacement);
67  }
68 
69 static void convert(const rplidar_response_measurement_node_t& from, rplidar_response_measurement_node_hq_t& to)
70 {
71  to.angle_z_q14 = (((from.angle_q6_checkbit) >> RPLIDAR_RESP_MEASUREMENT_ANGLE_SHIFT) << 8) / 90; //transfer to q14 Z-angle
72  to.dist_mm_q2 = from.distance_q2;
73  to.flag = (from.sync_quality & RPLIDAR_RESP_MEASUREMENT_SYNCBIT); // trasfer syncbit to HQ flag field
74  to.quality = (from.sync_quality >> RPLIDAR_RESP_MEASUREMENT_QUALITY_SHIFT) << RPLIDAR_RESP_MEASUREMENT_QUALITY_SHIFT; //remove the last two bits and then make quality from 0-63 to 0-255
75 }
76 
77 static void convert(const rplidar_response_measurement_node_hq_t& from, rplidar_response_measurement_node_t& to)
78 {
80  to.angle_q6_checkbit = 1 | (((from.angle_z_q14 * 90) >> 8) << RPLIDAR_RESP_MEASUREMENT_ANGLE_SHIFT);
81  to.distance_q2 = from.dist_mm_q2 > _u16(-1) ? _u16(0) : _u16(from.dist_mm_q2);
82 }
83 
84 // Factory Impl
86 {
87  switch (drivertype) {
89  return new RPlidarDriverSerial();
90  case DRIVER_TYPE_TCP:
91  return new RPlidarDriverTCP();
92  default:
93  return NULL;
94  }
95 }
96 
97 
99 {
100  delete drv;
101 }
102 
103 
105  : _isConnected(false)
106  , _isScanning(false)
107  , _isSupportingMotorCtrl(false)
108 {
113 }
114 
116 {
117  return _isConnected;
118 }
119 
120 
122 {
123  u_result ans;
124 
125  {
127 
128  if (IS_FAIL(ans = _sendCommand(RPLIDAR_CMD_RESET))) {
129  return ans;
130  }
131  }
132  return RESULT_OK;
133 }
134 
136 {
137  if (!isConnected()) return RESULT_OPERATION_FAIL;
138 
139  _chanDev->flush();
140 
141  return RESULT_OK;
142 }
143 
144 u_result RPlidarDriverImplCommon::_waitResponseHeader(rplidar_ans_header_t * header, _u32 timeout)
145 {
146  int recvPos = 0;
147  _u32 startTs = getms();
148  _u8 recvBuffer[sizeof(rplidar_ans_header_t)];
149  _u8 *headerBuffer = reinterpret_cast<_u8 *>(header);
150  _u32 waitTime;
151 
152  while ((waitTime=getms() - startTs) <= timeout) {
153  size_t remainSize = sizeof(rplidar_ans_header_t) - recvPos;
154  size_t recvSize;
155 
156  bool ans = _chanDev->waitfordata(remainSize, timeout - waitTime, &recvSize);
157  if(!ans) return RESULT_OPERATION_TIMEOUT;
158 
159  if(recvSize > remainSize) recvSize = remainSize;
160 
161  recvSize = _chanDev->recvdata(recvBuffer, recvSize);
162 
163  for (size_t pos = 0; pos < recvSize; ++pos) {
164  _u8 currentByte = recvBuffer[pos];
165  switch (recvPos) {
166  case 0:
167  if (currentByte != RPLIDAR_ANS_SYNC_BYTE1) {
168  continue;
169  }
170 
171  break;
172  case 1:
173  if (currentByte != RPLIDAR_ANS_SYNC_BYTE2) {
174  recvPos = 0;
175  continue;
176  }
177  break;
178  }
179  headerBuffer[recvPos++] = currentByte;
180 
181  if (recvPos == sizeof(rplidar_ans_header_t)) {
182  return RESULT_OK;
183  }
184  }
185  }
186 
188 }
189 
190 
191 u_result RPlidarDriverImplCommon::getHealth(rplidar_response_device_health_t & healthinfo, _u32 timeout)
192 {
193  u_result ans;
194 
195  if (!isConnected()) return RESULT_OPERATION_FAIL;
196 
198 
199  {
201 
203  return ans;
204  }
205 
206  rplidar_ans_header_t response_header;
207  if (IS_FAIL(ans = _waitResponseHeader(&response_header, timeout))) {
208  return ans;
209  }
210 
211  // verify whether we got a correct header
212  if (response_header.type != RPLIDAR_ANS_TYPE_DEVHEALTH) {
213  return RESULT_INVALID_DATA;
214  }
215 
216  _u32 header_size = (response_header.size_q30_subtype & RPLIDAR_ANS_HEADER_SIZE_MASK);
217  if ( header_size < sizeof(rplidar_response_device_health_t)) {
218  return RESULT_INVALID_DATA;
219  }
220 
221  if (!_chanDev->waitfordata(header_size, timeout)) {
223  }
224  _chanDev->recvdata(reinterpret_cast<_u8 *>(&healthinfo), sizeof(healthinfo));
225  }
226  return RESULT_OK;
227 }
228 
229 
230 
231 u_result RPlidarDriverImplCommon::getDeviceInfo(rplidar_response_device_info_t & info, _u32 timeout)
232 {
233  u_result ans;
234 
235  if (!isConnected()) return RESULT_OPERATION_FAIL;
236 
238 
239  {
241 
243  return ans;
244  }
245 
246  rplidar_ans_header_t response_header;
247  if (IS_FAIL(ans = _waitResponseHeader(&response_header, timeout))) {
248  return ans;
249  }
250 
251  // verify whether we got a correct header
252  if (response_header.type != RPLIDAR_ANS_TYPE_DEVINFO) {
253  return RESULT_INVALID_DATA;
254  }
255 
256  _u32 header_size = (response_header.size_q30_subtype & RPLIDAR_ANS_HEADER_SIZE_MASK);
257  if (header_size < sizeof(rplidar_response_device_info_t)) {
258  return RESULT_INVALID_DATA;
259  }
260 
261  if (!_chanDev->waitfordata(header_size, timeout)) {
263  }
264  _chanDev->recvdata(reinterpret_cast<_u8 *>(&info), sizeof(info));
265  if ((info.model >> 4) > RPLIDAR_TOF_MINUM_MAJOR_ID){
266  _isTofLidar = true;
267  }else {
268  _isTofLidar = false;
269  }
270  }
271  return RESULT_OK;
272 }
273 
275 {
276  isTofLidar = _isTofLidar;
277  return RESULT_OK;
278 }
279 
280 u_result RPlidarDriverImplCommon::getFrequency(bool inExpressMode, size_t count, float & frequency, bool & is4kmode)
281 {
282  DEPRECATED_WARN("getFrequency(bool,size_t,float&,bool&)", "getFrequency(const RplidarScanMode&,size_t,float&)");
283 
284  _u16 sample_duration = inExpressMode?_cached_sampleduration_express:_cached_sampleduration_std;
285  frequency = 1000000.0f/(count * sample_duration);
286 
287  if (sample_duration <= 277) {
288  is4kmode = true;
289  } else {
290  is4kmode = false;
291  }
292 
293  return RESULT_OK;
294 }
295 
296 u_result RPlidarDriverImplCommon::getFrequency(const RplidarScanMode& scanMode, size_t count, float & frequency)
297 {
298  float sample_duration = scanMode.us_per_sample;
299  frequency = 1000000.0f / (count * sample_duration);
300  return RESULT_OK;
301 }
302 
303 u_result RPlidarDriverImplCommon::_waitNode(rplidar_response_measurement_node_t * node, _u32 timeout)
304 {
305  int recvPos = 0;
306  _u32 startTs = getms();
307  _u8 recvBuffer[sizeof(rplidar_response_measurement_node_t)];
308  _u8 *nodeBuffer = (_u8*)node;
309  _u32 waitTime;
310 
311  while ((waitTime=getms() - startTs) <= timeout) {
312  size_t remainSize = sizeof(rplidar_response_measurement_node_t) - recvPos;
313  size_t recvSize;
314 
315  bool ans = _chanDev->waitfordata(remainSize, timeout-waitTime, &recvSize);
316  if(!ans) return RESULT_OPERATION_FAIL;
317 
318  if (recvSize > remainSize) recvSize = remainSize;
319 
320  recvSize = _chanDev->recvdata(recvBuffer, recvSize);
321 
322  for (size_t pos = 0; pos < recvSize; ++pos) {
323  _u8 currentByte = recvBuffer[pos];
324  switch (recvPos) {
325  case 0: // expect the sync bit and its reverse in this byte
326  {
327  _u8 tmp = (currentByte>>1);
328  if ( (tmp ^ currentByte) & 0x1 ) {
329  // pass
330  } else {
331  continue;
332  }
333 
334  }
335  break;
336  case 1: // expect the highest bit to be 1
337  {
338  if (currentByte & RPLIDAR_RESP_MEASUREMENT_CHECKBIT) {
339  // pass
340  } else {
341  recvPos = 0;
342  continue;
343  }
344  }
345  break;
346  }
347  nodeBuffer[recvPos++] = currentByte;
348 
349  if (recvPos == sizeof(rplidar_response_measurement_node_t)) {
350  return RESULT_OK;
351  }
352  }
353  }
354 
356 }
357 
358 u_result RPlidarDriverImplCommon::_waitScanData(rplidar_response_measurement_node_t * nodebuffer, size_t & count, _u32 timeout)
359 {
360  if (!_isConnected) {
361  count = 0;
362  return RESULT_OPERATION_FAIL;
363  }
364 
365  size_t recvNodeCount = 0;
366  _u32 startTs = getms();
367  _u32 waitTime;
368  u_result ans;
369 
370  while ((waitTime = getms() - startTs) <= timeout && recvNodeCount < count) {
371  rplidar_response_measurement_node_t node;
372  if (IS_FAIL(ans = _waitNode(&node, timeout - waitTime))) {
373  return ans;
374  }
375 
376  nodebuffer[recvNodeCount++] = node;
377 
378  if (recvNodeCount == count) return RESULT_OK;
379  }
380  count = recvNodeCount;
382 }
383 
384 
385 u_result RPlidarDriverImplCommon::_waitCapsuledNode(rplidar_response_capsule_measurement_nodes_t & node, _u32 timeout)
386 {
387  int recvPos = 0;
388  _u32 startTs = getms();
389  _u8 recvBuffer[sizeof(rplidar_response_capsule_measurement_nodes_t)];
390  _u8 *nodeBuffer = (_u8*)&node;
391  _u32 waitTime;
392 
393 
394  while ((waitTime=getms() - startTs) <= timeout) {
395  size_t remainSize = sizeof(rplidar_response_capsule_measurement_nodes_t) - recvPos;
396  size_t recvSize;
397 
398  bool ans = _chanDev->waitfordata(remainSize, timeout-waitTime, &recvSize);
399  if(!ans)
400  {
402  }
403  if (recvSize > remainSize) recvSize = remainSize;
404 
405  recvSize = _chanDev->recvdata(recvBuffer, recvSize);
406 
407  for (size_t pos = 0; pos < recvSize; ++pos) {
408  _u8 currentByte = recvBuffer[pos];
409 
410  switch (recvPos) {
411  case 0: // expect the sync bit 1
412  {
413  _u8 tmp = (currentByte>>4);
415  // pass
416  } else {
418  continue;
419  }
420 
421  }
422  break;
423  case 1: // expect the sync bit 2
424  {
425  _u8 tmp = (currentByte>>4);
427  // pass
428  } else {
429  recvPos = 0;
431  continue;
432  }
433  }
434  break;
435  }
436  nodeBuffer[recvPos++] = currentByte;
437  if (recvPos == sizeof(rplidar_response_capsule_measurement_nodes_t)) {
438  // calc the checksum ...
439  _u8 checksum = 0;
440  _u8 recvChecksum = ((node.s_checksum_1 & 0xF) | (node.s_checksum_2<<4));
441  for (size_t cpos = offsetof(rplidar_response_capsule_measurement_nodes_t, start_angle_sync_q6);
442  cpos < sizeof(rplidar_response_capsule_measurement_nodes_t); ++cpos)
443  {
444  checksum ^= nodeBuffer[cpos];
445  }
446  if (recvChecksum == checksum)
447  {
448  // only consider vaild if the checksum matches...
449  if (node.start_angle_sync_q6 & RPLIDAR_RESP_MEASUREMENT_EXP_SYNCBIT)
450  {
451  // this is the first capsule frame in logic, discard the previous cached data...
453  return RESULT_OK;
454  }
455  return RESULT_OK;
456  }
458  return RESULT_INVALID_DATA;
459  }
460  }
461  }
464 }
465 
466 u_result RPlidarDriverImplCommon::_waitUltraCapsuledNode(rplidar_response_ultra_capsule_measurement_nodes_t & node, _u32 timeout)
467 {
468  if (!_isConnected) {
469  return RESULT_OPERATION_FAIL;
470  }
471 
472  int recvPos = 0;
473  _u32 startTs = getms();
474  _u8 recvBuffer[sizeof(rplidar_response_ultra_capsule_measurement_nodes_t)];
475  _u8 *nodeBuffer = (_u8*)&node;
476  _u32 waitTime;
477 
478  while ((waitTime=getms() - startTs) <= timeout) {
479  size_t remainSize = sizeof(rplidar_response_ultra_capsule_measurement_nodes_t) - recvPos;
480  size_t recvSize;
481 
482  bool ans = _chanDev->waitfordata(remainSize, timeout-waitTime, &recvSize);
483  if(!ans)
484  {
486  }
487  if (recvSize > remainSize) recvSize = remainSize;
488 
489  recvSize = _chanDev->recvdata(recvBuffer, recvSize);
490 
491  for (size_t pos = 0; pos < recvSize; ++pos) {
492  _u8 currentByte = recvBuffer[pos];
493  switch (recvPos) {
494  case 0: // expect the sync bit 1
495  {
496  _u8 tmp = (currentByte>>4);
498  // pass
499  }
500  else {
502  continue;
503  }
504  }
505  break;
506  case 1: // expect the sync bit 2
507  {
508  _u8 tmp = (currentByte>>4);
510  // pass
511  }
512  else {
513  recvPos = 0;
515  continue;
516  }
517  }
518  break;
519  }
520  nodeBuffer[recvPos++] = currentByte;
521  if (recvPos == sizeof(rplidar_response_ultra_capsule_measurement_nodes_t)) {
522  // calc the checksum ...
523  _u8 checksum = 0;
524  _u8 recvChecksum = ((node.s_checksum_1 & 0xF) | (node.s_checksum_2 << 4));
525 
526  for (size_t cpos = offsetof(rplidar_response_ultra_capsule_measurement_nodes_t, start_angle_sync_q6);
527  cpos < sizeof(rplidar_response_ultra_capsule_measurement_nodes_t); ++cpos)
528  {
529  checksum ^= nodeBuffer[cpos];
530  }
531 
532  if (recvChecksum == checksum)
533  {
534  // only consider vaild if the checksum matches...
535  if (node.start_angle_sync_q6 & RPLIDAR_RESP_MEASUREMENT_EXP_SYNCBIT)
536  {
537  // this is the first capsule frame in logic, discard the previous cached data...
539  return RESULT_OK;
540  }
541  return RESULT_OK;
542  }
544  return RESULT_INVALID_DATA;
545  }
546  }
547  }
550 }
551 
553 {
554  rplidar_response_measurement_node_t local_buf[128];
555  size_t count = 128;
557  size_t scan_count = 0;
558  u_result ans;
559  memset(local_scan, 0, sizeof(local_scan));
560 
561  _waitScanData(local_buf, count); // // always discard the first data since it may be incomplete
562 
563  while(_isScanning)
564  {
565  if (IS_FAIL(ans=_waitScanData(local_buf, count))) {
566  if (ans != RESULT_OPERATION_TIMEOUT) {
567  _isScanning = false;
568  return RESULT_OPERATION_FAIL;
569  }
570  }
571 
572  for (size_t pos = 0; pos < count; ++pos)
573  {
574  if (local_buf[pos].sync_quality & RPLIDAR_RESP_MEASUREMENT_SYNCBIT)
575  {
576  // only publish the data when it contains a full 360 degree scan
577 
578  if ((local_scan[0].flag & RPLIDAR_RESP_MEASUREMENT_SYNCBIT)) {
579  _lock.lock();
580  memcpy(_cached_scan_node_hq_buf, local_scan, scan_count*sizeof(rplidar_response_measurement_node_hq_t));
581  _cached_scan_node_hq_count = scan_count;
582  _dataEvt.set();
583  _lock.unlock();
584  }
585  scan_count = 0;
586  }
587 
589  convert(local_buf[pos], nodeHq);
590  local_scan[scan_count++] = nodeHq;
591  if (scan_count == _countof(local_scan)) scan_count-=1; // prevent overflow
592 
593  //for interval retrieve
594  {
598  }
599  }
600  }
601  _isScanning = false;
602  return RESULT_OK;
603 }
604 
606 {
607  u_result ans;
608  if (!isConnected()) return RESULT_OPERATION_FAIL;
609  if (_isScanning) return RESULT_ALREADY_DONE;
610 
611  stop(); //force the previous operation to stop
612 
613  {
615 
617  return ans;
618  }
619 
620  // waiting for confirmation
621  rplidar_ans_header_t response_header;
622  if (IS_FAIL(ans = _waitResponseHeader(&response_header, timeout))) {
623  return ans;
624  }
625 
626  // verify whether we got a correct header
627  if (response_header.type != RPLIDAR_ANS_TYPE_MEASUREMENT) {
628  return RESULT_INVALID_DATA;
629  }
630 
631  _u32 header_size = (response_header.size_q30_subtype & RPLIDAR_ANS_HEADER_SIZE_MASK);
632  if (header_size < sizeof(rplidar_response_measurement_node_t)) {
633  return RESULT_INVALID_DATA;
634  }
635 
636  _isScanning = true;
638  if (_cachethread.getHandle() == 0) {
639  return RESULT_OPERATION_FAIL;
640  }
641  }
642  return RESULT_OK;
643 }
644 
646 {
647  DEPRECATED_WARN("checkExpressScanSupported(bool&,_u32)", "getAllSupportedScanModes()");
648 
649  rplidar_response_device_info_t devinfo;
650 
651  support = false;
652  u_result ans = getDeviceInfo(devinfo, timeout);
653 
654  if (IS_FAIL(ans)) return ans;
655 
656  if (devinfo.firmware_version >= ((0x1<<8) | 17)) {
657  support = true;
658  rplidar_response_sample_rate_t sample_rate;
659  getSampleDuration_uS(sample_rate);
660  _cached_sampleduration_express = sample_rate.express_sample_duration_us;
661  _cached_sampleduration_std = sample_rate.std_sample_duration_us;
662  }
663 
664  return RESULT_OK;
665 }
666 
668 {
669  rplidar_response_capsule_measurement_nodes_t capsule_node;
671  size_t count = 128;
673  size_t scan_count = 0;
674  u_result ans;
675  memset(local_scan, 0, sizeof(local_scan));
676 
677  _waitCapsuledNode(capsule_node); // // always discard the first data since it may be incomplete
678 
679 
680 
681 
682  while(_isScanning)
683  {
684  if (IS_FAIL(ans=_waitCapsuledNode(capsule_node))) {
685  if (ans != RESULT_OPERATION_TIMEOUT && ans != RESULT_INVALID_DATA) {
686  _isScanning = false;
687  return RESULT_OPERATION_FAIL;
688  } else {
689  // current data is invalid, do not use it.
690  continue;
691  }
692  }
693  switch (_cached_express_flag)
694  {
695  case 0:
696  _capsuleToNormal(capsule_node, local_buf, count);
697  break;
698  case 1:
699  _dense_capsuleToNormal(capsule_node, local_buf, count);
700  break;
701  }
702  //
703 
704  for (size_t pos = 0; pos < count; ++pos)
705  {
706  if (local_buf[pos].flag & RPLIDAR_RESP_MEASUREMENT_SYNCBIT)
707  {
708  // only publish the data when it contains a full 360 degree scan
709 
710  if ((local_scan[0].flag & RPLIDAR_RESP_MEASUREMENT_SYNCBIT)) {
711  _lock.lock();
712  memcpy(_cached_scan_node_hq_buf, local_scan, scan_count*sizeof(rplidar_response_measurement_node_hq_t));
713  _cached_scan_node_hq_count = scan_count;
714  _dataEvt.set();
715  _lock.unlock();
716  }
717  scan_count = 0;
718  }
719  local_scan[scan_count++] = local_buf[pos];
720  if (scan_count == _countof(local_scan)) scan_count-=1; // prevent overflow
721 
722  //for interval retrieve
723  {
727  }
728  }
729  }
730  _isScanning = false;
731 
732  return RESULT_OK;
733 }
734 
736 {
737  rplidar_response_ultra_capsule_measurement_nodes_t ultra_capsule_node;
739  size_t count = 128;
741  size_t scan_count = 0;
742  u_result ans;
743  memset(local_scan, 0, sizeof(local_scan));
744 
745  _waitUltraCapsuledNode(ultra_capsule_node);
746 
747  while(_isScanning)
748  {
749  if (IS_FAIL(ans=_waitUltraCapsuledNode(ultra_capsule_node))) {
750  if (ans != RESULT_OPERATION_TIMEOUT && ans != RESULT_INVALID_DATA) {
751  _isScanning = false;
752  return RESULT_OPERATION_FAIL;
753  } else {
754  // current data is invalid, do not use it.
755  continue;
756  }
757  }
758 
759  _ultraCapsuleToNormal(ultra_capsule_node, local_buf, count);
760 
761  for (size_t pos = 0; pos < count; ++pos)
762  {
763  if (local_buf[pos].flag & RPLIDAR_RESP_MEASUREMENT_SYNCBIT)
764  {
765  // only publish the data when it contains a full 360 degree scan
766 
767  if ((local_scan[0].flag & RPLIDAR_RESP_MEASUREMENT_SYNCBIT)) {
768  _lock.lock();
769  memcpy(_cached_scan_node_hq_buf, local_scan, scan_count*sizeof(rplidar_response_measurement_node_hq_t));
770  _cached_scan_node_hq_count = scan_count;
771  _dataEvt.set();
772  _lock.unlock();
773  }
774  scan_count = 0;
775  }
776  local_scan[scan_count++] = local_buf[pos];
777  if (scan_count == _countof(local_scan)) scan_count-=1; // prevent overflow
778 
779  //for interval retrieve
780  {
784  }
785  }
786  }
787 
788  _isScanning = false;
789 
790  return RESULT_OK;
791 }
792 
793 void RPlidarDriverImplCommon::_capsuleToNormal(const rplidar_response_capsule_measurement_nodes_t & capsule, rplidar_response_measurement_node_hq_t *nodebuffer, size_t &nodeCount)
794 {
795  nodeCount = 0;
797  int diffAngle_q8;
798  int currentStartAngle_q8 = ((capsule.start_angle_sync_q6 & 0x7FFF)<< 2);
799  int prevStartAngle_q8 = ((_cached_previous_capsuledata.start_angle_sync_q6 & 0x7FFF) << 2);
800 
801  diffAngle_q8 = (currentStartAngle_q8) - (prevStartAngle_q8);
802  if (prevStartAngle_q8 > currentStartAngle_q8) {
803  diffAngle_q8 += (360<<8);
804  }
805 
806  int angleInc_q16 = (diffAngle_q8 << 3);
807  int currentAngle_raw_q16 = (prevStartAngle_q8 << 8);
808  for (size_t pos = 0; pos < _countof(_cached_previous_capsuledata.cabins); ++pos)
809  {
810  int dist_q2[2];
811  int angle_q6[2];
812  int syncBit[2];
813 
814  dist_q2[0] = (_cached_previous_capsuledata.cabins[pos].distance_angle_1 & 0xFFFC);
815  dist_q2[1] = (_cached_previous_capsuledata.cabins[pos].distance_angle_2 & 0xFFFC);
816 
817  int angle_offset1_q3 = ( (_cached_previous_capsuledata.cabins[pos].offset_angles_q3 & 0xF) | ((_cached_previous_capsuledata.cabins[pos].distance_angle_1 & 0x3)<<4));
818  int angle_offset2_q3 = ( (_cached_previous_capsuledata.cabins[pos].offset_angles_q3 >> 4) | ((_cached_previous_capsuledata.cabins[pos].distance_angle_2 & 0x3)<<4));
819 
820  angle_q6[0] = ((currentAngle_raw_q16 - (angle_offset1_q3<<13))>>10);
821  syncBit[0] = (( (currentAngle_raw_q16 + angleInc_q16) % (360<<16)) < angleInc_q16 )?1:0;
822  currentAngle_raw_q16 += angleInc_q16;
823 
824 
825  angle_q6[1] = ((currentAngle_raw_q16 - (angle_offset2_q3<<13))>>10);
826  syncBit[1] = (( (currentAngle_raw_q16 + angleInc_q16) % (360<<16)) < angleInc_q16 )?1:0;
827  currentAngle_raw_q16 += angleInc_q16;
828 
829  for (int cpos = 0; cpos < 2; ++cpos) {
830 
831  if (angle_q6[cpos] < 0) angle_q6[cpos] += (360<<6);
832  if (angle_q6[cpos] >= (360<<6)) angle_q6[cpos] -= (360<<6);
833 
835 
836  node.angle_z_q14 = _u16((angle_q6[cpos] << 8) / 90);
837  node.flag = (syncBit[cpos] | ((!syncBit[cpos]) << 1));
838  node.quality = dist_q2[cpos] ? (0x2f << RPLIDAR_RESP_MEASUREMENT_QUALITY_SHIFT) : 0;
839  node.dist_mm_q2 = dist_q2[cpos];
840 
841  nodebuffer[nodeCount++] = node;
842  }
843 
844  }
845  }
846 
849 }
850 
851 void RPlidarDriverImplCommon::_dense_capsuleToNormal(const rplidar_response_capsule_measurement_nodes_t & capsule, rplidar_response_measurement_node_hq_t *nodebuffer, size_t &nodeCount)
852 {
853  const rplidar_response_dense_capsule_measurement_nodes_t *dense_capsule = reinterpret_cast<const rplidar_response_dense_capsule_measurement_nodes_t*>(&capsule);
854  nodeCount = 0;
856  int diffAngle_q8;
857  int currentStartAngle_q8 = ((dense_capsule->start_angle_sync_q6 & 0x7FFF) << 2);
858  int prevStartAngle_q8 = ((_cached_previous_dense_capsuledata.start_angle_sync_q6 & 0x7FFF) << 2);
859 
860  diffAngle_q8 = (currentStartAngle_q8)-(prevStartAngle_q8);
861  if (prevStartAngle_q8 > currentStartAngle_q8) {
862  diffAngle_q8 += (360 << 8);
863  }
864 
865  int angleInc_q16 = (diffAngle_q8 << 8)/40;
866  int currentAngle_raw_q16 = (prevStartAngle_q8 << 8);
867  for (size_t pos = 0; pos < _countof(_cached_previous_dense_capsuledata.cabins); ++pos)
868  {
869  int dist_q2;
870  int angle_q6;
871  int syncBit;
872  const int dist = static_cast<const int>(_cached_previous_dense_capsuledata.cabins[pos].distance);
873  dist_q2 = dist << 2;
874  angle_q6 = (currentAngle_raw_q16 >> 10);
875  syncBit = (((currentAngle_raw_q16 + angleInc_q16) % (360 << 16)) < angleInc_q16) ? 1 : 0;
876  currentAngle_raw_q16 += angleInc_q16;
877 
878  if (angle_q6 < 0) angle_q6 += (360 << 6);
879  if (angle_q6 >= (360 << 6)) angle_q6 -= (360 << 6);
880 
881 
882 
884 
885  node.angle_z_q14 = _u16((angle_q6 << 8) / 90);
886  node.flag = (syncBit | ((!syncBit) << 1));
887  node.quality = dist_q2 ? (0x2f << RPLIDAR_RESP_MEASUREMENT_QUALITY_SHIFT) : 0;
888  node.dist_mm_q2 = dist_q2;
889 
890  nodebuffer[nodeCount++] = node;
891 
892 
893  }
894  }
895 
896  _cached_previous_dense_capsuledata = *dense_capsule;
898 }
899 
901 {
902  rplidar_response_hq_capsule_measurement_nodes_t hq_node;
904  size_t count = 128;
906  size_t scan_count = 0;
907  u_result ans;
908  memset(local_scan, 0, sizeof(local_scan));
909  _waitHqNode(hq_node);
910  while (_isScanning) {
911  if (IS_FAIL(ans = _waitHqNode(hq_node))) {
912  if (ans != RESULT_OPERATION_TIMEOUT && ans != RESULT_INVALID_DATA) {
913  _isScanning = false;
914  return RESULT_OPERATION_FAIL;
915  }
916  else {
917  // current data is invalid, do not use it.
918  continue;
919  }
920  }
921 
922  _HqToNormal(hq_node, local_buf, count);
923  for (size_t pos = 0; pos < count; ++pos)
924  {
925  if (local_buf[pos].flag & RPLIDAR_RESP_MEASUREMENT_SYNCBIT)
926  {
927  // only publish the data when it contains a full 360 degree scan
928  if ((local_scan[0].flag & RPLIDAR_RESP_MEASUREMENT_SYNCBIT)) {
929  _lock.lock();
930  memcpy(_cached_scan_node_hq_buf, local_scan, scan_count * sizeof(rplidar_response_measurement_node_hq_t));
931  _cached_scan_node_hq_count = scan_count;
932  _dataEvt.set();
933  _lock.unlock();
934  }
935  scan_count = 0;
936  }
937  local_scan[scan_count++] = local_buf[pos];
938  if (scan_count == _countof(local_scan)) scan_count -= 1; // prevent overflow
939  //for interval retrieve
940  {
944  }
945  }
946 
947  }
948  return RESULT_OK;
949 }
950 
951 //CRC calculate
952 static _u32 table[256];//crc32_table
953 
954 //reflect
955 static _u32 _bitrev(_u32 input, _u16 bw)
956 {
957  _u16 i;
958  _u32 var;
959  var = 0;
960  for (i = 0; i<bw; i++){
961  if (input & 0x01)
962  {
963  var |= 1 << (bw - 1 - i);
964  }
965  input >>= 1;
966  }
967  return var;
968 }
969 
970 // crc32_table init
971 static void _crc32_init(_u32 poly)
972 {
973  _u16 i;
974  _u16 j;
975  _u32 c;
976 
977  poly = _bitrev(poly, 32);
978  for (i = 0; i<256; i++){
979  c = i;
980  for (j = 0; j<8; j++){
981  if (c & 1)
982  c = poly ^ (c >> 1);
983  else
984  c = c >> 1;
985  }
986  table[i] = c;
987  }
988 }
989 
990 static _u32 _crc32cal(_u32 crc, void* input, _u16 len)
991 {
992  _u16 i;
993  _u8 index;
994  _u8* pch;
995  pch = (unsigned char*)input;
996  _u8 leftBytes = 4 - len & 0x3;
997 
998  for (i = 0; i<len; i++){
999  index = (unsigned char)(crc^*pch);
1000  crc = (crc >> 8) ^ table[index];
1001  pch++;
1002  }
1003 
1004  for (i = 0; i < leftBytes; i++) {//zero padding
1005  index = (unsigned char)(crc^0);
1006  crc = (crc >> 8) ^ table[index];
1007  }
1008  return crc^0xffffffff;
1009 }
1010 
1011 //crc32cal
1012 static u_result _crc32(_u8 *ptr, _u32 len) {
1013  static _u8 tmp;
1014  if (tmp != 1) {
1015  _crc32_init(0x4C11DB7);
1016  tmp = 1;
1017  }
1018 
1019  return _crc32cal(0xFFFFFFFF, ptr,len);
1020 }
1021 
1022 u_result RPlidarDriverImplCommon::_waitHqNode(rplidar_response_hq_capsule_measurement_nodes_t & node, _u32 timeout)
1023 {
1024  if (!_isConnected) {
1025  return RESULT_OPERATION_FAIL;
1026  }
1027 
1028  int recvPos = 0;
1029  _u32 startTs = getms();
1030  _u8 recvBuffer[sizeof(rplidar_response_hq_capsule_measurement_nodes_t)];
1031  _u8 *nodeBuffer = (_u8*)&node;
1032  _u32 waitTime;
1033 
1034  while ((waitTime=getms() - startTs) <= timeout) {
1035  size_t remainSize = sizeof(rplidar_response_hq_capsule_measurement_nodes_t) - recvPos;
1036  size_t recvSize;
1037 
1038  bool ans = _chanDev->waitfordata(remainSize, timeout-waitTime, &recvSize);
1039  if(!ans)
1040  {
1041  return RESULT_OPERATION_TIMEOUT;
1042  }
1043  if (recvSize > remainSize) recvSize = remainSize;
1044 
1045  recvSize = _chanDev->recvdata(recvBuffer, recvSize);
1046 
1047  for (size_t pos = 0; pos < recvSize; ++pos) {
1048  _u8 currentByte = recvBuffer[pos];
1049  switch (recvPos) {
1050  case 0: // expect the sync byte
1051  {
1052  _u8 tmp = (currentByte);
1053  if ( tmp == RPLIDAR_RESP_MEASUREMENT_HQ_SYNC ) {
1054  // pass
1055  }
1056  else {
1057  recvPos = 0;
1058  _is_previous_HqdataRdy = false;
1059  continue;
1060  }
1061  }
1062  break;
1063  case sizeof(rplidar_response_hq_capsule_measurement_nodes_t) - 1 - 4:
1064  {
1065 
1066  }
1067  break;
1068  case sizeof(rplidar_response_hq_capsule_measurement_nodes_t) - 1:
1069  {
1070 
1071  }
1072  break;
1073  }
1074  nodeBuffer[recvPos++] = currentByte;
1075  if (recvPos == sizeof(rplidar_response_hq_capsule_measurement_nodes_t)) {
1076  _u32 crcCalc2 = _crc32(nodeBuffer, sizeof(rplidar_response_hq_capsule_measurement_nodes_t) - 4);
1077 
1078  if(crcCalc2 == node.crc32){
1079  _is_previous_HqdataRdy = true;
1080  return RESULT_OK;
1081  }
1082  else {
1083  _is_previous_HqdataRdy = false;
1084  return RESULT_INVALID_DATA;
1085  }
1086 
1087  }
1088  }
1089  }
1090  _is_previous_HqdataRdy = false;
1091  return RESULT_OPERATION_TIMEOUT;
1092 }
1093 
1094 void RPlidarDriverImplCommon::_HqToNormal(const rplidar_response_hq_capsule_measurement_nodes_t & node_hq, rplidar_response_measurement_node_hq_t *nodebuffer, size_t &nodeCount)
1095 {
1096  nodeCount = 0;
1097  if (_is_previous_HqdataRdy) {
1098  for (size_t pos = 0; pos < _countof(_cached_previous_Hqdata.node_hq); ++pos)
1099  {
1100  nodebuffer[nodeCount++] = node_hq.node_hq[pos];
1101  }
1102  }
1104  _is_previous_HqdataRdy = true;
1105 
1106 }
1107 //*******************************************HQ support********************************//
1108 
1109 static _u32 _varbitscale_decode(_u32 scaled, _u32 & scaleLevel)
1110 {
1111  static const _u32 VBS_SCALED_BASE[] = {
1116  0,
1117  };
1118 
1119  static const _u32 VBS_SCALED_LVL[] = {
1120  4,
1121  3,
1122  2,
1123  1,
1124  0,
1125  };
1126 
1127  static const _u32 VBS_TARGET_BASE[] = {
1132  0,
1133  };
1134 
1135  for (size_t i = 0; i < _countof(VBS_SCALED_BASE); ++i)
1136  {
1137  int remain = ((int)scaled - (int)VBS_SCALED_BASE[i]);
1138  if (remain >= 0) {
1139  scaleLevel = VBS_SCALED_LVL[i];
1140  return VBS_TARGET_BASE[i] + (remain << scaleLevel);
1141  }
1142  }
1143  return 0;
1144 }
1145 
1146 void RPlidarDriverImplCommon::_ultraCapsuleToNormal(const rplidar_response_ultra_capsule_measurement_nodes_t & capsule, rplidar_response_measurement_node_hq_t *nodebuffer, size_t &nodeCount)
1147 {
1148  nodeCount = 0;
1150  int diffAngle_q8;
1151  int currentStartAngle_q8 = ((capsule.start_angle_sync_q6 & 0x7FFF) << 2);
1152  int prevStartAngle_q8 = ((_cached_previous_ultracapsuledata.start_angle_sync_q6 & 0x7FFF) << 2);
1153 
1154  diffAngle_q8 = (currentStartAngle_q8)-(prevStartAngle_q8);
1155  if (prevStartAngle_q8 > currentStartAngle_q8) {
1156  diffAngle_q8 += (360 << 8);
1157  }
1158 
1159  int angleInc_q16 = (diffAngle_q8 << 3) / 3;
1160  int currentAngle_raw_q16 = (prevStartAngle_q8 << 8);
1161  for (size_t pos = 0; pos < _countof(_cached_previous_ultracapsuledata.ultra_cabins); ++pos)
1162  {
1163  int dist_q2[3];
1164  int angle_q6[3];
1165  int syncBit[3];
1166 
1167 
1168  _u32 combined_x3 = _cached_previous_ultracapsuledata.ultra_cabins[pos].combined_x3;
1169 
1170  // unpack ...
1171  int dist_major = (combined_x3 & 0xFFF);
1172 
1173  // signed partical integer, using the magic shift here
1174  // DO NOT TOUCH
1175 
1176  int dist_predict1 = (((int)(combined_x3 << 10)) >> 22);
1177  int dist_predict2 = (((int)combined_x3) >> 22);
1178 
1179  int dist_major2;
1180 
1181  _u32 scalelvl1, scalelvl2;
1182 
1183  // prefetch next ...
1184  if (pos == _countof(_cached_previous_ultracapsuledata.ultra_cabins) - 1)
1185  {
1186  dist_major2 = (capsule.ultra_cabins[0].combined_x3 & 0xFFF);
1187  }
1188  else {
1189  dist_major2 = (_cached_previous_ultracapsuledata.ultra_cabins[pos + 1].combined_x3 & 0xFFF);
1190  }
1191 
1192  // decode with the var bit scale ...
1193  dist_major = _varbitscale_decode(dist_major, scalelvl1);
1194  dist_major2 = _varbitscale_decode(dist_major2, scalelvl2);
1195 
1196 
1197  int dist_base1 = dist_major;
1198  int dist_base2 = dist_major2;
1199 
1200  if ((!dist_major) && dist_major2) {
1201  dist_base1 = dist_major2;
1202  scalelvl1 = scalelvl2;
1203  }
1204 
1205 
1206  dist_q2[0] = (dist_major << 2);
1207  if ((dist_predict1 == 0xFFFFFE00) || (dist_predict1 == 0x1FF)) {
1208  dist_q2[1] = 0;
1209  } else {
1210  dist_predict1 = (dist_predict1 << scalelvl1);
1211  dist_q2[1] = (dist_predict1 + dist_base1) << 2;
1212 
1213  }
1214 
1215  if ((dist_predict2 == 0xFFFFFE00) || (dist_predict2 == 0x1FF)) {
1216  dist_q2[2] = 0;
1217  } else {
1218  dist_predict2 = (dist_predict2 << scalelvl2);
1219  dist_q2[2] = (dist_predict2 + dist_base2) << 2;
1220  }
1221 
1222 
1223  for (int cpos = 0; cpos < 3; ++cpos)
1224  {
1225 
1226  syncBit[cpos] = (((currentAngle_raw_q16 + angleInc_q16) % (360 << 16)) < angleInc_q16) ? 1 : 0;
1227 
1228  int offsetAngleMean_q16 = (int)(7.5 * 3.1415926535 * (1 << 16) / 180.0);
1229 
1230  if (dist_q2[cpos] >= (50 * 4))
1231  {
1232  const int k1 = 98361;
1233  const int k2 = int(k1 / dist_q2[cpos]);
1234 
1235  offsetAngleMean_q16 = (int)(8 * 3.1415926535 * (1 << 16) / 180) - (k2 << 6) - (k2 * k2 * k2) / 98304;
1236  }
1237 
1238  angle_q6[cpos] = ((currentAngle_raw_q16 - int(offsetAngleMean_q16 * 180 / 3.14159265)) >> 10);
1239  currentAngle_raw_q16 += angleInc_q16;
1240 
1241  if (angle_q6[cpos] < 0) angle_q6[cpos] += (360 << 6);
1242  if (angle_q6[cpos] >= (360 << 6)) angle_q6[cpos] -= (360 << 6);
1243 
1245 
1246  node.flag = (syncBit[cpos] | ((!syncBit[cpos]) << 1));
1247  node.quality = dist_q2[cpos] ? (0x2F << RPLIDAR_RESP_MEASUREMENT_QUALITY_SHIFT) : 0;
1248  node.angle_z_q14 = _u16((angle_q6[cpos] << 8) / 90);
1249  node.dist_mm_q2 = dist_q2[cpos];
1250 
1251  nodebuffer[nodeCount++] = node;
1252  }
1253 
1254  }
1255  }
1256 
1259 }
1260 
1262 {
1263  u_result ans;
1264 
1265  rplidar_response_device_info_t devinfo;
1266  ans = getDeviceInfo(devinfo, timeoutInMs);
1267  if (IS_FAIL(ans)) return ans;
1268 
1269  // if lidar firmware >= 1.24
1270  if (devinfo.firmware_version >= ((0x1 << 8) | 24)) {
1271  outSupport = true;
1272  }
1273  return ans;
1274 }
1275 
1276 u_result RPlidarDriverImplCommon::getLidarConf(_u32 type, std::vector<_u8> &outputBuf, const std::vector<_u8> &reserve, _u32 timeout)
1277 {
1278  rplidar_payload_get_scan_conf_t query;
1279  memset(&query, 0, sizeof(query));
1280  query.type = type;
1281  int sizeVec = reserve.size();
1282 
1283  int maxLen = sizeof(query.reserved) / sizeof(query.reserved[0]);
1284  if (sizeVec > maxLen) sizeVec = maxLen;
1285 
1286  if (sizeVec > 0)
1287  memcpy(query.reserved, &reserve[0], reserve.size());
1288 
1289  u_result ans;
1290  {
1292  if (IS_FAIL(ans = _sendCommand(RPLIDAR_CMD_GET_LIDAR_CONF, &query, sizeof(query)))) {
1293  return ans;
1294  }
1295 
1296  // waiting for confirmation
1297  rplidar_ans_header_t response_header;
1298  if (IS_FAIL(ans = _waitResponseHeader(&response_header, timeout))) {
1299  return ans;
1300  }
1301 
1302  // verify whether we got a correct header
1303  if (response_header.type != RPLIDAR_ANS_TYPE_GET_LIDAR_CONF) {
1304  return RESULT_INVALID_DATA;
1305  }
1306 
1307  _u32 header_size = (response_header.size_q30_subtype & RPLIDAR_ANS_HEADER_SIZE_MASK);
1308  if (header_size < sizeof(type)) {
1309  return RESULT_INVALID_DATA;
1310  }
1311 
1312  if (!_chanDev->waitfordata(header_size, timeout)) {
1313  return RESULT_OPERATION_TIMEOUT;
1314  }
1315 
1316  std::vector<_u8> dataBuf;
1317  dataBuf.resize(header_size);
1318  _chanDev->recvdata(reinterpret_cast<_u8 *>(&dataBuf[0]), header_size);
1319 
1320  //check if returned type is same as asked type
1321  _u32 replyType = -1;
1322  memcpy(&replyType, &dataBuf[0], sizeof(type));
1323  if (replyType != type) {
1324  return RESULT_INVALID_DATA;
1325  }
1326 
1327  //copy all the payload into &outputBuf
1328  int payLoadLen = header_size - sizeof(type);
1329 
1330  //do consistency check
1331  if (payLoadLen <= 0) {
1332  return RESULT_INVALID_DATA;
1333  }
1334  //copy all payLoadLen bytes to outputBuf
1335  outputBuf.resize(payLoadLen);
1336  memcpy(&outputBuf[0], &dataBuf[0] + sizeof(type), payLoadLen);
1337  }
1338  return ans;
1339 }
1340 
1342 {
1343  u_result ans;
1344  std::vector<_u8> answer;
1345  bool lidarSupportConfigCmds = false;
1346  ans = checkSupportConfigCommands(lidarSupportConfigCmds);
1347  if (IS_FAIL(ans)) return RESULT_INVALID_DATA;
1348 
1349  if (lidarSupportConfigCmds)
1350  {
1351  ans = getLidarConf(RPLIDAR_CONF_SCAN_MODE_TYPICAL, answer, std::vector<_u8>(), timeoutInMs);
1352  if (IS_FAIL(ans)) {
1353  return ans;
1354  }
1355  if (answer.size() < sizeof(_u16)) {
1356  return RESULT_INVALID_DATA;
1357  }
1358 
1359  const _u16 *p_answer = reinterpret_cast<const _u16*>(&answer[0]);
1360  outMode = *p_answer;
1361  return ans;
1362  }
1363  //old version of triangle lidar
1364  else
1365  {
1367  return ans;
1368  }
1369  return ans;
1370 }
1371 
1372 u_result RPlidarDriverImplCommon::getLidarSampleDuration(float& sampleDurationRes, _u16 scanModeID, _u32 timeoutInMs)
1373 {
1374  u_result ans;
1375  std::vector<_u8> reserve(2);
1376  memcpy(&reserve[0], &scanModeID, sizeof(scanModeID));
1377 
1378  std::vector<_u8> answer;
1379  ans = getLidarConf(RPLIDAR_CONF_SCAN_MODE_US_PER_SAMPLE, answer, reserve, timeoutInMs);
1380  if (IS_FAIL(ans))
1381  {
1382  return ans;
1383  }
1384  if (answer.size() < sizeof(_u32))
1385  {
1386  return RESULT_INVALID_DATA;
1387  }
1388  const _u32 *result = reinterpret_cast<const _u32*>(&answer[0]);
1389  sampleDurationRes = (float)(*result >> 8);
1390  return ans;
1391 }
1392 
1393 u_result RPlidarDriverImplCommon::getMaxDistance(float &maxDistance, _u16 scanModeID, _u32 timeoutInMs)
1394 {
1395  u_result ans;
1396  std::vector<_u8> reserve(2);
1397  memcpy(&reserve[0], &scanModeID, sizeof(scanModeID));
1398 
1399  std::vector<_u8> answer;
1400  ans = getLidarConf(RPLIDAR_CONF_SCAN_MODE_MAX_DISTANCE, answer, reserve, timeoutInMs);
1401  if (IS_FAIL(ans))
1402  {
1403  return ans;
1404  }
1405  if (answer.size() < sizeof(_u32))
1406  {
1407  return RESULT_INVALID_DATA;
1408  }
1409  const _u32 *result = reinterpret_cast<const _u32*>(&answer[0]);
1410  maxDistance = (float)(*result >> 8);
1411  return ans;
1412 }
1413 
1415 {
1416  u_result ans;
1417  std::vector<_u8> reserve(2);
1418  memcpy(&reserve[0], &scanModeID, sizeof(scanModeID));
1419 
1420  std::vector<_u8> answer;
1421  ans = getLidarConf(RPLIDAR_CONF_SCAN_MODE_ANS_TYPE, answer, reserve, timeoutInMs);
1422  if (IS_FAIL(ans))
1423  {
1424  return ans;
1425  }
1426  if (answer.size() < sizeof(_u8))
1427  {
1428  return RESULT_INVALID_DATA;
1429  }
1430  const _u8 *result = reinterpret_cast<const _u8*>(&answer[0]);
1431  ansType = *result;
1432  return ans;
1433 }
1434 
1435 u_result RPlidarDriverImplCommon::getScanModeName(char* modeName, _u16 scanModeID, _u32 timeoutInMs)
1436 {
1437  u_result ans;
1438  std::vector<_u8> reserve(2);
1439  memcpy(&reserve[0], &scanModeID, sizeof(scanModeID));
1440 
1441  std::vector<_u8> answer;
1442  ans = getLidarConf(RPLIDAR_CONF_SCAN_MODE_NAME, answer, reserve, timeoutInMs);
1443  if (IS_FAIL(ans))
1444  {
1445  return ans;
1446  }
1447  int len = answer.size();
1448  if (0 == len) return RESULT_INVALID_DATA;
1449  memcpy(modeName, &answer[0], len);
1450  return ans;
1451 }
1452 
1453 u_result RPlidarDriverImplCommon::getAllSupportedScanModes(std::vector<RplidarScanMode>& outModes, _u32 timeoutInMs)
1454 {
1455  u_result ans;
1456  bool confProtocolSupported = false;
1457  ans = checkSupportConfigCommands(confProtocolSupported);
1458  if (IS_FAIL(ans)) return RESULT_INVALID_DATA;
1459 
1460  if (confProtocolSupported)
1461  {
1462  // 1. get scan mode count
1463  _u16 modeCount;
1464  ans = getScanModeCount(modeCount);
1465  if (IS_FAIL(ans))
1466  {
1467  return RESULT_INVALID_DATA;
1468  }
1469  // 2. for loop to get all fields of each scan mode
1470  for (_u16 i = 0; i < modeCount; i++)
1471  {
1472  RplidarScanMode scanModeInfoTmp;
1473  memset(&scanModeInfoTmp, 0, sizeof(scanModeInfoTmp));
1474  scanModeInfoTmp.id = i;
1475  ans = getLidarSampleDuration(scanModeInfoTmp.us_per_sample, i);
1476  if (IS_FAIL(ans))
1477  {
1478  return RESULT_INVALID_DATA;
1479  }
1480  ans = getMaxDistance(scanModeInfoTmp.max_distance, i);
1481  if (IS_FAIL(ans))
1482  {
1483  return RESULT_INVALID_DATA;
1484  }
1485  ans = getScanModeAnsType(scanModeInfoTmp.ans_type, i);
1486  if (IS_FAIL(ans))
1487  {
1488  return RESULT_INVALID_DATA;
1489  }
1490  ans = getScanModeName(scanModeInfoTmp.scan_mode, i);
1491  if (IS_FAIL(ans))
1492  {
1493  return RESULT_INVALID_DATA;
1494  }
1495  outModes.push_back(scanModeInfoTmp);
1496  }
1497  return ans;
1498  }
1499  else
1500  {
1501  rplidar_response_sample_rate_t sampleRateTmp;
1502  ans = getSampleDuration_uS(sampleRateTmp);
1503  if (IS_FAIL(ans)) return RESULT_INVALID_DATA;
1504  //judge if support express scan
1505  bool ifSupportExpScan = false;
1506  ans = checkExpressScanSupported(ifSupportExpScan);
1507  if (IS_FAIL(ans)) return RESULT_INVALID_DATA;
1508 
1509  RplidarScanMode stdScanModeInfo;
1510  stdScanModeInfo.id = RPLIDAR_CONF_SCAN_COMMAND_STD;
1511  stdScanModeInfo.us_per_sample = sampleRateTmp.std_sample_duration_us;
1512  stdScanModeInfo.max_distance = 16;
1513  stdScanModeInfo.ans_type = RPLIDAR_ANS_TYPE_MEASUREMENT;
1514  strcpy(stdScanModeInfo.scan_mode, "Standard");
1515  outModes.push_back(stdScanModeInfo);
1516  if (ifSupportExpScan)
1517  {
1518  RplidarScanMode expScanModeInfo;
1519  expScanModeInfo.id = RPLIDAR_CONF_SCAN_COMMAND_EXPRESS;
1520  expScanModeInfo.us_per_sample = sampleRateTmp.express_sample_duration_us;
1521  expScanModeInfo.max_distance = 16;
1523  strcpy(expScanModeInfo.scan_mode, "Express");
1524  outModes.push_back(expScanModeInfo);
1525  }
1526  return ans;
1527  }
1528  return ans;
1529 }
1530 
1532 {
1533  u_result ans;
1534  std::vector<_u8> answer;
1535  ans = getLidarConf(RPLIDAR_CONF_SCAN_MODE_COUNT, answer, std::vector<_u8>(), timeoutInMs);
1536 
1537  if (IS_FAIL(ans)) {
1538  return ans;
1539  }
1540  if (answer.size() < sizeof(_u16)) {
1541  return RESULT_INVALID_DATA;
1542  }
1543  const _u16 *p_answer = reinterpret_cast<const _u16*>(&answer[0]);
1544  modeCount = *p_answer;
1545 
1546  return ans;
1547 }
1548 
1549 
1550 u_result RPlidarDriverImplCommon::startScan(bool force, bool useTypicalScan, _u32 options, RplidarScanMode* outUsedScanMode)
1551 {
1552  if(_isScanning)return RESULT_ALREADY_DONE;
1553  u_result ans;
1554 
1555  bool ifSupportLidarConf = false;
1556  ans = checkSupportConfigCommands(ifSupportLidarConf);
1557  if (IS_FAIL(ans)) return RESULT_INVALID_DATA;
1558 
1559  if (useTypicalScan)
1560  {
1561  //if support lidar config protocol
1562  if (ifSupportLidarConf)
1563  {
1564  _u16 typicalMode;
1565  ans = getTypicalScanMode(typicalMode);
1566  if (IS_FAIL(ans)) return RESULT_INVALID_DATA;
1567 
1568  //call startScanExpress to do the job
1569  return startScanExpress(false, typicalMode, 0, outUsedScanMode);
1570  }
1571  //if old version of triangle lidar
1572  else
1573  {
1574  bool isExpScanSupported = false;
1575  ans = checkExpressScanSupported(isExpScanSupported);
1576  if (IS_FAIL(ans)) {
1577  return ans;
1578  }
1579  if (isExpScanSupported)
1580  {
1581  return startScanExpress(false, RPLIDAR_CONF_SCAN_COMMAND_EXPRESS, 0, outUsedScanMode);
1582  }
1583  }
1584  }
1585 
1586  // 'useTypicalScan' is false, just use normal scan mode
1587  if(ifSupportLidarConf)
1588  {
1589  if(outUsedScanMode)
1590  {
1591  outUsedScanMode->id = RPLIDAR_CONF_SCAN_COMMAND_STD;
1592  ans = getLidarSampleDuration(outUsedScanMode->us_per_sample, outUsedScanMode->id);
1593  if(IS_FAIL(ans))
1594  {
1595  return RESULT_INVALID_DATA;
1596  }
1597 
1598  ans = getMaxDistance(outUsedScanMode->max_distance, outUsedScanMode->id);
1599  if(IS_FAIL(ans))
1600  {
1601  return RESULT_INVALID_DATA;
1602  }
1603 
1604  ans = getScanModeAnsType(outUsedScanMode->ans_type, outUsedScanMode->id);
1605  if(IS_FAIL(ans))
1606  {
1607  return RESULT_INVALID_DATA;
1608  }
1609 
1610  ans = getScanModeName(outUsedScanMode->scan_mode, outUsedScanMode->id);
1611  if(IS_FAIL(ans))
1612  {
1613  return RESULT_INVALID_DATA;
1614  }
1615  }
1616  }
1617  else
1618  {
1619  if(outUsedScanMode)
1620  {
1621  rplidar_response_sample_rate_t sampleRateTmp;
1622  ans = getSampleDuration_uS(sampleRateTmp);
1623  if(IS_FAIL(ans)) return RESULT_INVALID_DATA;
1624  outUsedScanMode->us_per_sample = sampleRateTmp.std_sample_duration_us;
1625  outUsedScanMode->max_distance = 16;
1626  outUsedScanMode->ans_type = RPLIDAR_ANS_TYPE_MEASUREMENT;
1627  strcpy(outUsedScanMode->scan_mode, "Standard");
1628  }
1629  }
1630 
1631  return startScanNormal(force);
1632 }
1633 
1634 u_result RPlidarDriverImplCommon::startScanExpress(bool force, _u16 scanMode, _u32 options, RplidarScanMode* outUsedScanMode, _u32 timeout)
1635 {
1636  u_result ans;
1637  if (!isConnected()) return RESULT_OPERATION_FAIL;
1638  if (_isScanning) return RESULT_ALREADY_DONE;
1639 
1640  stop(); //force the previous operation to stop
1641 
1642  if (scanMode == RPLIDAR_CONF_SCAN_COMMAND_STD)
1643  {
1644  return startScan(force, false, 0, outUsedScanMode);
1645  }
1646 
1647 
1648  bool ifSupportLidarConf = false;
1649  ans = checkSupportConfigCommands(ifSupportLidarConf);
1650  if (IS_FAIL(ans)) return RESULT_INVALID_DATA;
1651 
1652  if (outUsedScanMode)
1653  {
1654  outUsedScanMode->id = scanMode;
1655  if (ifSupportLidarConf)
1656  {
1657  ans = getLidarSampleDuration(outUsedScanMode->us_per_sample, outUsedScanMode->id);
1658  if (IS_FAIL(ans))
1659  {
1660  return RESULT_INVALID_DATA;
1661  }
1662 
1663  ans = getMaxDistance(outUsedScanMode->max_distance, outUsedScanMode->id);
1664  if (IS_FAIL(ans))
1665  {
1666  return RESULT_INVALID_DATA;
1667  }
1668 
1669  ans = getScanModeAnsType(outUsedScanMode->ans_type, outUsedScanMode->id);
1670  if (IS_FAIL(ans))
1671  {
1672  return RESULT_INVALID_DATA;
1673  }
1674 
1675  ans = getScanModeName(outUsedScanMode->scan_mode, outUsedScanMode->id);
1676  if (IS_FAIL(ans))
1677  {
1678  return RESULT_INVALID_DATA;
1679  }
1680 
1681 
1682  }
1683  else
1684  {
1685  rplidar_response_sample_rate_t sampleRateTmp;
1686  ans = getSampleDuration_uS(sampleRateTmp);
1687  if (IS_FAIL(ans)) return RESULT_INVALID_DATA;
1688 
1689  outUsedScanMode->us_per_sample = sampleRateTmp.express_sample_duration_us;
1690  outUsedScanMode->max_distance = 16;
1692  strcpy(outUsedScanMode->scan_mode, "Express");
1693  }
1694  }
1695 
1696  //get scan answer type to specify how to wait data
1697  _u8 scanAnsType;
1698  if (ifSupportLidarConf)
1699  {
1700  getScanModeAnsType(scanAnsType, scanMode);
1701  }
1702  else
1703  {
1705  }
1706 
1707  {
1709 
1710  rplidar_payload_express_scan_t scanReq;
1711  memset(&scanReq, 0, sizeof(scanReq));
1713  scanReq.working_mode = _u8(scanMode);
1714  scanReq.working_flags = options;
1715 
1716  if (IS_FAIL(ans = _sendCommand(RPLIDAR_CMD_EXPRESS_SCAN, &scanReq, sizeof(scanReq)))) {
1717  return ans;
1718  }
1719 
1720  // waiting for confirmation
1721  rplidar_ans_header_t response_header;
1722  if (IS_FAIL(ans = _waitResponseHeader(&response_header, timeout))) {
1723  return ans;
1724  }
1725 
1726  // verify whether we got a correct header
1727  if (response_header.type != scanAnsType) {
1728  return RESULT_INVALID_DATA;
1729  }
1730 
1731  _u32 header_size = (response_header.size_q30_subtype & RPLIDAR_ANS_HEADER_SIZE_MASK);
1732 
1733  if (scanAnsType == RPLIDAR_ANS_TYPE_MEASUREMENT_CAPSULED)
1734  {
1735  if (header_size < sizeof(rplidar_response_capsule_measurement_nodes_t)) {
1736  return RESULT_INVALID_DATA;
1737  }
1739  _isScanning = true;
1741  }
1742  else if (scanAnsType == RPLIDAR_ANS_TYPE_MEASUREMENT_DENSE_CAPSULED)
1743  {
1744  if (header_size < sizeof(rplidar_response_capsule_measurement_nodes_t)) {
1745  return RESULT_INVALID_DATA;
1746  }
1748  _isScanning = true;
1750  }
1751  else if (scanAnsType == RPLIDAR_ANS_TYPE_MEASUREMENT_HQ) {
1752  if (header_size < sizeof(rplidar_response_hq_capsule_measurement_nodes_t)) {
1753  return RESULT_INVALID_DATA;
1754  }
1755  _isScanning = true;
1757  }
1758  else
1759  {
1760  if (header_size < sizeof(rplidar_response_ultra_capsule_measurement_nodes_t)) {
1761  return RESULT_INVALID_DATA;
1762  }
1763  _isScanning = true;
1765  }
1766 
1767  if (_cachethread.getHandle() == 0) {
1768  return RESULT_OPERATION_FAIL;
1769  }
1770  }
1771  return RESULT_OK;
1772 }
1773 
1775 {
1776  u_result ans;
1778 
1779  {
1781 
1782  if (IS_FAIL(ans = _sendCommand(RPLIDAR_CMD_STOP))) {
1783  return ans;
1784  }
1785  }
1786  return RESULT_OK;
1787 }
1788 
1789 u_result RPlidarDriverImplCommon::grabScanData(rplidar_response_measurement_node_t * nodebuffer, size_t & count, _u32 timeout)
1790 {
1791  DEPRECATED_WARN("grabScanData()", "grabScanDataHq()");
1792 
1793  switch (_dataEvt.wait(timeout))
1794  {
1796  count = 0;
1797  return RESULT_OPERATION_TIMEOUT;
1799  {
1800  if(_cached_scan_node_hq_count == 0) return RESULT_OPERATION_TIMEOUT; //consider as timeout
1801 
1803 
1804  size_t size_to_copy = min(count, _cached_scan_node_hq_count);
1805 
1806  for (size_t i = 0; i < size_to_copy; i++)
1807  convert(_cached_scan_node_hq_buf[i], nodebuffer[i]);
1808 
1809  count = size_to_copy;
1811  }
1812  return RESULT_OK;
1813 
1814  default:
1815  count = 0;
1816  return RESULT_OPERATION_FAIL;
1817  }
1818 }
1819 
1821 {
1822  switch (_dataEvt.wait(timeout))
1823  {
1825  count = 0;
1826  return RESULT_OPERATION_TIMEOUT;
1828  {
1829  if (_cached_scan_node_hq_count == 0) return RESULT_OPERATION_TIMEOUT; //consider as timeout
1830 
1832 
1833  size_t size_to_copy = min(count, _cached_scan_node_hq_count);
1834  memcpy(nodebuffer, _cached_scan_node_hq_buf, size_to_copy * sizeof(rplidar_response_measurement_node_hq_t));
1835 
1836  count = size_to_copy;
1838  }
1839  return RESULT_OK;
1840 
1841  default:
1842  count = 0;
1843  return RESULT_OPERATION_FAIL;
1844  }
1845 }
1846 
1847 u_result RPlidarDriverImplCommon::getScanDataWithInterval(rplidar_response_measurement_node_t * nodebuffer, size_t & count)
1848 {
1849  DEPRECATED_WARN("getScanDataWithInterval(rplidar_response_measurement_node_t*, size_t&)", "getScanDataWithInterval(rplidar_response_measurement_node_hq_t*, size_t&)");
1850 
1851  size_t size_to_copy = 0;
1852  {
1855  {
1856  return RESULT_OPERATION_TIMEOUT;
1857  }
1858  //copy all the nodes(_cached_scan_node_count_for_interval_retrieve nodes) in _cached_scan_node_buf_for_interval_retrieve
1860  for (size_t i = 0; i < size_to_copy; i++)
1861  {
1863  }
1865  }
1866  count = size_to_copy;
1867 
1868  return RESULT_OK;
1869 }
1870 
1872 {
1873  size_t size_to_copy = 0;
1874  // Prevent crash in case lidar is not scanning - that way this function will leave nodebuffer untouched and set
1875  // count to 0.
1876  if (_isScanning)
1877  {
1880  {
1881  return RESULT_OPERATION_TIMEOUT;
1882  }
1883  // Copy at most count nodes from _cached_scan_node_buf_for_interval_retrieve
1887  // Move remaining data to the start of the array.
1889  }
1890  count = size_to_copy;
1891 
1892  // If there is remaining data, return with a warning.
1894  return RESULT_REMAINING_DATA;
1895  return RESULT_OK;
1896 }
1897 
1898 static inline float getAngle(const rplidar_response_measurement_node_t& node)
1899 {
1900  return (node.angle_q6_checkbit >> RPLIDAR_RESP_MEASUREMENT_ANGLE_SHIFT) / 64.f;
1901 }
1902 
1903 static inline void setAngle(rplidar_response_measurement_node_t& node, float v)
1904 {
1905  _u16 checkbit = node.angle_q6_checkbit & RPLIDAR_RESP_MEASUREMENT_CHECKBIT;
1906  node.angle_q6_checkbit = (((_u16)(v * 64.0f)) << RPLIDAR_RESP_MEASUREMENT_ANGLE_SHIFT) | checkbit;
1907 }
1908 
1909 static inline float getAngle(const rplidar_response_measurement_node_hq_t& node)
1910 {
1911  return node.angle_z_q14 * 90.f / 16384.f;
1912 }
1913 
1914 static inline void setAngle(rplidar_response_measurement_node_hq_t& node, float v)
1915 {
1916  node.angle_z_q14 = _u32(v * 16384.f / 90.f);
1917 }
1918 
1919 static inline _u16 getDistanceQ2(const rplidar_response_measurement_node_t& node)
1920 {
1921  return node.distance_q2;
1922 }
1923 
1925 {
1926  return node.dist_mm_q2;
1927 }
1928 
1929 template <class TNode>
1930 static bool angleLessThan(const TNode& a, const TNode& b)
1931 {
1932  return getAngle(a) < getAngle(b);
1933 }
1934 
1935 template < class TNode >
1936 static u_result ascendScanData_(TNode * nodebuffer, size_t count)
1937 {
1938  float inc_origin_angle = 360.f/count;
1939  size_t i = 0;
1940 
1941  //Tune head
1942  for (i = 0; i < count; i++) {
1943  if(getDistanceQ2(nodebuffer[i]) == 0) {
1944  continue;
1945  } else {
1946  while(i != 0) {
1947  i--;
1948  float expect_angle = getAngle(nodebuffer[i+1]) - inc_origin_angle;
1949  if (expect_angle < 0.0f) expect_angle = 0.0f;
1950  setAngle(nodebuffer[i], expect_angle);
1951  }
1952  break;
1953  }
1954  }
1955 
1956  // all the data is invalid
1957  if (i == count) return RESULT_OPERATION_FAIL;
1958 
1959  //Tune tail
1960  for (i = count - 1; i >= 0; i--) {
1961  if(getDistanceQ2(nodebuffer[i]) == 0) {
1962  continue;
1963  } else {
1964  while(i != (count - 1)) {
1965  i++;
1966  float expect_angle = getAngle(nodebuffer[i-1]) + inc_origin_angle;
1967  if (expect_angle > 360.0f) expect_angle -= 360.0f;
1968  setAngle(nodebuffer[i], expect_angle);
1969  }
1970  break;
1971  }
1972  }
1973 
1974  //Fill invalid angle in the scan
1975  float frontAngle = getAngle(nodebuffer[0]);
1976  for (i = 1; i < count; i++) {
1977  if(getDistanceQ2(nodebuffer[i]) == 0) {
1978  float expect_angle = frontAngle + i * inc_origin_angle;
1979  if (expect_angle > 360.0f) expect_angle -= 360.0f;
1980  setAngle(nodebuffer[i], expect_angle);
1981  }
1982  }
1983 
1984  // Reorder the scan according to the angle value
1985  std::sort(nodebuffer, nodebuffer + count, &angleLessThan<TNode>);
1986 
1987  return RESULT_OK;
1988 }
1989 
1990 u_result RPlidarDriverImplCommon::ascendScanData(rplidar_response_measurement_node_t * nodebuffer, size_t count)
1991 {
1992  DEPRECATED_WARN("ascendScanData(rplidar_response_measurement_node_t*, size_t)", "ascendScanData(rplidar_response_measurement_node_hq_t*, size_t)");
1993 
1994  return ascendScanData_<rplidar_response_measurement_node_t>(nodebuffer, count);
1995 }
1996 
1998 {
1999  return ascendScanData_<rplidar_response_measurement_node_hq_t>(nodebuffer, count);
2000 }
2001 
2002 u_result RPlidarDriverImplCommon::_sendCommand(_u8 cmd, const void * payload, size_t payloadsize)
2003 {
2004  _u8 pkt_header[10];
2005  rplidar_cmd_packet_t * header = reinterpret_cast<rplidar_cmd_packet_t * >(pkt_header);
2006  _u8 checksum = 0;
2007 
2008  if (!_isConnected) return RESULT_OPERATION_FAIL;
2009 
2010  if (payloadsize && payload) {
2012  }
2013 
2014  header->syncByte = RPLIDAR_CMD_SYNC_BYTE;
2015  header->cmd_flag = cmd;
2016 
2017  // send header first
2018  _chanDev->senddata(pkt_header, 2) ;
2019 
2020  if (cmd & RPLIDAR_CMDFLAG_HAS_PAYLOAD) {
2021  checksum ^= RPLIDAR_CMD_SYNC_BYTE;
2022  checksum ^= cmd;
2023  checksum ^= (payloadsize & 0xFF);
2024 
2025  // calc checksum
2026  for (size_t pos = 0; pos < payloadsize; ++pos) {
2027  checksum ^= ((_u8 *)payload)[pos];
2028  }
2029 
2030  // send size
2031  _u8 sizebyte = payloadsize;
2032  _chanDev->senddata(&sizebyte, 1);
2033 
2034  // send payload
2035  _chanDev->senddata((const _u8 *)payload, sizebyte);
2036 
2037  // send checksum
2038  _chanDev->senddata(&checksum, 1);
2039  }
2040 
2041  return RESULT_OK;
2042 }
2043 
2044 u_result RPlidarDriverImplCommon::getSampleDuration_uS(rplidar_response_sample_rate_t & rateInfo, _u32 timeout)
2045 {
2046  DEPRECATED_WARN("getSampleDuration_uS", "RplidarScanMode::us_per_sample");
2047 
2048  if (!isConnected()) return RESULT_OPERATION_FAIL;
2049 
2051 
2052  rplidar_response_device_info_t devinfo;
2053  // 1. fetch the device version first...
2054  u_result ans = getDeviceInfo(devinfo, timeout);
2055 
2056  rateInfo.express_sample_duration_us = _cached_sampleduration_express;
2057  rateInfo.std_sample_duration_us = _cached_sampleduration_std;
2058 
2059  if (devinfo.firmware_version < ((0x1<<8) | 17)) {
2060  // provide fake data...
2061 
2062  return RESULT_OK;
2063  }
2064 
2065 
2066  {
2068 
2070  return ans;
2071  }
2072 
2073  rplidar_ans_header_t response_header;
2074  if (IS_FAIL(ans = _waitResponseHeader(&response_header, timeout))) {
2075  return ans;
2076  }
2077 
2078  // verify whether we got a correct header
2079  if (response_header.type != RPLIDAR_ANS_TYPE_SAMPLE_RATE) {
2080  return RESULT_INVALID_DATA;
2081  }
2082 
2083  _u32 header_size = (response_header.size_q30_subtype & RPLIDAR_ANS_HEADER_SIZE_MASK);
2084  if ( header_size < sizeof(rplidar_response_sample_rate_t)) {
2085  return RESULT_INVALID_DATA;
2086  }
2087 
2088  if (!_chanDev->waitfordata(header_size, timeout)) {
2089  return RESULT_OPERATION_TIMEOUT;
2090  }
2091  _chanDev->recvdata(reinterpret_cast<_u8 *>(&rateInfo), sizeof(rateInfo));
2092  }
2093  return RESULT_OK;
2094 }
2095 
2097 {
2098  u_result ans;
2099  support = false;
2100 
2101  if (!isConnected()) return RESULT_OPERATION_FAIL;
2102 
2104 
2105  {
2107 
2108  rplidar_payload_acc_board_flag_t flag;
2109  flag.reserved = 0;
2110 
2111  if (IS_FAIL(ans = _sendCommand(RPLIDAR_CMD_GET_ACC_BOARD_FLAG, &flag, sizeof(flag)))) {
2112  return ans;
2113  }
2114 
2115  rplidar_ans_header_t response_header;
2116  if (IS_FAIL(ans = _waitResponseHeader(&response_header, timeout))) {
2117  return ans;
2118  }
2119 
2120  // verify whether we got a correct header
2121  if (response_header.type != RPLIDAR_ANS_TYPE_ACC_BOARD_FLAG) {
2122  return RESULT_INVALID_DATA;
2123  }
2124 
2125  _u32 header_size = (response_header.size_q30_subtype & RPLIDAR_ANS_HEADER_SIZE_MASK);
2126  if ( header_size < sizeof(rplidar_response_acc_board_flag_t)) {
2127  return RESULT_INVALID_DATA;
2128  }
2129 
2130  if (!_chanDev->waitfordata(header_size, timeout)) {
2131  return RESULT_OPERATION_TIMEOUT;
2132  }
2133  rplidar_response_acc_board_flag_t acc_board_flag;
2134  _chanDev->recvdata(reinterpret_cast<_u8 *>(&acc_board_flag), sizeof(acc_board_flag));
2135 
2136  if (acc_board_flag.support_flag & RPLIDAR_RESP_ACC_BOARD_FLAG_MOTOR_CTRL_SUPPORT_MASK) {
2137  support = true;
2138  }
2139  }
2140  return RESULT_OK;
2141 }
2142 
2144 {
2146  u_result ans;
2147  rplidar_payload_motor_pwm_t motor_pwm;
2148  motor_pwm.pwm_value = pwm;
2149 
2150  {
2152 
2153  if (IS_FAIL(ans = _sendCommand(RPLIDAR_CMD_SET_MOTOR_PWM,(const _u8 *)&motor_pwm, sizeof(motor_pwm)))) {
2154  return ans;
2155  }
2156  }
2157 
2158  return RESULT_OK;
2159 }
2160 
2161 
2163 {
2165 
2166  u_result ans;
2167  rplidar_payload_hq_spd_ctrl_t speedReq;
2168  speedReq.rpm = rpm;
2169  if (IS_FAIL(ans = _sendCommand(RPLIDAR_CMD_HQ_MOTOR_SPEED_CTRL, (const _u8 *)&speedReq, sizeof(speedReq)))) {
2170  return ans;
2171  }
2172  return RESULT_OK;
2173 }
2174 
2176 {
2177  if (!_isTofLidar) {
2178  if (_isSupportingMotorCtrl) { // RPLIDAR A2
2180  delay(500);
2181  return RESULT_OK;
2182  }
2183  else { // RPLIDAR A1
2185  _chanDev->clearDTR();
2186  delay(500);
2187  return RESULT_OK;
2188  }
2189  }
2190  else {
2191  setLidarSpinSpeed(600);//set default rpm to tof lidar
2192  return RESULT_OK;
2193  }
2194 
2195 }
2196 
2198 {
2199  if(_isTofLidar) return RESULT_OK;
2200  if (_isSupportingMotorCtrl) { // RPLIDAR A2
2201  setMotorPWM(0);
2202  delay(500);
2203  return RESULT_OK;
2204  } else { // RPLIDAR A1
2206  _chanDev->setDTR();
2207  delay(500);
2208  return RESULT_OK;
2209  }
2210 }
2211 
2213 {
2214  _isScanning = false;
2215  _cachethread.join();
2216 }
2217 
2218 // Serial Driver Impl
2219 
2221 {
2222  _chanDev = new SerialChannelDevice();
2223 }
2224 
2226 {
2227  // force disconnection
2228  disconnect();
2229 
2230  _chanDev->close();
2231  _chanDev->ReleaseRxTx();
2232 }
2233 
2235 {
2236  if (!_isConnected) return ;
2237  stop();
2238 }
2239 
2240 u_result RPlidarDriverSerial::connect(const char * port_path, _u32 baudrate, _u32 flag)
2241 {
2242  if (isConnected()) return RESULT_ALREADY_DONE;
2243 
2244  if (!_chanDev) return RESULT_INSUFFICIENT_MEMORY;
2245 
2246  {
2248 
2249  // establish the serial connection...
2250  if (!_chanDev->bind(port_path, baudrate) || !_chanDev->open()) {
2251  return RESULT_INVALID_DATA;
2252  }
2253  _chanDev->flush();
2254  }
2255 
2256  _isConnected = true;
2257 
2259  stopMotor();
2260 
2261  return RESULT_OK;
2262 }
2263 
2265 {
2266  _chanDev = new TCPChannelDevice();
2267 }
2268 
2270 {
2271  // force disconnection
2272  disconnect();
2273 }
2274 
2276 {
2277  if (!_isConnected) return ;
2278  stop();
2279  _chanDev->close();
2280 }
2281 
2283 {
2284  if (isConnected()) return RESULT_ALREADY_DONE;
2285 
2286  if (!_chanDev) return RESULT_INSUFFICIENT_MEMORY;
2287 
2288  {
2290 
2291  // establish the serial connection...
2292  if(!_chanDev->bind(ipStr, port))
2293  return RESULT_INVALID_DATA;
2294  }
2295 
2296  _isConnected = true;
2297 
2299  stopMotor();
2300 
2301  return RESULT_OK;
2302 }
2303 
2304 }}}
#define offsetof(_structure, _field)
Definition: util.h:55
#define RPLIDAR_RESP_MEASUREMENT_CHECKBIT
Definition: rplidar_cmd.h:152
virtual u_result connect(const char *ipStr, _u32 port, _u32 flag=0)
#define CLASS_THREAD(c, x)
Definition: thread.h:38
#define RPLIDAR_RESP_MEASUREMENT_EXP_SYNCBIT
Definition: rplidar_cmd.h:182
static bool angleLessThan(const TNode &a, const TNode &b)
#define RPLIDAR_ANS_TYPE_MEASUREMENT_HQ
Definition: rplidar_cmd.h:124
#define RPLIDAR_CMD_FORCE_SCAN
Definition: rplidar_cmd.h:45
#define RPLIDAR_CONF_SCAN_COMMAND_EXPRESS
Definition: rplidar_cmd.h:236
rplidar_response_measurement_node_hq_t node_hq[16]
Definition: rplidar_cmd.h:4
#define RPLIDAR_CONF_SCAN_MODE_MAX_DISTANCE
Definition: rplidar_cmd.h:251
#define RPLIDAR_CMD_GET_LIDAR_CONF
Definition: rplidar_cmd.h:60
#define min(a, b)
virtual void _capsuleToNormal(const rplidar_response_capsule_measurement_nodes_t &capsule, rplidar_response_measurement_node_hq_t *nodebuffer, size_t &nodeCount)
_u32 combined_x3
Definition: rplidar_cmd.h:4
#define RPLIDAR_ANS_TYPE_MEASUREMENT_DENSE_CAPSULED
Definition: rplidar_cmd.h:134
rplidar_response_dense_capsule_measurement_nodes_t _cached_previous_dense_capsuledata
#define RPLIDAR_RESP_MEASUREMENT_ANGLE_SHIFT
Definition: rplidar_cmd.h:153
_u8 flag
Definition: rplidar_cmd.h:2
#define RPLIDAR_ANS_TYPE_MEASUREMENT_CAPSULED
Definition: rplidar_cmd.h:123
virtual u_result setLidarSpinSpeed(_u16 rpm, _u32 timeout=DEFAULT_TIMEOUT)
_u8 payload[0]
Definition: rplidar_cmd.h:3
virtual u_result checkSupportConfigCommands(bool &outSupport, _u32 timeoutInMs=DEFAULT_TIMEOUT)
#define RPLIDAR_ANS_TYPE_GET_LIDAR_CONF
Definition: rplidar_cmd.h:132
f
virtual u_result _waitCapsuledNode(rplidar_response_capsule_measurement_nodes_t &node, _u32 timeout=DEFAULT_TIMEOUT)
#define RPLIDAR_CMD_HQ_MOTOR_SPEED_CTRL
Definition: rplidar_cmd.h:55
virtual void disconnect()
Disconnect with the RPLIDAR and close the serial port.
#define RPLIDAR_VARBITSCALE_X4_DEST_VAL
Definition: rplidar_cmd.h:287
virtual void disconnect()
Disconnect with the RPLIDAR and close the serial port.
_u16 start_angle_sync_q6
Definition: rplidar_cmd.h:4
#define RPLIDAR_ANS_TYPE_SAMPLE_RATE
Definition: rplidar_cmd.h:128
virtual u_result startScanNormal(bool force, _u32 timeout=DEFAULT_TIMEOUT)
virtual u_result _waitResponseHeader(rplidar_ans_header_t *header, _u32 timeout=DEFAULT_TIMEOUT)
virtual void _dense_capsuleToNormal(const rplidar_response_capsule_measurement_nodes_t &capsule, rplidar_response_measurement_node_hq_t *nodebuffer, size_t &nodeCount)
virtual u_result grabScanData(rplidar_response_measurement_node_t *nodebuffer, size_t &count, _u32 timeout=DEFAULT_TIMEOUT)
virtual u_result reset(_u32 timeout=DEFAULT_TIMEOUT)
_u32 result
Definition: rplidar_cmd.h:2
static void DisposeDriver(RPlidarDriver *drv)
#define RPLIDAR_VARBITSCALE_X8_SRC_BIT
Definition: rplidar_cmd.h:283
virtual void _ultraCapsuleToNormal(const rplidar_response_ultra_capsule_measurement_nodes_t &capsule, rplidar_response_measurement_node_hq_t *nodebuffer, size_t &nodeCount)
virtual u_result _waitUltraCapsuledNode(rplidar_response_ultra_capsule_measurement_nodes_t &node, _u32 timeout=DEFAULT_TIMEOUT)
#define RPLIDAR_VARBITSCALE_X2_SRC_BIT
Definition: rplidar_cmd.h:281
virtual u_result startScan(bool force, bool useTypicalScan, _u32 options=0, RplidarScanMode *outUsedScanMode=NULL)
static void printDeprecationWarn(const char *fn, const char *replacement)
rplidar_response_capsule_measurement_nodes_t _cached_previous_capsuledata
virtual u_result startScanExpress(bool force, _u16 scanMode, _u32 options=0, RplidarScanMode *outUsedScanMode=NULL, _u32 timeout=DEFAULT_TIMEOUT)
virtual void disconnect()=0
Disconnect with the RPLIDAR and close the serial port.
#define RPLIDAR_ANS_HEADER_SIZE_MASK
#define RESULT_OK
Definition: rptypes.h:102
virtual u_result connect(const char *port_path, _u32 baudrate, _u32 flag=0)
std_msgs::Header * header(M &m)
#define RPLIDAR_CMD_GET_DEVICE_INFO
Definition: rplidar_cmd.h:50
#define RPLIDAR_ANS_TYPE_DEVHEALTH
Definition: rplidar_cmd.h:119
#define RPLIDAR_CMD_SYNC_BYTE
#define RPLIDAR_RESP_MEASUREMENT_SYNCBIT
Definition: rplidar_cmd.h:147
virtual u_result getLidarConf(_u32 type, std::vector< _u8 > &outputBuf, const std::vector< _u8 > &reserve=std::vector< _u8 >(), _u32 timeout=DEFAULT_TIMEOUT)
virtual bool waitfordata(size_t data_count, _u32 timeout=-1, size_t *returned_size=NULL)=0
virtual u_result grabScanDataHq(rplidar_response_measurement_node_hq_t *nodebuffer, size_t &count, _u32 timeout=DEFAULT_TIMEOUT)
virtual bool bind(const char *, uint32_t)=0
virtual u_result getSampleDuration_uS(rplidar_response_sample_rate_t &rateInfo, _u32 timeout=DEFAULT_TIMEOUT)
static _u32 _varbitscale_decode(_u32 scaled, _u32 &scaleLevel)
#define RPLIDAR_VARBITSCALE_X16_SRC_BIT
Definition: rplidar_cmd.h:284
#define RPLIDAR_CONF_SCAN_MODE_US_PER_SAMPLE
Definition: rplidar_cmd.h:250
static void _crc32_init(_u32 poly)
#define RESULT_INSUFFICIENT_MEMORY
Definition: rptypes.h:111
#define RPLIDAR_ANS_SYNC_BYTE1
virtual u_result getScanDataWithIntervalHq(rplidar_response_measurement_node_hq_t *nodebuffer, size_t &count)
virtual u_result _sendCommand(_u8 cmd, const void *payload=NULL, size_t payloadsize=0)
#define RPLIDAR_RESP_MEASUREMENT_HQ_SYNC
Definition: rplidar_cmd.h:180
#define delay(x)
Definition: win32/timer.h:39
#define RPLIDAR_CMD_GET_SAMPLERATE
Definition: rplidar_cmd.h:53
virtual u_result getHealth(rplidar_response_device_health_t &health, _u32 timeout=DEFAULT_TIMEOUT)
virtual int senddata(const _u8 *data, size_t size)=0
#define IS_FAIL(x)
Definition: rptypes.h:114
#define RESULT_REMAINING_DATA
Definition: types.h:91
virtual u_result getScanModeName(char *modeName, _u16 scanModeID, _u32 timeoutInMs=DEFAULT_TIMEOUT)
uint8_t _u8
Definition: rptypes.h:63
virtual u_result startMotor()
Start RPLIDAR&#39;s motor when using accessory board.
#define RPLIDAR_CMD_RESET
Definition: rplidar_cmd.h:46
#define RPLIDAR_RESP_ACC_BOARD_FLAG_MOTOR_CTRL_SUPPORT_MASK
Definition: rplidar_cmd.h:137
static _u32 _crc32cal(_u32 crc, void *input, _u16 len)
virtual u_result stop(_u32 timeout=DEFAULT_TIMEOUT)
#define RPLIDAR_CMDFLAG_HAS_PAYLOAD
rplidar_response_measurement_node_hq_t _cached_scan_node_hq_buf[8192]
#define RPLIDAR_ANS_TYPE_ACC_BOARD_FLAG
Definition: rplidar_cmd.h:135
void unlock()
Definition: locker.h:117
virtual u_result getTypicalScanMode(_u16 &outMode, _u32 timeoutInMs=DEFAULT_TIMEOUT)
Get typical scan mode of lidar.
virtual u_result getFrequency(bool inExpressMode, size_t count, float &frequency, bool &is4kmode)
virtual u_result _waitNode(rplidar_response_measurement_node_t *node, _u32 timeout=DEFAULT_TIMEOUT)
static u_result ascendScanData_(TNode *nodebuffer, size_t count)
#define RPLIDAR_CMD_SET_MOTOR_PWM
Definition: rplidar_cmd.h:63
_u8 sync_quality
Definition: rplidar_cmd.h:2
#define getms()
Definition: linux/timer.h:57
static void setAngle(rplidar_response_measurement_node_t &node, float v)
#define RPLIDAR_CMD_EXPRESS_SCAN
Definition: rplidar_cmd.h:58
void set(bool isSignal=true)
Definition: event.h:70
#define RPLIDAR_CONF_SCAN_MODE_ANS_TYPE
Definition: rplidar_cmd.h:252
#define RESULT_OPERATION_TIMEOUT
Definition: rptypes.h:107
#define RPLIDAR_ANS_TYPE_MEASUREMENT
Definition: rplidar_cmd.h:121
u_result join(unsigned long timeout=-1)
#define RPLIDAR_CMD_GET_ACC_BOARD_FLAG
Definition: rplidar_cmd.h:64
#define RPLIDAR_CONF_SCAN_COMMAND_STD
Definition: rplidar_cmd.h:235
_word_size_t getHandle()
Definition: thread.h:71
virtual bool isConnected()
Returns TRUE when the connection has been established.
virtual u_result ascendScanData(rplidar_response_measurement_node_t *nodebuffer, size_t count)
static void convert(const rplidar_response_measurement_node_t &from, rplidar_response_measurement_node_hq_t &to)
_u16 rpm
Definition: rplidar_cmd.h:2
_u32 type
Definition: rplidar_cmd.h:2
rplidar_response_hq_capsule_measurement_nodes_t _cached_previous_Hqdata
virtual u_result getDeviceInfo(rplidar_response_device_info_t &info, _u32 timeout=DEFAULT_TIMEOUT)
#define RPLIDAR_RESP_MEASUREMENT_QUALITY_SHIFT
Definition: rplidar_cmd.h:148
Locker::LOCK_STATUS lock(unsigned long timeout=0xFFFFFFFF)
Definition: locker.h:60
virtual u_result getScanModeCount(_u16 &modeCount, _u32 timeoutInMs=DEFAULT_TIMEOUT)
static _u32 _bitrev(_u32 input, _u16 bw)
virtual void _HqToNormal(const rplidar_response_hq_capsule_measurement_nodes_t &node_hq, rplidar_response_measurement_node_hq_t *nodebuffer, size_t &nodeCount)
unsigned long wait(unsigned long timeout=0xFFFFFFFF)
Definition: event.h:98
#define RPLIDAR_CONF_SCAN_MODE_NAME
Definition: rplidar_cmd.h:254
uint32_t _u32
Definition: rptypes.h:69
#define RPLIDAR_CONF_SCAN_MODE_COUNT
Definition: rplidar_cmd.h:249
static float getAngle(const rplidar_response_measurement_node_t &node)
virtual u_result getAllSupportedScanModes(std::vector< RplidarScanMode > &outModes, _u32 timeoutInMs=DEFAULT_TIMEOUT)
Get all scan modes that supported by lidar.
#define RPLIDAR_RESP_MEASUREMENT_EXP_SYNC_1
Definition: rplidar_cmd.h:177
#define DEFAULT_MOTOR_PWM
Definition: rplidar_cmd.h:103
static RPlidarDriver * CreateDriver(_u32 drivertype=DRIVER_TYPE_SERIALPORT)
virtual u_result getScanDataWithInterval(rplidar_response_measurement_node_t *nodebuffer, size_t &count)
#define RESULT_OPERATION_NOT_SUPPORT
Definition: rptypes.h:109
#define RPLIDAR_VARBITSCALE_X8_DEST_VAL
Definition: rplidar_cmd.h:288
#define RPLIDAR_CONF_SCAN_MODE_TYPICAL
Definition: rplidar_cmd.h:253
virtual u_result checkExpressScanSupported(bool &support, _u32 timeout=DEFAULT_TIMEOUT)
virtual u_result _waitHqNode(rplidar_response_hq_capsule_measurement_nodes_t &node, _u32 timeout=DEFAULT_TIMEOUT)
#define RESULT_OPERATION_FAIL
Definition: rptypes.h:106
#define RPLIDAR_VARBITSCALE_X2_DEST_VAL
Definition: rplidar_cmd.h:286
virtual u_result getScanModeAnsType(_u8 &ansType, _u16 scanModeID, _u32 timeoutInMs=DEFAULT_TIMEOUT)
virtual u_result stopMotor()
Stop RPLIDAR&#39;s motor when using accessory board.
#define RESULT_ALREADY_DONE
Definition: rptypes.h:104
#define RPLIDAR_CMD_STOP
Definition: rplidar_cmd.h:43
virtual u_result getLidarSampleDuration(float &sampleDurationRes, _u16 scanModeID, _u32 timeoutInMs=DEFAULT_TIMEOUT)
#define RPLIDAR_RESP_MEASUREMENT_EXP_SYNC_2
Definition: rplidar_cmd.h:178
#define RPLIDAR_CMD_GET_DEVICE_HEALTH
Definition: rplidar_cmd.h:51
uint16_t _u16
Definition: rptypes.h:66
#define RPLIDAR_VARBITSCALE_X16_DEST_VAL
Definition: rplidar_cmd.h:289
#define DEPRECATED_WARN(fn, replacement)
rplidar_response_measurement_node_hq_t _cached_scan_node_hq_buf_for_interval_retrieve[8192]
#define RPLIDAR_ANS_SYNC_BYTE2
static u_result _crc32(_u8 *ptr, _u32 len)
#define _countof(_Array)
Definition: util.h:42
static _u16 getDistanceQ2(const rplidar_response_measurement_node_t &node)
rplidar_response_ultra_capsule_measurement_nodes_t _cached_previous_ultracapsuledata
virtual u_result getMaxDistance(float &maxDistance, _u16 scanModeID, _u32 timeoutInMs=DEFAULT_TIMEOUT)
#define RESULT_INVALID_DATA
Definition: rptypes.h:105
RPlidarDriver * drv
Definition: node.cpp:48
virtual u_result _waitScanData(rplidar_response_measurement_node_t *nodebuffer, size_t &count, _u32 timeout=DEFAULT_TIMEOUT)
uint32_t u_result
Definition: rptypes.h:100
#define RPLIDAR_ANS_TYPE_DEVINFO
Definition: rplidar_cmd.h:118
virtual u_result checkMotorCtrlSupport(bool &support, _u32 timeout=DEFAULT_TIMEOUT)
#define RPLIDAR_CMD_SCAN
Definition: rplidar_cmd.h:44
virtual u_result checkIfTofLidar(bool &isTofLidar, _u32 timeout=DEFAULT_TIMEOUT)
virtual int recvdata(unsigned char *data, size_t size)=0
#define RPLIDAR_VARBITSCALE_X4_SRC_BIT
Definition: rplidar_cmd.h:282


rplidar_ros
Author(s):
autogenerated on Wed Jan 1 2020 04:01:40