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 
135 
137 {
138  if (!isConnected()) return RESULT_OPERATION_FAIL;
139 
140  _chanDev->flush();
141 
142  return RESULT_OK;
143 }
144 
145 u_result RPlidarDriverImplCommon::_waitResponseHeader(rplidar_ans_header_t * header, _u32 timeout)
146 {
147  int recvPos = 0;
148  _u32 startTs = getms();
149  _u8 recvBuffer[sizeof(rplidar_ans_header_t)];
150  _u8 *headerBuffer = reinterpret_cast<_u8 *>(header);
151  _u32 waitTime;
152 
153  while ((waitTime=getms() - startTs) <= timeout) {
154  size_t remainSize = sizeof(rplidar_ans_header_t) - recvPos;
155  size_t recvSize;
156 
157  bool ans = _chanDev->waitfordata(remainSize, timeout - waitTime, &recvSize);
158  if(!ans) return RESULT_OPERATION_TIMEOUT;
159 
160  if(recvSize > remainSize) recvSize = remainSize;
161 
162  recvSize = _chanDev->recvdata(recvBuffer, recvSize);
163 
164  for (size_t pos = 0; pos < recvSize; ++pos) {
165  _u8 currentByte = recvBuffer[pos];
166  switch (recvPos) {
167  case 0:
168  if (currentByte != RPLIDAR_ANS_SYNC_BYTE1) {
169  continue;
170  }
171 
172  break;
173  case 1:
174  if (currentByte != RPLIDAR_ANS_SYNC_BYTE2) {
175  recvPos = 0;
176  continue;
177  }
178  break;
179  }
180  headerBuffer[recvPos++] = currentByte;
181 
182  if (recvPos == sizeof(rplidar_ans_header_t)) {
183  return RESULT_OK;
184  }
185  }
186  }
187 
189 }
190 
191 
192 
193 u_result RPlidarDriverImplCommon::getHealth(rplidar_response_device_health_t & healthinfo, _u32 timeout)
194 {
195  u_result ans;
196 
197  if (!isConnected()) return RESULT_OPERATION_FAIL;
198 
200 
201  {
203 
205  return ans;
206  }
207 
208  rplidar_ans_header_t response_header;
209  if (IS_FAIL(ans = _waitResponseHeader(&response_header, timeout))) {
210  return ans;
211  }
212 
213  // verify whether we got a correct header
214  if (response_header.type != RPLIDAR_ANS_TYPE_DEVHEALTH) {
215  return RESULT_INVALID_DATA;
216  }
217 
218  _u32 header_size = (response_header.size_q30_subtype & RPLIDAR_ANS_HEADER_SIZE_MASK);
219  if ( header_size < sizeof(rplidar_response_device_health_t)) {
220  return RESULT_INVALID_DATA;
221  }
222 
223  if (!_chanDev->waitfordata(header_size, timeout)) {
225  }
226  _chanDev->recvdata(reinterpret_cast<_u8 *>(&healthinfo), sizeof(healthinfo));
227  }
228  return RESULT_OK;
229 }
230 
231 
232 
233 u_result RPlidarDriverImplCommon::getDeviceInfo(rplidar_response_device_info_t & info, _u32 timeout)
234 {
235  u_result ans;
236 
237  if (!isConnected()) return RESULT_OPERATION_FAIL;
238 
240 
241  {
243 
245  return ans;
246  }
247 
248  rplidar_ans_header_t response_header;
249  if (IS_FAIL(ans = _waitResponseHeader(&response_header, timeout))) {
250  return ans;
251  }
252 
253  // verify whether we got a correct header
254  if (response_header.type != RPLIDAR_ANS_TYPE_DEVINFO) {
255  return RESULT_INVALID_DATA;
256  }
257 
258  _u32 header_size = (response_header.size_q30_subtype & RPLIDAR_ANS_HEADER_SIZE_MASK);
259  if (header_size < sizeof(rplidar_response_device_info_t)) {
260  return RESULT_INVALID_DATA;
261  }
262 
263  if (!_chanDev->waitfordata(header_size, timeout)) {
265  }
266  _chanDev->recvdata(reinterpret_cast<_u8 *>(&info), sizeof(info));
267  }
268  return RESULT_OK;
269 }
270 
271 u_result RPlidarDriverImplCommon::getFrequency(bool inExpressMode, size_t count, float & frequency, bool & is4kmode)
272 {
273  DEPRECATED_WARN("getFrequency(bool,size_t,float&,bool&)", "getFrequency(const RplidarScanMode&,size_t,float&)");
274 
275  _u16 sample_duration = inExpressMode?_cached_sampleduration_express:_cached_sampleduration_std;
276  frequency = 1000000.0f/(count * sample_duration);
277 
278  if (sample_duration <= 277) {
279  is4kmode = true;
280  } else {
281  is4kmode = false;
282  }
283 
284  return RESULT_OK;
285 }
286 
287 u_result RPlidarDriverImplCommon::getFrequency(const RplidarScanMode& scanMode, size_t count, float & frequency)
288 {
289  float sample_duration = scanMode.us_per_sample;
290  frequency = 1000000.0f / (count * sample_duration);
291  return RESULT_OK;
292 }
293 
294 u_result RPlidarDriverImplCommon::_waitNode(rplidar_response_measurement_node_t * node, _u32 timeout)
295 {
296  int recvPos = 0;
297  _u32 startTs = getms();
298  _u8 recvBuffer[sizeof(rplidar_response_measurement_node_t)];
299  _u8 *nodeBuffer = (_u8*)node;
300  _u32 waitTime;
301 
302  while ((waitTime=getms() - startTs) <= timeout) {
303  size_t remainSize = sizeof(rplidar_response_measurement_node_t) - recvPos;
304  size_t recvSize;
305 
306  bool ans = _chanDev->waitfordata(remainSize, timeout-waitTime, &recvSize);
307  if(!ans) return RESULT_OPERATION_FAIL;
308 
309  if (recvSize > remainSize) recvSize = remainSize;
310 
311  recvSize = _chanDev->recvdata(recvBuffer, recvSize);
312 
313  for (size_t pos = 0; pos < recvSize; ++pos) {
314  _u8 currentByte = recvBuffer[pos];
315  switch (recvPos) {
316  case 0: // expect the sync bit and its reverse in this byte
317  {
318  _u8 tmp = (currentByte>>1);
319  if ( (tmp ^ currentByte) & 0x1 ) {
320  // pass
321  } else {
322  continue;
323  }
324 
325  }
326  break;
327  case 1: // expect the highest bit to be 1
328  {
329  if (currentByte & RPLIDAR_RESP_MEASUREMENT_CHECKBIT) {
330  // pass
331  } else {
332  recvPos = 0;
333  continue;
334  }
335  }
336  break;
337  }
338  nodeBuffer[recvPos++] = currentByte;
339 
340  if (recvPos == sizeof(rplidar_response_measurement_node_t)) {
341  return RESULT_OK;
342  }
343  }
344  }
345 
347 }
348 
349 u_result RPlidarDriverImplCommon::_waitScanData(rplidar_response_measurement_node_t * nodebuffer, size_t & count, _u32 timeout)
350 {
351  if (!_isConnected) {
352  count = 0;
353  return RESULT_OPERATION_FAIL;
354  }
355 
356  size_t recvNodeCount = 0;
357  _u32 startTs = getms();
358  _u32 waitTime;
359  u_result ans;
360 
361  while ((waitTime = getms() - startTs) <= timeout && recvNodeCount < count) {
362  rplidar_response_measurement_node_t node;
363  if (IS_FAIL(ans = _waitNode(&node, timeout - waitTime))) {
364  return ans;
365  }
366 
367  nodebuffer[recvNodeCount++] = node;
368 
369  if (recvNodeCount == count) return RESULT_OK;
370  }
371  count = recvNodeCount;
373 }
374 
375 
376 u_result RPlidarDriverImplCommon::_waitCapsuledNode(rplidar_response_capsule_measurement_nodes_t & node, _u32 timeout)
377 {
378  int recvPos = 0;
379  _u32 startTs = getms();
380  _u8 recvBuffer[sizeof(rplidar_response_capsule_measurement_nodes_t)];
381  _u8 *nodeBuffer = (_u8*)&node;
382  _u32 waitTime;
383 
384 
385  while ((waitTime=getms() - startTs) <= timeout) {
386  size_t remainSize = sizeof(rplidar_response_capsule_measurement_nodes_t) - recvPos;
387  size_t recvSize;
388 
389  bool ans = _chanDev->waitfordata(remainSize, timeout-waitTime, &recvSize);
390  if(!ans)
391  {
393  }
394  if (recvSize > remainSize) recvSize = remainSize;
395 
396  recvSize = _chanDev->recvdata(recvBuffer, recvSize);
397 
398  for (size_t pos = 0; pos < recvSize; ++pos) {
399  _u8 currentByte = recvBuffer[pos];
400 
401  switch (recvPos) {
402  case 0: // expect the sync bit 1
403  {
404  _u8 tmp = (currentByte>>4);
406  // pass
407  } else {
409  continue;
410  }
411 
412  }
413  break;
414  case 1: // expect the sync bit 2
415  {
416  _u8 tmp = (currentByte>>4);
418  // pass
419  } else {
420  recvPos = 0;
422  continue;
423  }
424  }
425  break;
426  }
427  nodeBuffer[recvPos++] = currentByte;
428  if (recvPos == sizeof(rplidar_response_capsule_measurement_nodes_t)) {
429  // calc the checksum ...
430  _u8 checksum = 0;
431  _u8 recvChecksum = ((node.s_checksum_1 & 0xF) | (node.s_checksum_2<<4));
432  for (size_t cpos = offsetof(rplidar_response_capsule_measurement_nodes_t, start_angle_sync_q6);
433  cpos < sizeof(rplidar_response_capsule_measurement_nodes_t); ++cpos)
434  {
435  checksum ^= nodeBuffer[cpos];
436  }
437  if (recvChecksum == checksum)
438  {
439  // only consider vaild if the checksum matches...
440  if (node.start_angle_sync_q6 & RPLIDAR_RESP_MEASUREMENT_EXP_SYNCBIT)
441  {
442  // this is the first capsule frame in logic, discard the previous cached data...
444  return RESULT_OK;
445  }
446  return RESULT_OK;
447  }
449  return RESULT_INVALID_DATA;
450  }
451  }
452  }
455 }
456 
457 u_result RPlidarDriverImplCommon::_waitUltraCapsuledNode(rplidar_response_ultra_capsule_measurement_nodes_t & node, _u32 timeout)
458 {
459  if (!_isConnected) {
460  return RESULT_OPERATION_FAIL;
461  }
462 
463  int recvPos = 0;
464  _u32 startTs = getms();
465  _u8 recvBuffer[sizeof(rplidar_response_ultra_capsule_measurement_nodes_t)];
466  _u8 *nodeBuffer = (_u8*)&node;
467  _u32 waitTime;
468 
469  while ((waitTime=getms() - startTs) <= timeout) {
470  size_t remainSize = sizeof(rplidar_response_ultra_capsule_measurement_nodes_t) - recvPos;
471  size_t recvSize;
472 
473  bool ans = _chanDev->waitfordata(remainSize, timeout-waitTime, &recvSize);
474  if(!ans)
475  {
477  }
478  if (recvSize > remainSize) recvSize = remainSize;
479 
480  recvSize = _chanDev->recvdata(recvBuffer, recvSize);
481 
482  for (size_t pos = 0; pos < recvSize; ++pos) {
483  _u8 currentByte = recvBuffer[pos];
484  switch (recvPos) {
485  case 0: // expect the sync bit 1
486  {
487  _u8 tmp = (currentByte>>4);
489  // pass
490  }
491  else {
493  continue;
494  }
495  }
496  break;
497  case 1: // expect the sync bit 2
498  {
499  _u8 tmp = (currentByte>>4);
501  // pass
502  }
503  else {
504  recvPos = 0;
506  continue;
507  }
508  }
509  break;
510  }
511  nodeBuffer[recvPos++] = currentByte;
512  if (recvPos == sizeof(rplidar_response_ultra_capsule_measurement_nodes_t)) {
513  // calc the checksum ...
514  _u8 checksum = 0;
515  _u8 recvChecksum = ((node.s_checksum_1 & 0xF) | (node.s_checksum_2 << 4));
516 
517  for (size_t cpos = offsetof(rplidar_response_ultra_capsule_measurement_nodes_t, start_angle_sync_q6);
518  cpos < sizeof(rplidar_response_ultra_capsule_measurement_nodes_t); ++cpos)
519  {
520  checksum ^= nodeBuffer[cpos];
521  }
522 
523  if (recvChecksum == checksum)
524  {
525  // only consider vaild if the checksum matches...
526  if (node.start_angle_sync_q6 & RPLIDAR_RESP_MEASUREMENT_EXP_SYNCBIT)
527  {
528  // this is the first capsule frame in logic, discard the previous cached data...
530  return RESULT_OK;
531  }
532  return RESULT_OK;
533  }
535  return RESULT_INVALID_DATA;
536  }
537  }
538  }
541 }
542 
544 {
545  rplidar_response_measurement_node_t local_buf[128];
546  size_t count = 128;
548  size_t scan_count = 0;
549  u_result ans;
550  memset(local_scan, 0, sizeof(local_scan));
551 
552  _waitScanData(local_buf, count); // // always discard the first data since it may be incomplete
553 
554  while(_isScanning)
555  {
556  if (IS_FAIL(ans=_waitScanData(local_buf, count))) {
557  if (ans != RESULT_OPERATION_TIMEOUT) {
558  _isScanning = false;
559  return RESULT_OPERATION_FAIL;
560  }
561  }
562 
563  for (size_t pos = 0; pos < count; ++pos)
564  {
565  if (local_buf[pos].sync_quality & RPLIDAR_RESP_MEASUREMENT_SYNCBIT)
566  {
567  // only publish the data when it contains a full 360 degree scan
568 
569  if ((local_scan[0].flag & RPLIDAR_RESP_MEASUREMENT_SYNCBIT)) {
570  _lock.lock();
571  memcpy(_cached_scan_node_hq_buf, local_scan, scan_count*sizeof(rplidar_response_measurement_node_hq_t));
572  _cached_scan_node_hq_count = scan_count;
573  _dataEvt.set();
574  _lock.unlock();
575  }
576  scan_count = 0;
577  }
578 
580  convert(local_buf[pos], nodeHq);
581  local_scan[scan_count++] = nodeHq;
582  if (scan_count == _countof(local_scan)) scan_count-=1; // prevent overflow
583 
584  //for interval retrieve
585  {
589  }
590  }
591  }
592  _isScanning = false;
593  return RESULT_OK;
594 }
595 
597 {
598  u_result ans;
599  if (!isConnected()) return RESULT_OPERATION_FAIL;
600  if (_isScanning) return RESULT_ALREADY_DONE;
601 
602  stop(); //force the previous operation to stop
603 
604  {
606 
608  return ans;
609  }
610 
611  // waiting for confirmation
612  rplidar_ans_header_t response_header;
613  if (IS_FAIL(ans = _waitResponseHeader(&response_header, timeout))) {
614  return ans;
615  }
616 
617  // verify whether we got a correct header
618  if (response_header.type != RPLIDAR_ANS_TYPE_MEASUREMENT) {
619  return RESULT_INVALID_DATA;
620  }
621 
622  _u32 header_size = (response_header.size_q30_subtype & RPLIDAR_ANS_HEADER_SIZE_MASK);
623  if (header_size < sizeof(rplidar_response_measurement_node_t)) {
624  return RESULT_INVALID_DATA;
625  }
626 
627  _isScanning = true;
629  if (_cachethread.getHandle() == 0) {
630  return RESULT_OPERATION_FAIL;
631  }
632  }
633  return RESULT_OK;
634 }
635 
637 {
638  DEPRECATED_WARN("checkExpressScanSupported(bool&,_u32)", "getAllSupportedScanModes()");
639 
640  rplidar_response_device_info_t devinfo;
641 
642  support = false;
643  u_result ans = getDeviceInfo(devinfo, timeout);
644 
645  if (IS_FAIL(ans)) return ans;
646 
647  if (devinfo.firmware_version >= ((0x1<<8) | 17)) {
648  support = true;
649  rplidar_response_sample_rate_t sample_rate;
650  getSampleDuration_uS(sample_rate);
651  _cached_sampleduration_express = sample_rate.express_sample_duration_us;
652  _cached_sampleduration_std = sample_rate.std_sample_duration_us;
653  }
654 
655  return RESULT_OK;
656 }
657 
659 {
660  rplidar_response_capsule_measurement_nodes_t capsule_node;
662  size_t count = 128;
664  size_t scan_count = 0;
665  u_result ans;
666  memset(local_scan, 0, sizeof(local_scan));
667 
668  _waitCapsuledNode(capsule_node); // // always discard the first data since it may be incomplete
669 
670 
671 
672 
673  while(_isScanning)
674  {
675  if (IS_FAIL(ans=_waitCapsuledNode(capsule_node))) {
676  if (ans != RESULT_OPERATION_TIMEOUT && ans != RESULT_INVALID_DATA) {
677  _isScanning = false;
678  return RESULT_OPERATION_FAIL;
679  } else {
680  // current data is invalid, do not use it.
681  continue;
682  }
683  }
684  switch (_cached_express_flag)
685  {
686  case 0:
687  _capsuleToNormal(capsule_node, local_buf, count);
688  break;
689  case 1:
690  _dense_capsuleToNormal(capsule_node, local_buf, count);
691  break;
692  }
693  //
694 
695  for (size_t pos = 0; pos < count; ++pos)
696  {
697  if (local_buf[pos].flag & RPLIDAR_RESP_MEASUREMENT_SYNCBIT)
698  {
699  // only publish the data when it contains a full 360 degree scan
700 
701  if ((local_scan[0].flag & RPLIDAR_RESP_MEASUREMENT_SYNCBIT)) {
702  _lock.lock();
703  memcpy(_cached_scan_node_hq_buf, local_scan, scan_count*sizeof(rplidar_response_measurement_node_hq_t));
704  _cached_scan_node_hq_count = scan_count;
705  _dataEvt.set();
706  _lock.unlock();
707  }
708  scan_count = 0;
709  }
710  local_scan[scan_count++] = local_buf[pos];
711  if (scan_count == _countof(local_scan)) scan_count-=1; // prevent overflow
712 
713  //for interval retrieve
714  {
718  }
719  }
720  }
721  _isScanning = false;
722 
723  return RESULT_OK;
724 }
725 
727 {
728  rplidar_response_ultra_capsule_measurement_nodes_t ultra_capsule_node;
730  size_t count = 128;
732  size_t scan_count = 0;
733  u_result ans;
734  memset(local_scan, 0, sizeof(local_scan));
735 
736  _waitUltraCapsuledNode(ultra_capsule_node);
737 
738  while(_isScanning)
739  {
740  if (IS_FAIL(ans=_waitUltraCapsuledNode(ultra_capsule_node))) {
741  if (ans != RESULT_OPERATION_TIMEOUT && ans != RESULT_INVALID_DATA) {
742  _isScanning = false;
743  return RESULT_OPERATION_FAIL;
744  } else {
745  // current data is invalid, do not use it.
746  continue;
747  }
748  }
749 
750  _ultraCapsuleToNormal(ultra_capsule_node, local_buf, count);
751 
752  for (size_t pos = 0; pos < count; ++pos)
753  {
754  if (local_buf[pos].flag & RPLIDAR_RESP_MEASUREMENT_SYNCBIT)
755  {
756  // only publish the data when it contains a full 360 degree scan
757 
758  if ((local_scan[0].flag & RPLIDAR_RESP_MEASUREMENT_SYNCBIT)) {
759  _lock.lock();
760  memcpy(_cached_scan_node_hq_buf, local_scan, scan_count*sizeof(rplidar_response_measurement_node_hq_t));
761  _cached_scan_node_hq_count = scan_count;
762  _dataEvt.set();
763  _lock.unlock();
764  }
765  scan_count = 0;
766  }
767  local_scan[scan_count++] = local_buf[pos];
768  if (scan_count == _countof(local_scan)) scan_count-=1; // prevent overflow
769 
770  //for interval retrieve
771  {
775  }
776  }
777  }
778 
779  _isScanning = false;
780 
781  return RESULT_OK;
782 }
783 
784 void RPlidarDriverImplCommon::_capsuleToNormal(const rplidar_response_capsule_measurement_nodes_t & capsule, rplidar_response_measurement_node_hq_t *nodebuffer, size_t &nodeCount)
785 {
786  nodeCount = 0;
788  int diffAngle_q8;
789  int currentStartAngle_q8 = ((capsule.start_angle_sync_q6 & 0x7FFF)<< 2);
790  int prevStartAngle_q8 = ((_cached_previous_capsuledata.start_angle_sync_q6 & 0x7FFF) << 2);
791 
792  diffAngle_q8 = (currentStartAngle_q8) - (prevStartAngle_q8);
793  if (prevStartAngle_q8 > currentStartAngle_q8) {
794  diffAngle_q8 += (360<<8);
795  }
796 
797  int angleInc_q16 = (diffAngle_q8 << 3);
798  int currentAngle_raw_q16 = (prevStartAngle_q8 << 8);
799  for (size_t pos = 0; pos < _countof(_cached_previous_capsuledata.cabins); ++pos)
800  {
801  int dist_q2[2];
802  int angle_q6[2];
803  int syncBit[2];
804 
805  dist_q2[0] = (_cached_previous_capsuledata.cabins[pos].distance_angle_1 & 0xFFFC);
806  dist_q2[1] = (_cached_previous_capsuledata.cabins[pos].distance_angle_2 & 0xFFFC);
807 
808  int angle_offset1_q3 = ( (_cached_previous_capsuledata.cabins[pos].offset_angles_q3 & 0xF) | ((_cached_previous_capsuledata.cabins[pos].distance_angle_1 & 0x3)<<4));
809  int angle_offset2_q3 = ( (_cached_previous_capsuledata.cabins[pos].offset_angles_q3 >> 4) | ((_cached_previous_capsuledata.cabins[pos].distance_angle_2 & 0x3)<<4));
810 
811  angle_q6[0] = ((currentAngle_raw_q16 - (angle_offset1_q3<<13))>>10);
812  syncBit[0] = (( (currentAngle_raw_q16 + angleInc_q16) % (360<<16)) < angleInc_q16 )?1:0;
813  currentAngle_raw_q16 += angleInc_q16;
814 
815 
816  angle_q6[1] = ((currentAngle_raw_q16 - (angle_offset2_q3<<13))>>10);
817  syncBit[1] = (( (currentAngle_raw_q16 + angleInc_q16) % (360<<16)) < angleInc_q16 )?1:0;
818  currentAngle_raw_q16 += angleInc_q16;
819 
820  for (int cpos = 0; cpos < 2; ++cpos) {
821 
822  if (angle_q6[cpos] < 0) angle_q6[cpos] += (360<<6);
823  if (angle_q6[cpos] >= (360<<6)) angle_q6[cpos] -= (360<<6);
824 
826 
827  node.angle_z_q14 = _u16((angle_q6[cpos] << 8) / 90);
828  node.flag = (syncBit[cpos] | ((!syncBit[cpos]) << 1));
829  node.quality = dist_q2[cpos] ? (0x2f << RPLIDAR_RESP_MEASUREMENT_QUALITY_SHIFT) : 0;
830  node.dist_mm_q2 = dist_q2[cpos];
831 
832  nodebuffer[nodeCount++] = node;
833  }
834 
835  }
836  }
837 
840 }
841 
842 void RPlidarDriverImplCommon::_dense_capsuleToNormal(const rplidar_response_capsule_measurement_nodes_t & capsule, rplidar_response_measurement_node_hq_t *nodebuffer, size_t &nodeCount)
843 {
844  const rplidar_response_dense_capsule_measurement_nodes_t *dense_capsule = reinterpret_cast<const rplidar_response_dense_capsule_measurement_nodes_t*>(&capsule);
845  nodeCount = 0;
847  int diffAngle_q8;
848  int currentStartAngle_q8 = ((dense_capsule->start_angle_sync_q6 & 0x7FFF) << 2);
849  int prevStartAngle_q8 = ((_cached_previous_dense_capsuledata.start_angle_sync_q6 & 0x7FFF) << 2);
850 
851  diffAngle_q8 = (currentStartAngle_q8)-(prevStartAngle_q8);
852  if (prevStartAngle_q8 > currentStartAngle_q8) {
853  diffAngle_q8 += (360 << 8);
854  }
855 
856  int angleInc_q16 = (diffAngle_q8 << 8)/40;
857  int currentAngle_raw_q16 = (prevStartAngle_q8 << 8);
858  for (size_t pos = 0; pos < _countof(_cached_previous_dense_capsuledata.cabins); ++pos)
859  {
860  int dist_q2;
861  int angle_q6;
862  int syncBit;
863  const int dist = static_cast<const int>(_cached_previous_dense_capsuledata.cabins[pos].distance);
864  dist_q2 = dist << 2;
865  angle_q6 = (currentAngle_raw_q16 >> 10);
866  syncBit = (((currentAngle_raw_q16 + angleInc_q16) % (360 << 16)) < angleInc_q16) ? 1 : 0;
867  currentAngle_raw_q16 += angleInc_q16;
868 
869  if (angle_q6 < 0) angle_q6 += (360 << 6);
870  if (angle_q6 >= (360 << 6)) angle_q6 -= (360 << 6);
871 
872 
873 
875 
876  node.angle_z_q14 = _u16((angle_q6 << 8) / 90);
877  node.flag = (syncBit | ((!syncBit) << 1));
878  node.quality = dist_q2 ? (0x2f << RPLIDAR_RESP_MEASUREMENT_QUALITY_SHIFT) : 0;
879  node.dist_mm_q2 = dist_q2;
880 
881  nodebuffer[nodeCount++] = node;
882 
883 
884  }
885  }
886 
887  _cached_previous_dense_capsuledata = *dense_capsule;
889 }
890 
892 {
893  rplidar_response_hq_capsule_measurement_nodes_t hq_node;
895  size_t count = 128;
897  size_t scan_count = 0;
898  u_result ans;
899  memset(local_scan, 0, sizeof(local_scan));
900  _waitHqNode(hq_node);
901  while (_isScanning) {
902  if (IS_FAIL(ans = _waitHqNode(hq_node))) {
903  if (ans != RESULT_OPERATION_TIMEOUT && ans != RESULT_INVALID_DATA) {
904  _isScanning = false;
905  return RESULT_OPERATION_FAIL;
906  }
907  else {
908  // current data is invalid, do not use it.
909  continue;
910  }
911  }
912 
913  _HqToNormal(hq_node, local_buf, count);
914  for (size_t pos = 0; pos < count; ++pos)
915  {
916  if (local_buf[pos].flag & RPLIDAR_RESP_MEASUREMENT_SYNCBIT)
917  {
918  // only publish the data when it contains a full 360 degree scan
919  if ((local_scan[0].flag & RPLIDAR_RESP_MEASUREMENT_SYNCBIT)) {
920  _lock.lock();
921  memcpy(_cached_scan_node_hq_buf, local_scan, scan_count * sizeof(rplidar_response_measurement_node_hq_t));
922  _cached_scan_node_hq_count = scan_count;
923  _dataEvt.set();
924  _lock.unlock();
925  }
926  scan_count = 0;
927  }
928  local_scan[scan_count++] = local_buf[pos];
929  if (scan_count == _countof(local_scan)) scan_count -= 1; // prevent overflow
930  //for interval retrieve
931  {
935  }
936  }
937 
938  }
939  return RESULT_OK;
940 }
941 
942 //CRC calculate
943 static _u32 table[256];//crc32_table
944 
945 //reflect
946 static _u32 _bitrev(_u32 input, _u16 bw)
947 {
948  _u16 i;
949  _u32 var;
950  var = 0;
951  for (i = 0; i<bw; i++){
952  if (input & 0x01)
953  {
954  var |= 1 << (bw - 1 - i);
955  }
956  input >>= 1;
957  }
958  return var;
959 }
960 
961 // crc32_table init
962 static void _crc32_init(_u32 poly)
963 {
964  _u16 i;
965  _u16 j;
966  _u32 c;
967 
968  poly = _bitrev(poly, 32);
969  for (i = 0; i<256; i++){
970  c = i;
971  for (j = 0; j<8; j++){
972  if (c & 1)
973  c = poly ^ (c >> 1);
974  else
975  c = c >> 1;
976  }
977  table[i] = c;
978  }
979 }
980 
981 static _u32 _crc32cal(_u32 crc, void* input, _u16 len)
982 {
983  _u16 i;
984  _u8 index;
985  _u8* pch;
986  pch = (unsigned char*)input;
987  _u8 leftBytes = 4 - len & 0x3;
988 
989  for (i = 0; i<len; i++){
990  index = (unsigned char)(crc^*pch);
991  crc = (crc >> 8) ^ table[index];
992  pch++;
993  }
994 
995  for (i = 0; i < leftBytes; i++) {//zero padding
996  index = (unsigned char)(crc^0);
997  crc = (crc >> 8) ^ table[index];
998  }
999  return crc^0xffffffff;
1000 }
1001 
1002 //crc32cal
1003 static u_result _crc32(_u8 *ptr, _u32 len) {
1004  static _u8 tmp;
1005  if (tmp != 1) {
1006  _crc32_init(0x4C11DB7);
1007  tmp = 1;
1008  }
1009 
1010  return _crc32cal(0xFFFFFFFF, ptr,len);
1011 }
1012 
1013 u_result RPlidarDriverImplCommon::_waitHqNode(rplidar_response_hq_capsule_measurement_nodes_t & node, _u32 timeout)
1014 {
1015  if (!_isConnected) {
1016  return RESULT_OPERATION_FAIL;
1017  }
1018 
1019  int recvPos = 0;
1020  _u32 startTs = getms();
1021  _u8 recvBuffer[sizeof(rplidar_response_hq_capsule_measurement_nodes_t)];
1022  _u8 *nodeBuffer = (_u8*)&node;
1023  _u32 waitTime;
1024 
1025  while ((waitTime=getms() - startTs) <= timeout) {
1026  size_t remainSize = sizeof(rplidar_response_hq_capsule_measurement_nodes_t) - recvPos;
1027  size_t recvSize;
1028 
1029  bool ans = _chanDev->waitfordata(remainSize, timeout-waitTime, &recvSize);
1030  if(!ans)
1031  {
1032  return RESULT_OPERATION_TIMEOUT;
1033  }
1034  if (recvSize > remainSize) recvSize = remainSize;
1035 
1036  recvSize = _chanDev->recvdata(recvBuffer, recvSize);
1037 
1038  for (size_t pos = 0; pos < recvSize; ++pos) {
1039  _u8 currentByte = recvBuffer[pos];
1040  switch (recvPos) {
1041  case 0: // expect the sync byte
1042  {
1043  _u8 tmp = (currentByte);
1044  if ( tmp == RPLIDAR_RESP_MEASUREMENT_HQ_SYNC ) {
1045  // pass
1046  }
1047  else {
1048  recvPos = 0;
1049  _is_previous_HqdataRdy = false;
1050  continue;
1051  }
1052  }
1053  break;
1054  case sizeof(rplidar_response_hq_capsule_measurement_nodes_t) - 1 - 4:
1055  {
1056 
1057  }
1058  break;
1059  case sizeof(rplidar_response_hq_capsule_measurement_nodes_t) - 1:
1060  {
1061 
1062  }
1063  break;
1064  }
1065  nodeBuffer[recvPos++] = currentByte;
1066  if (recvPos == sizeof(rplidar_response_hq_capsule_measurement_nodes_t)) {
1067  _u32 crcCalc2 = _crc32(nodeBuffer, sizeof(rplidar_response_hq_capsule_measurement_nodes_t) - 4);
1068 
1069  if(crcCalc2 == node.crc32){
1070  _is_previous_HqdataRdy = true;
1071  return RESULT_OK;
1072  }
1073  else {
1074  _is_previous_HqdataRdy = false;
1075  return RESULT_INVALID_DATA;
1076  }
1077 
1078  }
1079  }
1080  }
1081  _is_previous_HqdataRdy = false;
1082  return RESULT_OPERATION_TIMEOUT;
1083 }
1084 
1085 void RPlidarDriverImplCommon::_HqToNormal(const rplidar_response_hq_capsule_measurement_nodes_t & node_hq, rplidar_response_measurement_node_hq_t *nodebuffer, size_t &nodeCount)
1086 {
1087  nodeCount = 0;
1088  if (_is_previous_HqdataRdy) {
1089  for (size_t pos = 0; pos < _countof(_cached_previous_Hqdata.node_hq); ++pos)
1090  {
1091  nodebuffer[nodeCount++] = node_hq.node_hq[pos];
1092  }
1093  }
1095  _is_previous_HqdataRdy = true;
1096 
1097 }
1098 //*******************************************HQ support********************************//
1099 
1100 static _u32 _varbitscale_decode(_u32 scaled, _u32 & scaleLevel)
1101 {
1102  static const _u32 VBS_SCALED_BASE[] = {
1107  0,
1108  };
1109 
1110  static const _u32 VBS_SCALED_LVL[] = {
1111  4,
1112  3,
1113  2,
1114  1,
1115  0,
1116  };
1117 
1118  static const _u32 VBS_TARGET_BASE[] = {
1123  0,
1124  };
1125 
1126  for (size_t i = 0; i < _countof(VBS_SCALED_BASE); ++i)
1127  {
1128  int remain = ((int)scaled - (int)VBS_SCALED_BASE[i]);
1129  if (remain >= 0) {
1130  scaleLevel = VBS_SCALED_LVL[i];
1131  return VBS_TARGET_BASE[i] + (remain << scaleLevel);
1132  }
1133  }
1134  return 0;
1135 }
1136 
1137 void RPlidarDriverImplCommon::_ultraCapsuleToNormal(const rplidar_response_ultra_capsule_measurement_nodes_t & capsule, rplidar_response_measurement_node_hq_t *nodebuffer, size_t &nodeCount)
1138 {
1139  nodeCount = 0;
1141  int diffAngle_q8;
1142  int currentStartAngle_q8 = ((capsule.start_angle_sync_q6 & 0x7FFF) << 2);
1143  int prevStartAngle_q8 = ((_cached_previous_ultracapsuledata.start_angle_sync_q6 & 0x7FFF) << 2);
1144 
1145  diffAngle_q8 = (currentStartAngle_q8)-(prevStartAngle_q8);
1146  if (prevStartAngle_q8 > currentStartAngle_q8) {
1147  diffAngle_q8 += (360 << 8);
1148  }
1149 
1150  int angleInc_q16 = (diffAngle_q8 << 3) / 3;
1151  int currentAngle_raw_q16 = (prevStartAngle_q8 << 8);
1152  for (size_t pos = 0; pos < _countof(_cached_previous_ultracapsuledata.ultra_cabins); ++pos)
1153  {
1154  int dist_q2[3];
1155  int angle_q6[3];
1156  int syncBit[3];
1157 
1158 
1159  _u32 combined_x3 = _cached_previous_ultracapsuledata.ultra_cabins[pos].combined_x3;
1160 
1161  // unpack ...
1162  int dist_major = (combined_x3 & 0xFFF);
1163 
1164  // signed partical integer, using the magic shift here
1165  // DO NOT TOUCH
1166 
1167  int dist_predict1 = (((int)(combined_x3 << 10)) >> 22);
1168  int dist_predict2 = (((int)combined_x3) >> 22);
1169 
1170  int dist_major2;
1171 
1172  _u32 scalelvl1, scalelvl2;
1173 
1174  // prefetch next ...
1175  if (pos == _countof(_cached_previous_ultracapsuledata.ultra_cabins) - 1)
1176  {
1177  dist_major2 = (capsule.ultra_cabins[0].combined_x3 & 0xFFF);
1178  }
1179  else {
1180  dist_major2 = (_cached_previous_ultracapsuledata.ultra_cabins[pos + 1].combined_x3 & 0xFFF);
1181  }
1182 
1183  // decode with the var bit scale ...
1184  dist_major = _varbitscale_decode(dist_major, scalelvl1);
1185  dist_major2 = _varbitscale_decode(dist_major2, scalelvl2);
1186 
1187 
1188  int dist_base1 = dist_major;
1189  int dist_base2 = dist_major2;
1190 
1191  if ((!dist_major) && dist_major2) {
1192  dist_base1 = dist_major2;
1193  scalelvl1 = scalelvl2;
1194  }
1195 
1196 
1197  dist_q2[0] = (dist_major << 2);
1198  if ((dist_predict1 == 0xFFFFFE00) || (dist_predict1 == 0x1FF)) {
1199  dist_q2[1] = 0;
1200  } else {
1201  dist_predict1 = (dist_predict1 << scalelvl1);
1202  dist_q2[1] = (dist_predict1 + dist_base1) << 2;
1203 
1204  }
1205 
1206  if ((dist_predict2 == 0xFFFFFE00) || (dist_predict2 == 0x1FF)) {
1207  dist_q2[2] = 0;
1208  } else {
1209  dist_predict2 = (dist_predict2 << scalelvl2);
1210  dist_q2[2] = (dist_predict2 + dist_base2) << 2;
1211  }
1212 
1213 
1214  for (int cpos = 0; cpos < 3; ++cpos)
1215  {
1216 
1217  syncBit[cpos] = (((currentAngle_raw_q16 + angleInc_q16) % (360 << 16)) < angleInc_q16) ? 1 : 0;
1218 
1219  int offsetAngleMean_q16 = (int)(7.5 * 3.1415926535 * (1 << 16) / 180.0);
1220 
1221  if (dist_q2[cpos] >= (50 * 4))
1222  {
1223  const int k1 = 98361;
1224  const int k2 = int(k1 / dist_q2[cpos]);
1225 
1226  offsetAngleMean_q16 = (int)(8 * 3.1415926535 * (1 << 16) / 180) - (k2 << 6) - (k2 * k2 * k2) / 98304;
1227  }
1228 
1229  angle_q6[cpos] = ((currentAngle_raw_q16 - int(offsetAngleMean_q16 * 180 / 3.14159265)) >> 10);
1230  currentAngle_raw_q16 += angleInc_q16;
1231 
1232  if (angle_q6[cpos] < 0) angle_q6[cpos] += (360 << 6);
1233  if (angle_q6[cpos] >= (360 << 6)) angle_q6[cpos] -= (360 << 6);
1234 
1236 
1237  node.flag = (syncBit[cpos] | ((!syncBit[cpos]) << 1));
1238  node.quality = dist_q2[cpos] ? (0x2F << RPLIDAR_RESP_MEASUREMENT_QUALITY_SHIFT) : 0;
1239  node.angle_z_q14 = _u16((angle_q6[cpos] << 8) / 90);
1240  node.dist_mm_q2 = dist_q2[cpos];
1241 
1242  nodebuffer[nodeCount++] = node;
1243  }
1244 
1245  }
1246  }
1247 
1250 }
1251 
1253 {
1254  u_result ans;
1255 
1256  rplidar_response_device_info_t devinfo;
1257  ans = getDeviceInfo(devinfo, timeoutInMs);
1258  if (IS_FAIL(ans)) return ans;
1259 
1260  // if lidar firmware >= 1.24
1261  if (devinfo.firmware_version >= ((0x1 << 8) | 24)) {
1262  outSupport = true;
1263  }
1264  return ans;
1265 }
1266 
1267 u_result RPlidarDriverImplCommon::getLidarConf(_u32 type, std::vector<_u8> &outputBuf, const std::vector<_u8> &reserve, _u32 timeout)
1268 {
1269  rplidar_payload_get_scan_conf_t query;
1270  memset(&query, 0, sizeof(query));
1271  query.type = type;
1272  int sizeVec = reserve.size();
1273 
1274  int maxLen = sizeof(query.reserved) / sizeof(query.reserved[0]);
1275  if (sizeVec > maxLen) sizeVec = maxLen;
1276 
1277  if (sizeVec > 0)
1278  memcpy(query.reserved, &reserve[0], reserve.size());
1279 
1280  u_result ans;
1281  {
1283  if (IS_FAIL(ans = _sendCommand(RPLIDAR_CMD_GET_LIDAR_CONF, &query, sizeof(query)))) {
1284  return ans;
1285  }
1286 
1287  // waiting for confirmation
1288  rplidar_ans_header_t response_header;
1289  if (IS_FAIL(ans = _waitResponseHeader(&response_header, timeout))) {
1290  return ans;
1291  }
1292 
1293  // verify whether we got a correct header
1294  if (response_header.type != RPLIDAR_ANS_TYPE_GET_LIDAR_CONF) {
1295  return RESULT_INVALID_DATA;
1296  }
1297 
1298  _u32 header_size = (response_header.size_q30_subtype & RPLIDAR_ANS_HEADER_SIZE_MASK);
1299  if (header_size < sizeof(type)) {
1300  return RESULT_INVALID_DATA;
1301  }
1302 
1303  if (!_chanDev->waitfordata(header_size, timeout)) {
1304  return RESULT_OPERATION_TIMEOUT;
1305  }
1306 
1307  std::vector<_u8> dataBuf;
1308  dataBuf.resize(header_size);
1309  _chanDev->recvdata(reinterpret_cast<_u8 *>(&dataBuf[0]), header_size);
1310 
1311  //check if returned type is same as asked type
1312  _u32 replyType = -1;
1313  memcpy(&replyType, &dataBuf[0], sizeof(type));
1314  if (replyType != type) {
1315  return RESULT_INVALID_DATA;
1316  }
1317 
1318  //copy all the payload into &outputBuf
1319  int payLoadLen = header_size - sizeof(type);
1320 
1321  //do consistency check
1322  if (payLoadLen <= 0) {
1323  return RESULT_INVALID_DATA;
1324  }
1325  //copy all payLoadLen bytes to outputBuf
1326  outputBuf.resize(payLoadLen);
1327  memcpy(&outputBuf[0], &dataBuf[0] + sizeof(type), payLoadLen);
1328  }
1329  return ans;
1330 }
1331 
1333 {
1334  u_result ans;
1335  std::vector<_u8> answer;
1336  bool lidarSupportConfigCmds = false;
1337  ans = checkSupportConfigCommands(lidarSupportConfigCmds);
1338  if (IS_FAIL(ans)) return RESULT_INVALID_DATA;
1339 
1340  if (lidarSupportConfigCmds)
1341  {
1342  ans = getLidarConf(RPLIDAR_CONF_SCAN_MODE_TYPICAL, answer, std::vector<_u8>(), timeoutInMs);
1343  if (IS_FAIL(ans)) {
1344  return ans;
1345  }
1346  if (answer.size() < sizeof(_u16)) {
1347  return RESULT_INVALID_DATA;
1348  }
1349 
1350  const _u16 *p_answer = reinterpret_cast<const _u16*>(&answer[0]);
1351  outMode = *p_answer;
1352  return ans;
1353  }
1354  //old version of triangle lidar
1355  else
1356  {
1358  return ans;
1359  }
1360  return ans;
1361 }
1362 
1363 u_result RPlidarDriverImplCommon::getLidarSampleDuration(float& sampleDurationRes, _u16 scanModeID, _u32 timeoutInMs)
1364 {
1365  u_result ans;
1366  std::vector<_u8> reserve(2);
1367  memcpy(&reserve[0], &scanModeID, sizeof(scanModeID));
1368 
1369  std::vector<_u8> answer;
1370  ans = getLidarConf(RPLIDAR_CONF_SCAN_MODE_US_PER_SAMPLE, answer, reserve, timeoutInMs);
1371  if (IS_FAIL(ans))
1372  {
1373  return ans;
1374  }
1375  if (answer.size() < sizeof(_u32))
1376  {
1377  return RESULT_INVALID_DATA;
1378  }
1379  const _u32 *result = reinterpret_cast<const _u32*>(&answer[0]);
1380  sampleDurationRes = (float)(*result >> 8);
1381  return ans;
1382 }
1383 
1384 u_result RPlidarDriverImplCommon::getMaxDistance(float &maxDistance, _u16 scanModeID, _u32 timeoutInMs)
1385 {
1386  u_result ans;
1387  std::vector<_u8> reserve(2);
1388  memcpy(&reserve[0], &scanModeID, sizeof(scanModeID));
1389 
1390  std::vector<_u8> answer;
1391  ans = getLidarConf(RPLIDAR_CONF_SCAN_MODE_MAX_DISTANCE, answer, reserve, timeoutInMs);
1392  if (IS_FAIL(ans))
1393  {
1394  return ans;
1395  }
1396  if (answer.size() < sizeof(_u32))
1397  {
1398  return RESULT_INVALID_DATA;
1399  }
1400  const _u32 *result = reinterpret_cast<const _u32*>(&answer[0]);
1401  maxDistance = (float)(*result >> 8);
1402  return ans;
1403 }
1404 
1406 {
1407  u_result ans;
1408  std::vector<_u8> reserve(2);
1409  memcpy(&reserve[0], &scanModeID, sizeof(scanModeID));
1410 
1411  std::vector<_u8> answer;
1412  ans = getLidarConf(RPLIDAR_CONF_SCAN_MODE_ANS_TYPE, answer, reserve, timeoutInMs);
1413  if (IS_FAIL(ans))
1414  {
1415  return ans;
1416  }
1417  if (answer.size() < sizeof(_u8))
1418  {
1419  return RESULT_INVALID_DATA;
1420  }
1421  const _u8 *result = reinterpret_cast<const _u8*>(&answer[0]);
1422  ansType = *result;
1423  return ans;
1424 }
1425 
1426 u_result RPlidarDriverImplCommon::getScanModeName(char* modeName, _u16 scanModeID, _u32 timeoutInMs)
1427 {
1428  u_result ans;
1429  std::vector<_u8> reserve(2);
1430  memcpy(&reserve[0], &scanModeID, sizeof(scanModeID));
1431 
1432  std::vector<_u8> answer;
1433  ans = getLidarConf(RPLIDAR_CONF_SCAN_MODE_NAME, answer, reserve, timeoutInMs);
1434  if (IS_FAIL(ans))
1435  {
1436  return ans;
1437  }
1438  int len = answer.size();
1439  if (0 == len) return RESULT_INVALID_DATA;
1440  memcpy(modeName, &answer[0], len);
1441  return ans;
1442 }
1443 
1444 u_result RPlidarDriverImplCommon::getAllSupportedScanModes(std::vector<RplidarScanMode>& outModes, _u32 timeoutInMs)
1445 {
1446  u_result ans;
1447  bool confProtocolSupported = false;
1448  ans = checkSupportConfigCommands(confProtocolSupported);
1449  if (IS_FAIL(ans)) return RESULT_INVALID_DATA;
1450 
1451  if (confProtocolSupported)
1452  {
1453  // 1. get scan mode count
1454  _u16 modeCount;
1455  ans = getScanModeCount(modeCount);
1456  if (IS_FAIL(ans))
1457  {
1458  return RESULT_INVALID_DATA;
1459  }
1460  // 2. for loop to get all fields of each scan mode
1461  for (_u16 i = 0; i < modeCount; i++)
1462  {
1463  RplidarScanMode scanModeInfoTmp;
1464  memset(&scanModeInfoTmp, 0, sizeof(scanModeInfoTmp));
1465  scanModeInfoTmp.id = i;
1466  ans = getLidarSampleDuration(scanModeInfoTmp.us_per_sample, i);
1467  if (IS_FAIL(ans))
1468  {
1469  return RESULT_INVALID_DATA;
1470  }
1471  ans = getMaxDistance(scanModeInfoTmp.max_distance, i);
1472  if (IS_FAIL(ans))
1473  {
1474  return RESULT_INVALID_DATA;
1475  }
1476  ans = getScanModeAnsType(scanModeInfoTmp.ans_type, i);
1477  if (IS_FAIL(ans))
1478  {
1479  return RESULT_INVALID_DATA;
1480  }
1481  ans = getScanModeName(scanModeInfoTmp.scan_mode, i);
1482  if (IS_FAIL(ans))
1483  {
1484  return RESULT_INVALID_DATA;
1485  }
1486  outModes.push_back(scanModeInfoTmp);
1487  }
1488  return ans;
1489  }
1490  else
1491  {
1492  rplidar_response_sample_rate_t sampleRateTmp;
1493  ans = getSampleDuration_uS(sampleRateTmp);
1494  if (IS_FAIL(ans)) return RESULT_INVALID_DATA;
1495  //judge if support express scan
1496  bool ifSupportExpScan = false;
1497  ans = checkExpressScanSupported(ifSupportExpScan);
1498  if (IS_FAIL(ans)) return RESULT_INVALID_DATA;
1499 
1500  RplidarScanMode stdScanModeInfo;
1501  stdScanModeInfo.id = RPLIDAR_CONF_SCAN_COMMAND_STD;
1502  stdScanModeInfo.us_per_sample = sampleRateTmp.std_sample_duration_us;
1503  stdScanModeInfo.max_distance = 16;
1504  stdScanModeInfo.ans_type = RPLIDAR_ANS_TYPE_MEASUREMENT;
1505  strcpy(stdScanModeInfo.scan_mode, "Standard");
1506  outModes.push_back(stdScanModeInfo);
1507  if (ifSupportExpScan)
1508  {
1509  RplidarScanMode expScanModeInfo;
1510  expScanModeInfo.id = RPLIDAR_CONF_SCAN_COMMAND_EXPRESS;
1511  expScanModeInfo.us_per_sample = sampleRateTmp.express_sample_duration_us;
1512  expScanModeInfo.max_distance = 16;
1514  strcpy(expScanModeInfo.scan_mode, "Express");
1515  outModes.push_back(expScanModeInfo);
1516  }
1517  return ans;
1518  }
1519  return ans;
1520 }
1521 
1523 {
1524  u_result ans;
1525  std::vector<_u8> answer;
1526  ans = getLidarConf(RPLIDAR_CONF_SCAN_MODE_COUNT, answer, std::vector<_u8>(), timeoutInMs);
1527 
1528  if (IS_FAIL(ans)) {
1529  return ans;
1530  }
1531  if (answer.size() < sizeof(_u16)) {
1532  return RESULT_INVALID_DATA;
1533  }
1534  const _u16 *p_answer = reinterpret_cast<const _u16*>(&answer[0]);
1535  modeCount = *p_answer;
1536 
1537  return ans;
1538 }
1539 
1540 
1541 u_result RPlidarDriverImplCommon::startScan(bool force, bool useTypicalScan, _u32 options, RplidarScanMode* outUsedScanMode)
1542 {
1543  u_result ans;
1544 
1545  bool ifSupportLidarConf = false;
1546  ans = checkSupportConfigCommands(ifSupportLidarConf);
1547  if (IS_FAIL(ans)) return RESULT_INVALID_DATA;
1548 
1549  if (useTypicalScan)
1550  {
1551  //if support lidar config protocol
1552  if (ifSupportLidarConf)
1553  {
1554  _u16 typicalMode;
1555  ans = getTypicalScanMode(typicalMode);
1556  if (IS_FAIL(ans)) return RESULT_INVALID_DATA;
1557 
1558  //call startScanExpress to do the job
1559  return startScanExpress(false, typicalMode, 0, outUsedScanMode);
1560  }
1561  //if old version of triangle lidar
1562  else
1563  {
1564  bool isExpScanSupported = false;
1565  ans = checkExpressScanSupported(isExpScanSupported);
1566  if (IS_FAIL(ans)) {
1567  return ans;
1568  }
1569  if (isExpScanSupported)
1570  {
1571  return startScanExpress(false, RPLIDAR_CONF_SCAN_COMMAND_EXPRESS, 0, outUsedScanMode);
1572  }
1573  }
1574  }
1575 
1576  // 'useTypicalScan' is false, just use normal scan mode
1577  if(ifSupportLidarConf)
1578  {
1579  if(outUsedScanMode)
1580  {
1581  outUsedScanMode->id = RPLIDAR_CONF_SCAN_COMMAND_STD;
1582  ans = getLidarSampleDuration(outUsedScanMode->us_per_sample, outUsedScanMode->id);
1583  if(IS_FAIL(ans))
1584  {
1585  return RESULT_INVALID_DATA;
1586  }
1587 
1588  ans = getMaxDistance(outUsedScanMode->max_distance, outUsedScanMode->id);
1589  if(IS_FAIL(ans))
1590  {
1591  return RESULT_INVALID_DATA;
1592  }
1593 
1594  ans = getScanModeAnsType(outUsedScanMode->ans_type, outUsedScanMode->id);
1595  if(IS_FAIL(ans))
1596  {
1597  return RESULT_INVALID_DATA;
1598  }
1599 
1600  ans = getScanModeName(outUsedScanMode->scan_mode, outUsedScanMode->id);
1601  if(IS_FAIL(ans))
1602  {
1603  return RESULT_INVALID_DATA;
1604  }
1605  }
1606  }
1607  else
1608  {
1609  if(outUsedScanMode)
1610  {
1611  rplidar_response_sample_rate_t sampleRateTmp;
1612  ans = getSampleDuration_uS(sampleRateTmp);
1613  if(IS_FAIL(ans)) return RESULT_INVALID_DATA;
1614  outUsedScanMode->us_per_sample = sampleRateTmp.std_sample_duration_us;
1615  outUsedScanMode->max_distance = 16;
1616  outUsedScanMode->ans_type = RPLIDAR_ANS_TYPE_MEASUREMENT;
1617  strcpy(outUsedScanMode->scan_mode, "Standard");
1618  }
1619  }
1620 
1621  return startScanNormal(force);
1622 }
1623 
1624 u_result RPlidarDriverImplCommon::startScanExpress(bool force, _u16 scanMode, _u32 options, RplidarScanMode* outUsedScanMode, _u32 timeout)
1625 {
1626  u_result ans;
1627  if (!isConnected()) return RESULT_OPERATION_FAIL;
1628  if (_isScanning) return RESULT_ALREADY_DONE;
1629 
1630  stop(); //force the previous operation to stop
1631 
1632  if (scanMode == RPLIDAR_CONF_SCAN_COMMAND_STD)
1633  {
1634  return startScan(force, false, 0, outUsedScanMode);
1635  }
1636 
1637 
1638  bool ifSupportLidarConf = false;
1639  ans = checkSupportConfigCommands(ifSupportLidarConf);
1640  if (IS_FAIL(ans)) return RESULT_INVALID_DATA;
1641 
1642  if (outUsedScanMode)
1643  {
1644  outUsedScanMode->id = scanMode;
1645  if (ifSupportLidarConf)
1646  {
1647  ans = getLidarSampleDuration(outUsedScanMode->us_per_sample, outUsedScanMode->id);
1648  if (IS_FAIL(ans))
1649  {
1650  return RESULT_INVALID_DATA;
1651  }
1652 
1653  ans = getMaxDistance(outUsedScanMode->max_distance, outUsedScanMode->id);
1654  if (IS_FAIL(ans))
1655  {
1656  return RESULT_INVALID_DATA;
1657  }
1658 
1659  ans = getScanModeAnsType(outUsedScanMode->ans_type, outUsedScanMode->id);
1660  if (IS_FAIL(ans))
1661  {
1662  return RESULT_INVALID_DATA;
1663  }
1664 
1665  ans = getScanModeName(outUsedScanMode->scan_mode, outUsedScanMode->id);
1666  if (IS_FAIL(ans))
1667  {
1668  return RESULT_INVALID_DATA;
1669  }
1670 
1671 
1672  }
1673  else
1674  {
1675  rplidar_response_sample_rate_t sampleRateTmp;
1676  ans = getSampleDuration_uS(sampleRateTmp);
1677  if (IS_FAIL(ans)) return RESULT_INVALID_DATA;
1678 
1679  outUsedScanMode->us_per_sample = sampleRateTmp.express_sample_duration_us;
1680  outUsedScanMode->max_distance = 16;
1682  strcpy(outUsedScanMode->scan_mode, "Express");
1683  }
1684  }
1685 
1686  //get scan answer type to specify how to wait data
1687  _u8 scanAnsType;
1688  if (ifSupportLidarConf)
1689  {
1690  getScanModeAnsType(scanAnsType, scanMode);
1691  }
1692  else
1693  {
1695  }
1696 
1697  {
1699 
1700  rplidar_payload_express_scan_t scanReq;
1701  memset(&scanReq, 0, sizeof(scanReq));
1703  scanReq.working_mode = _u8(scanMode);
1704  scanReq.working_flags = options;
1705 
1706  if (IS_FAIL(ans = _sendCommand(RPLIDAR_CMD_EXPRESS_SCAN, &scanReq, sizeof(scanReq)))) {
1707  return ans;
1708  }
1709 
1710  // waiting for confirmation
1711  rplidar_ans_header_t response_header;
1712  if (IS_FAIL(ans = _waitResponseHeader(&response_header, timeout))) {
1713  return ans;
1714  }
1715 
1716  // verify whether we got a correct header
1717  if (response_header.type != scanAnsType) {
1718  return RESULT_INVALID_DATA;
1719  }
1720 
1721  _u32 header_size = (response_header.size_q30_subtype & RPLIDAR_ANS_HEADER_SIZE_MASK);
1722 
1723  if (scanAnsType == RPLIDAR_ANS_TYPE_MEASUREMENT_CAPSULED)
1724  {
1725  if (header_size < sizeof(rplidar_response_capsule_measurement_nodes_t)) {
1726  return RESULT_INVALID_DATA;
1727  }
1729  _isScanning = true;
1731  }
1732  else if (scanAnsType == RPLIDAR_ANS_TYPE_MEASUREMENT_DENSE_CAPSULED)
1733  {
1734  if (header_size < sizeof(rplidar_response_capsule_measurement_nodes_t)) {
1735  return RESULT_INVALID_DATA;
1736  }
1738  _isScanning = true;
1740  }
1741  else if (scanAnsType == RPLIDAR_ANS_TYPE_MEASUREMENT_HQ) {
1742  if (header_size < sizeof(rplidar_response_hq_capsule_measurement_nodes_t)) {
1743  return RESULT_INVALID_DATA;
1744  }
1745  _isScanning = true;
1747  }
1748  else
1749  {
1750  if (header_size < sizeof(rplidar_response_ultra_capsule_measurement_nodes_t)) {
1751  return RESULT_INVALID_DATA;
1752  }
1753  _isScanning = true;
1755  }
1756 
1757  if (_cachethread.getHandle() == 0) {
1758  return RESULT_OPERATION_FAIL;
1759  }
1760  }
1761  return RESULT_OK;
1762 }
1763 
1765 {
1766  u_result ans;
1768 
1769  {
1771 
1772  if (IS_FAIL(ans = _sendCommand(RPLIDAR_CMD_STOP))) {
1773  return ans;
1774  }
1775  }
1776 
1777  return RESULT_OK;
1778 }
1779 
1780 u_result RPlidarDriverImplCommon::grabScanData(rplidar_response_measurement_node_t * nodebuffer, size_t & count, _u32 timeout)
1781 {
1782  DEPRECATED_WARN("grabScanData()", "grabScanDataHq()");
1783 
1784  switch (_dataEvt.wait(timeout))
1785  {
1787  count = 0;
1788  return RESULT_OPERATION_TIMEOUT;
1790  {
1791  if(_cached_scan_node_hq_count == 0) return RESULT_OPERATION_TIMEOUT; //consider as timeout
1792 
1794 
1795  size_t size_to_copy = min(count, _cached_scan_node_hq_count);
1796 
1797  for (size_t i = 0; i < size_to_copy; i++)
1798  convert(_cached_scan_node_hq_buf[i], nodebuffer[i]);
1799 
1800  count = size_to_copy;
1802  }
1803  return RESULT_OK;
1804 
1805  default:
1806  count = 0;
1807  return RESULT_OPERATION_FAIL;
1808  }
1809 }
1810 
1812 {
1813  switch (_dataEvt.wait(timeout))
1814  {
1816  count = 0;
1817  return RESULT_OPERATION_TIMEOUT;
1819  {
1820  if (_cached_scan_node_hq_count == 0) return RESULT_OPERATION_TIMEOUT; //consider as timeout
1821 
1823 
1824  size_t size_to_copy = min(count, _cached_scan_node_hq_count);
1825  memcpy(nodebuffer, _cached_scan_node_hq_buf, size_to_copy * sizeof(rplidar_response_measurement_node_hq_t));
1826 
1827  count = size_to_copy;
1829  }
1830  return RESULT_OK;
1831 
1832  default:
1833  count = 0;
1834  return RESULT_OPERATION_FAIL;
1835  }
1836 }
1837 
1838 u_result RPlidarDriverImplCommon::getScanDataWithInterval(rplidar_response_measurement_node_t * nodebuffer, size_t & count)
1839 {
1840  DEPRECATED_WARN("getScanDataWithInterval(rplidar_response_measurement_node_t*, size_t&)", "getScanDataWithInterval(rplidar_response_measurement_node_hq_t*, size_t&)");
1841 
1842  size_t size_to_copy = 0;
1843  {
1846  {
1847  return RESULT_OPERATION_TIMEOUT;
1848  }
1849  //copy all the nodes(_cached_scan_node_count_for_interval_retrieve nodes) in _cached_scan_node_buf_for_interval_retrieve
1851  for (size_t i = 0; i < size_to_copy; i++)
1852  {
1854  }
1856  }
1857  count = size_to_copy;
1858 
1859  return RESULT_OK;
1860 }
1861 
1863 {
1864  size_t size_to_copy = 0;
1865  {
1868  {
1869  return RESULT_OPERATION_TIMEOUT;
1870  }
1871  //copy all the nodes(_cached_scan_node_count_for_interval_retrieve nodes) in _cached_scan_node_buf_for_interval_retrieve
1875  }
1876  count = size_to_copy;
1877 
1878  return RESULT_OK;
1879 }
1880 
1881 static inline float getAngle(const rplidar_response_measurement_node_t& node)
1882 {
1883  return (node.angle_q6_checkbit >> RPLIDAR_RESP_MEASUREMENT_ANGLE_SHIFT) / 64.f;
1884 }
1885 
1886 static inline void setAngle(rplidar_response_measurement_node_t& node, float v)
1887 {
1888  _u16 checkbit = node.angle_q6_checkbit & RPLIDAR_RESP_MEASUREMENT_CHECKBIT;
1889  node.angle_q6_checkbit = (((_u16)(v * 64.0f)) << RPLIDAR_RESP_MEASUREMENT_ANGLE_SHIFT) | checkbit;
1890 }
1891 
1892 static inline float getAngle(const rplidar_response_measurement_node_hq_t& node)
1893 {
1894  return node.angle_z_q14 * 90.f / 16384.f;
1895 }
1896 
1897 static inline void setAngle(rplidar_response_measurement_node_hq_t& node, float v)
1898 {
1899  node.angle_z_q14 = _u32(v * 16384.f / 90.f);
1900 }
1901 
1902 static inline _u16 getDistanceQ2(const rplidar_response_measurement_node_t& node)
1903 {
1904  return node.distance_q2;
1905 }
1906 
1908 {
1909  return node.dist_mm_q2;
1910 }
1911 
1912 template <class TNode>
1913 static bool angleLessThan(const TNode& a, const TNode& b)
1914 {
1915  return getAngle(a) < getAngle(b);
1916 }
1917 
1918 template < class TNode >
1919 static u_result ascendScanData_(TNode * nodebuffer, size_t count)
1920 {
1921  float inc_origin_angle = 360.f/count;
1922  size_t i = 0;
1923 
1924  //Tune head
1925  for (i = 0; i < count; i++) {
1926  if(getDistanceQ2(nodebuffer[i]) == 0) {
1927  continue;
1928  } else {
1929  while(i != 0) {
1930  i--;
1931  float expect_angle = getAngle(nodebuffer[i+1]) - inc_origin_angle;
1932  if (expect_angle < 0.0f) expect_angle = 0.0f;
1933  setAngle(nodebuffer[i], expect_angle);
1934  }
1935  break;
1936  }
1937  }
1938 
1939  // all the data is invalid
1940  if (i == count) return RESULT_OPERATION_FAIL;
1941 
1942  //Tune tail
1943  for (i = count - 1; i >= 0; i--) {
1944  if(getDistanceQ2(nodebuffer[i]) == 0) {
1945  continue;
1946  } else {
1947  while(i != (count - 1)) {
1948  i++;
1949  float expect_angle = getAngle(nodebuffer[i-1]) + inc_origin_angle;
1950  if (expect_angle > 360.0f) expect_angle -= 360.0f;
1951  setAngle(nodebuffer[i], expect_angle);
1952  }
1953  break;
1954  }
1955  }
1956 
1957  //Fill invalid angle in the scan
1958  float frontAngle = getAngle(nodebuffer[0]);
1959  for (i = 1; i < count; i++) {
1960  if(getDistanceQ2(nodebuffer[i]) == 0) {
1961  float expect_angle = frontAngle + i * inc_origin_angle;
1962  if (expect_angle > 360.0f) expect_angle -= 360.0f;
1963  setAngle(nodebuffer[i], expect_angle);
1964  }
1965  }
1966 
1967  // Reorder the scan according to the angle value
1968  std::sort(nodebuffer, nodebuffer + count, &angleLessThan<TNode>);
1969 
1970  return RESULT_OK;
1971 }
1972 
1973 u_result RPlidarDriverImplCommon::ascendScanData(rplidar_response_measurement_node_t * nodebuffer, size_t count)
1974 {
1975  DEPRECATED_WARN("ascendScanData(rplidar_response_measurement_node_t*, size_t)", "ascendScanData(rplidar_response_measurement_node_hq_t*, size_t)");
1976 
1977  return ascendScanData_<rplidar_response_measurement_node_t>(nodebuffer, count);
1978 }
1979 
1981 {
1982  return ascendScanData_<rplidar_response_measurement_node_hq_t>(nodebuffer, count);
1983 }
1984 
1985 u_result RPlidarDriverImplCommon::_sendCommand(_u8 cmd, const void * payload, size_t payloadsize)
1986 {
1987  _u8 pkt_header[10];
1988  rplidar_cmd_packet_t * header = reinterpret_cast<rplidar_cmd_packet_t * >(pkt_header);
1989  _u8 checksum = 0;
1990 
1991  if (!_isConnected) return RESULT_OPERATION_FAIL;
1992 
1993  if (payloadsize && payload) {
1995  }
1996 
1997  header->syncByte = RPLIDAR_CMD_SYNC_BYTE;
1998  header->cmd_flag = cmd;
1999 
2000  // send header first
2001  _chanDev->senddata(pkt_header, 2) ;
2002 
2003  if (cmd & RPLIDAR_CMDFLAG_HAS_PAYLOAD) {
2004  checksum ^= RPLIDAR_CMD_SYNC_BYTE;
2005  checksum ^= cmd;
2006  checksum ^= (payloadsize & 0xFF);
2007 
2008  // calc checksum
2009  for (size_t pos = 0; pos < payloadsize; ++pos) {
2010  checksum ^= ((_u8 *)payload)[pos];
2011  }
2012 
2013  // send size
2014  _u8 sizebyte = payloadsize;
2015  _chanDev->senddata(&sizebyte, 1);
2016 
2017  // send payload
2018  _chanDev->senddata((const _u8 *)payload, sizebyte);
2019 
2020  // send checksum
2021  _chanDev->senddata(&checksum, 1);
2022  }
2023 
2024  return RESULT_OK;
2025 }
2026 
2027 u_result RPlidarDriverImplCommon::getSampleDuration_uS(rplidar_response_sample_rate_t & rateInfo, _u32 timeout)
2028 {
2029  DEPRECATED_WARN("getSampleDuration_uS", "RplidarScanMode::us_per_sample");
2030 
2031  if (!isConnected()) return RESULT_OPERATION_FAIL;
2032 
2034 
2035  rplidar_response_device_info_t devinfo;
2036  // 1. fetch the device version first...
2037  u_result ans = getDeviceInfo(devinfo, timeout);
2038 
2039  rateInfo.express_sample_duration_us = _cached_sampleduration_express;
2040  rateInfo.std_sample_duration_us = _cached_sampleduration_std;
2041 
2042  if (devinfo.firmware_version < ((0x1<<8) | 17)) {
2043  // provide fake data...
2044 
2045  return RESULT_OK;
2046  }
2047 
2048 
2049  {
2051 
2053  return ans;
2054  }
2055 
2056  rplidar_ans_header_t response_header;
2057  if (IS_FAIL(ans = _waitResponseHeader(&response_header, timeout))) {
2058  return ans;
2059  }
2060 
2061  // verify whether we got a correct header
2062  if (response_header.type != RPLIDAR_ANS_TYPE_SAMPLE_RATE) {
2063  return RESULT_INVALID_DATA;
2064  }
2065 
2066  _u32 header_size = (response_header.size_q30_subtype & RPLIDAR_ANS_HEADER_SIZE_MASK);
2067  if ( header_size < sizeof(rplidar_response_sample_rate_t)) {
2068  return RESULT_INVALID_DATA;
2069  }
2070 
2071  if (!_chanDev->waitfordata(header_size, timeout)) {
2072  return RESULT_OPERATION_TIMEOUT;
2073  }
2074  _chanDev->recvdata(reinterpret_cast<_u8 *>(&rateInfo), sizeof(rateInfo));
2075  }
2076  return RESULT_OK;
2077 }
2078 
2080 {
2081  u_result ans;
2082  support = false;
2083 
2084  if (!isConnected()) return RESULT_OPERATION_FAIL;
2085 
2087 
2088  {
2090 
2091  rplidar_payload_acc_board_flag_t flag;
2092  flag.reserved = 0;
2093 
2094  if (IS_FAIL(ans = _sendCommand(RPLIDAR_CMD_GET_ACC_BOARD_FLAG, &flag, sizeof(flag)))) {
2095  return ans;
2096  }
2097 
2098  rplidar_ans_header_t response_header;
2099  if (IS_FAIL(ans = _waitResponseHeader(&response_header, timeout))) {
2100  return ans;
2101  }
2102 
2103  // verify whether we got a correct header
2104  if (response_header.type != RPLIDAR_ANS_TYPE_ACC_BOARD_FLAG) {
2105  return RESULT_INVALID_DATA;
2106  }
2107 
2108  _u32 header_size = (response_header.size_q30_subtype & RPLIDAR_ANS_HEADER_SIZE_MASK);
2109  if ( header_size < sizeof(rplidar_response_acc_board_flag_t)) {
2110  return RESULT_INVALID_DATA;
2111  }
2112 
2113  if (!_chanDev->waitfordata(header_size, timeout)) {
2114  return RESULT_OPERATION_TIMEOUT;
2115  }
2116  rplidar_response_acc_board_flag_t acc_board_flag;
2117  _chanDev->recvdata(reinterpret_cast<_u8 *>(&acc_board_flag), sizeof(acc_board_flag));
2118 
2119  if (acc_board_flag.support_flag & RPLIDAR_RESP_ACC_BOARD_FLAG_MOTOR_CTRL_SUPPORT_MASK) {
2120  support = true;
2121  }
2122  }
2123  return RESULT_OK;
2124 }
2125 
2127 {
2128  u_result ans;
2129  rplidar_payload_motor_pwm_t motor_pwm;
2130  motor_pwm.pwm_value = pwm;
2131 
2132  {
2134 
2135  if (IS_FAIL(ans = _sendCommand(RPLIDAR_CMD_SET_MOTOR_PWM,(const _u8 *)&motor_pwm, sizeof(motor_pwm)))) {
2136  return ans;
2137  }
2138  }
2139 
2140  return RESULT_OK;
2141 }
2142 
2144 {
2145  if (_isSupportingMotorCtrl) { // RPLIDAR A2
2147  delay(500);
2148  return RESULT_OK;
2149  } else { // RPLIDAR A1
2151  _chanDev->clearDTR();
2152  delay(500);
2153  return RESULT_OK;
2154  }
2155 }
2156 
2158 {
2159  if (_isSupportingMotorCtrl) { // RPLIDAR A2
2160  setMotorPWM(0);
2161  delay(500);
2162  return RESULT_OK;
2163  } else { // RPLIDAR A1
2165  _chanDev->setDTR();
2166  delay(500);
2167  return RESULT_OK;
2168  }
2169 }
2170 
2172 {
2173  _isScanning = false;
2174  _cachethread.join();
2175 }
2176 
2177 // Serial Driver Impl
2178 
2180 {
2181  _chanDev = new SerialChannelDevice();
2182 }
2183 
2185 {
2186  // force disconnection
2187  disconnect();
2188 
2189  _chanDev->close();
2190  _chanDev->ReleaseRxTx();
2191 }
2192 
2194 {
2195  if (!_isConnected) return ;
2196  stop();
2197 }
2198 
2199 u_result RPlidarDriverSerial::connect(const char * port_path, _u32 baudrate, _u32 flag)
2200 {
2201  if (isConnected()) return RESULT_ALREADY_DONE;
2202 
2203  if (!_chanDev) return RESULT_INSUFFICIENT_MEMORY;
2204 
2205  {
2207 
2208  // establish the serial connection...
2209  if (!_chanDev->bind(port_path, baudrate) || !_chanDev->open()) {
2210  return RESULT_INVALID_DATA;
2211  }
2212  _chanDev->flush();
2213  }
2214 
2215  _isConnected = true;
2216 
2218  stopMotor();
2219 
2220  return RESULT_OK;
2221 }
2222 
2224 {
2225  _chanDev = new TCPChannelDevice();
2226 }
2227 
2229 {
2230  // force disconnection
2231  disconnect();
2232 }
2233 
2235 {
2236  if (!_isConnected) return ;
2237  stop();
2238  _chanDev->close();
2239 }
2240 
2242 {
2243  if (isConnected()) return RESULT_ALREADY_DONE;
2244 
2245  if (!_chanDev) return RESULT_INSUFFICIENT_MEMORY;
2246 
2247  {
2249 
2250  // establish the serial connection...
2251  if(!_chanDev->bind(ipStr, port))
2252  return RESULT_INVALID_DATA;
2253  }
2254 
2255  _isConnected = true;
2256 
2258  stopMotor();
2259 
2260  return RESULT_OK;
2261 }
2262 
2263 }}}
#define offsetof(_structure, _field)
Definition: util.h:55
#define RPLIDAR_RESP_MEASUREMENT_CHECKBIT
Definition: rplidar_cmd.h:148
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:178
static bool angleLessThan(const TNode &a, const TNode &b)
#define RPLIDAR_ANS_TYPE_MEASUREMENT_HQ
Definition: rplidar_cmd.h:120
#define RPLIDAR_CMD_FORCE_SCAN
Definition: rplidar_cmd.h:45
#define RPLIDAR_CONF_SCAN_COMMAND_EXPRESS
Definition: rplidar_cmd.h:232
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:247
#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:130
rplidar_response_dense_capsule_measurement_nodes_t _cached_previous_dense_capsuledata
#define RPLIDAR_RESP_MEASUREMENT_ANGLE_SHIFT
Definition: rplidar_cmd.h:149
_u8 flag
Definition: rplidar_cmd.h:2
#define RPLIDAR_ANS_TYPE_MEASUREMENT_CAPSULED
Definition: rplidar_cmd.h:119
_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:128
f
virtual u_result _waitCapsuledNode(rplidar_response_capsule_measurement_nodes_t &node, _u32 timeout=DEFAULT_TIMEOUT)
virtual void disconnect()
Disconnect with the RPLIDAR and close the serial port.
#define RPLIDAR_VARBITSCALE_X4_DEST_VAL
Definition: rplidar_cmd.h:283
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:124
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:279
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:277
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)
#define RPLIDAR_CMD_GET_DEVICE_INFO
Definition: rplidar_cmd.h:50
#define RPLIDAR_ANS_TYPE_DEVHEALTH
Definition: rplidar_cmd.h:115
#define RPLIDAR_CMD_SYNC_BYTE
#define RPLIDAR_RESP_MEASUREMENT_SYNCBIT
Definition: rplidar_cmd.h:143
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:280
#define RPLIDAR_CONF_SCAN_MODE_US_PER_SAMPLE
Definition: rplidar_cmd.h:246
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:176
#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
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:133
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:131
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:248
#define RESULT_OPERATION_TIMEOUT
Definition: rptypes.h:107
#define RPLIDAR_ANS_TYPE_MEASUREMENT
Definition: rplidar_cmd.h:117
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:231
_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)
_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:144
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:250
uint32_t _u32
Definition: rptypes.h:69
#define RPLIDAR_CONF_SCAN_MODE_COUNT
Definition: rplidar_cmd.h:245
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:173
#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 RPLIDAR_VARBITSCALE_X8_DEST_VAL
Definition: rplidar_cmd.h:284
#define RPLIDAR_CONF_SCAN_MODE_TYPICAL
Definition: rplidar_cmd.h:249
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:282
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
const std::string header
virtual u_result getLidarSampleDuration(float &sampleDurationRes, _u16 scanModeID, _u32 timeoutInMs=DEFAULT_TIMEOUT)
#define RPLIDAR_RESP_MEASUREMENT_EXP_SYNC_2
Definition: rplidar_cmd.h:174
#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:285
#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:114
virtual u_result checkMotorCtrlSupport(bool &support, _u32 timeout=DEFAULT_TIMEOUT)
#define RPLIDAR_CMD_SCAN
Definition: rplidar_cmd.h:44
virtual int recvdata(unsigned char *data, size_t size)=0
#define RPLIDAR_VARBITSCALE_X4_SRC_BIT
Definition: rplidar_cmd.h:278


rplidar_ros
Author(s):
autogenerated on Wed Mar 20 2019 07:54:15