MRPT  1.9.9
rplidar_driver.cpp
Go to the documentation of this file.
1 /* +------------------------------------------------------------------------+
2  | Mobile Robot Programming Toolkit (MRPT) |
3  | http://www.mrpt.org/ |
4  | |
5  | Copyright (c) 2005-2018, Individual contributors, see AUTHORS file |
6  | See: http://www.mrpt.org/Authors - All rights reserved. |
7  | Released under BSD License. See details in http://www.mrpt.org/License |
8  +------------------------------------------------------------------------+ */
9 /*
10  * Redistribution and use in source and binary forms, with or without
11  * modification, are permitted provided that the following conditions are met:
12  *
13  * 1. Redistributions of source code must retain the above copyright notice,
14  * this list of conditions and the following disclaimer.
15  *
16  * 2. Redistributions in binary form must reproduce the above copyright notice,
17  * this list of conditions and the following disclaimer in the documentation
18  * and/or other materials provided with the distribution.
19  *
20  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
21  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO,
22  * THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
23  * PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
24  * CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL,
25  * EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO,
26  * PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS;
27  * OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY,
28  * WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR
29  * OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE,
30  * EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
31  *
32  */
33 
34 #include "sdkcommon.h"
35 #include "hal/abs_rxtx.h"
36 #include "hal/thread.h"
37 #include "hal/locker.h"
38 #include "hal/event.h"
39 #include "rplidar_driver_serial.h"
40 
41 #ifndef min
42 #define min(a, b) (((a) < (b)) ? (a) : (b))
43 #endif
44 
46 {
47 // Factory Impl
49 {
50  switch (drivertype)
51  {
53  return new RPlidarDriverSerialImpl();
54  default:
55  return nullptr;
56  }
57 }
58 
59 void RPlidarDriver::DisposeDriver(RPlidarDriver* drv) { delete drv; }
60 // Serial Driver Impl
61 
63  : _isConnected(false), _isScanning(false), _isSupportingMotorCtrl(false)
64 {
69 }
70 
72 {
73  // force disconnection
74  disconnect();
75 
77 }
78 
80  const char* port_path, _u32 baudrate, _u32 flag)
81 {
82  if (isConnected()) return RESULT_ALREADY_DONE;
83 
84  if (!_rxtx) return RESULT_INSUFFICIENT_MEMORY;
85 
86  {
88 
89  // establish the serial connection...
90  if (!_rxtx->bind(port_path, baudrate) || !_rxtx->open())
91  {
92  return RESULT_INVALID_DATA;
93  }
94 
95  _rxtx->flush(0);
96  }
97 
98  _isConnected = true;
99 
101  stopMotor();
102 
103  return RESULT_OK;
104 }
105 
107 {
108  if (!_isConnected) return;
109  stop();
110  _rxtx->close();
111 }
112 
115 {
116  u_result ans;
117 
118  {
120 
122  {
123  return ans;
124  }
125  }
126  return RESULT_OK;
127 }
128 
130  rplidar_response_device_health_t& healthinfo, _u32 timeout)
131 {
132  u_result ans;
133 
134  if (!isConnected()) return RESULT_OPERATION_FAIL;
135 
137 
138  {
140 
142  {
143  return ans;
144  }
145 
146  rplidar_ans_header_t response_header;
147  if (IS_FAIL(ans = _waitResponseHeader(&response_header, timeout)))
148  {
149  return ans;
150  }
151 
152  // verify whether we got a correct header
153  if (response_header.type != RPLIDAR_ANS_TYPE_DEVHEALTH)
154  {
155  return RESULT_INVALID_DATA;
156  }
157 
158  _u32 header_size =
159  (response_header.size_q30_subtype & RPLIDAR_ANS_HEADER_SIZE_MASK);
160  if (header_size < sizeof(rplidar_response_device_health_t))
161  {
162  return RESULT_INVALID_DATA;
163  }
164 
165  if (_rxtx->waitfordata(header_size, timeout) !=
167  {
169  }
170  _rxtx->recvdata(
171  reinterpret_cast<_u8*>(&healthinfo), sizeof(healthinfo));
172  }
173  return RESULT_OK;
174 }
175 
177  rplidar_response_device_info_t& info, _u32 timeout)
178 {
179  u_result ans;
180 
181  if (!isConnected()) return RESULT_OPERATION_FAIL;
182 
184 
185  {
187 
189  {
190  return ans;
191  }
192 
193  rplidar_ans_header_t response_header;
194  if (IS_FAIL(ans = _waitResponseHeader(&response_header, timeout)))
195  {
196  return ans;
197  }
198 
199  // verify whether we got a correct header
200  if (response_header.type != RPLIDAR_ANS_TYPE_DEVINFO)
201  {
202  return RESULT_INVALID_DATA;
203  }
204 
205  _u32 header_size =
206  (response_header.size_q30_subtype & RPLIDAR_ANS_HEADER_SIZE_MASK);
207  if (header_size < sizeof(rplidar_response_device_info_t))
208  {
209  return RESULT_INVALID_DATA;
210  }
211 
212  if (_rxtx->waitfordata(header_size, timeout) !=
214  {
216  }
217 
218  _rxtx->recvdata(reinterpret_cast<_u8*>(&info), sizeof(info));
219  }
220  return RESULT_OK;
221 }
222 
224  bool inExpressMode, size_t count, float& frequency, bool& is4kmode)
225 {
226  _u16 sample_duration = inExpressMode ? _cached_sampleduration_express
228  frequency = 1000000.0f / (count * sample_duration);
229 
230  if (sample_duration <= 277)
231  {
232  is4kmode = true;
233  }
234  else
235  {
236  is4kmode = false;
237  }
238 
239  return RESULT_OK;
240 }
241 
243 {
244  u_result ans;
245  if (!isConnected()) return RESULT_OPERATION_FAIL;
246  if (_isScanning) return RESULT_ALREADY_DONE;
247 
248  stop(); // force the previous operation to stop
249 
250  {
252 
253  if (IS_FAIL(
254  ans = _sendCommand(
256  {
257  return ans;
258  }
259 
260  // waiting for confirmation
261  rplidar_ans_header_t response_header;
262  if (IS_FAIL(ans = _waitResponseHeader(&response_header, timeout)))
263  {
264  return ans;
265  }
266 
267  // verify whether we got a correct header
268  if (response_header.type != RPLIDAR_ANS_TYPE_MEASUREMENT)
269  {
270  return RESULT_INVALID_DATA;
271  }
272 
273  _u32 header_size =
274  (response_header.size_q30_subtype & RPLIDAR_ANS_HEADER_SIZE_MASK);
275  if (header_size < sizeof(rplidar_response_measurement_node_t))
276  {
277  return RESULT_INVALID_DATA;
278  }
279 
280  _isScanning = true;
282  if (_cachethread.getHandle() == 0)
283  {
284  return RESULT_OPERATION_FAIL;
285  }
286  }
287  return RESULT_OK;
288 }
289 
291  bool& support, _u32 timeout)
292 {
293  rplidar_response_device_info_t devinfo;
294 
295  support = false;
296  u_result ans = getDeviceInfo(devinfo, timeout);
297 
298  if (IS_FAIL(ans)) return ans;
299 
300  if (devinfo.firmware_version >= ((0x1 << 8) | 17))
301  {
302  support = true;
303  rplidar_response_sample_rate_t sample_rate;
304  getSampleDuration_uS(sample_rate);
305  _cached_sampleduration_express = sample_rate.express_sample_duration_us;
306  _cached_sampleduration_std = sample_rate.std_sample_duration_us;
307  }
308 
309  return RESULT_OK;
310 }
311 
313  bool fixedAngle, _u32 timeout)
314 {
315  u_result ans;
316  if (!isConnected()) return RESULT_OPERATION_FAIL;
317  if (_isScanning) return RESULT_ALREADY_DONE;
318 
319  stop(); // force the previous operation to stop
320 
321  {
323 
324  rplidar_payload_express_scan_t scanReq;
325  scanReq.working_mode =
328  scanReq.reserved = 0;
329 
330  if (IS_FAIL(
331  ans = _sendCommand(
332  RPLIDAR_CMD_EXPRESS_SCAN, &scanReq, sizeof(scanReq))))
333  {
334  return ans;
335  }
336 
337  // waiting for confirmation
338  rplidar_ans_header_t response_header;
339  if (IS_FAIL(ans = _waitResponseHeader(&response_header, timeout)))
340  {
341  return ans;
342  }
343 
344  // verify whether we got a correct header
345  if (response_header.type != RPLIDAR_ANS_TYPE_MEASUREMENT_CAPSULED)
346  {
347  return RESULT_INVALID_DATA;
348  }
349 
350  _u32 header_size =
351  (response_header.size_q30_subtype & RPLIDAR_ANS_HEADER_SIZE_MASK);
352  if (header_size < sizeof(rplidar_response_capsule_measurement_nodes_t))
353  {
354  return RESULT_INVALID_DATA;
355  }
356 
357  _isScanning = true;
358  _cachethread =
360  if (_cachethread.getHandle() == 0)
361  {
362  return RESULT_OPERATION_FAIL;
363  }
364  }
365  return RESULT_OK;
366 }
367 
368 u_result RPlidarDriverSerialImpl::startScan(bool force, bool autoExpressMode)
369 {
370  bool isExpressModeSupported;
371  u_result ans;
372 
373  if (autoExpressMode)
374  {
375  ans = checkExpressScanSupported(isExpressModeSupported);
376 
377  if (IS_FAIL(ans)) return ans;
378 
379  if (isExpressModeSupported)
380  {
381  return startScanExpress(false);
382  }
383  }
384 
385  return startScanNormal(force);
386 }
387 
389 {
390  u_result ans;
392 
393  {
395 
397  {
398  return ans;
399  }
400  }
401 
402  return RESULT_OK;
403 }
404 
406 {
407  rplidar_response_measurement_node_t local_buf[128];
408  size_t count = 128;
409  rplidar_response_measurement_node_t local_scan[MAX_SCAN_NODES];
410  size_t scan_count = 0;
411  u_result ans;
412  memset(local_scan, 0, sizeof(local_scan));
413 
415  local_buf,
416  count); // // always discard the first data since it may be incomplete
417 
418  while (_isScanning)
419  {
420  if (IS_FAIL(ans = _waitScanData(local_buf, count)))
421  {
422  if (ans != RESULT_OPERATION_TIMEOUT)
423  {
424  _isScanning = false;
425  return RESULT_OPERATION_FAIL;
426  }
427  }
428 
429  for (size_t pos = 0; pos < count; ++pos)
430  {
431  if (local_buf[pos].sync_quality & RPLIDAR_RESP_MEASUREMENT_SYNCBIT)
432  {
433  // only publish the data when it contains a full 360 degree scan
434 
435  if ((local_scan[0].sync_quality &
437  {
438  _lock.lock();
439  memcpy(
440  _cached_scan_node_buf, local_scan,
441  scan_count *
442  sizeof(rplidar_response_measurement_node_t));
443  _cached_scan_node_count = scan_count;
444  _dataEvt.set();
445  _lock.unlock();
446  }
447  scan_count = 0;
448  }
449  local_scan[scan_count++] = local_buf[pos];
450  if (scan_count == _countof(local_scan))
451  scan_count -= 1; // prevent overflow
452  }
453  }
454  _isScanning = false;
455  return RESULT_OK;
456 }
457 
459  const rplidar_response_capsule_measurement_nodes_t& capsule,
460  rplidar_response_measurement_node_t* nodebuffer, size_t& nodeCount)
461 {
462  nodeCount = 0;
464  {
465  int diffAngle_q8;
466  int currentStartAngle_q8 =
467  ((capsule.start_angle_sync_q6 & 0x7FFF) << 2);
468  int prevStartAngle_q8 =
469  ((_cached_previous_capsuledata.start_angle_sync_q6 & 0x7FFF) << 2);
470 
471  diffAngle_q8 = (currentStartAngle_q8) - (prevStartAngle_q8);
472  if (prevStartAngle_q8 > currentStartAngle_q8)
473  {
474  diffAngle_q8 += (360 << 8);
475  }
476 
477  int angleInc_q16 = (diffAngle_q8 << 3);
478  int currentAngle_raw_q16 = (prevStartAngle_q8 << 8);
479  for (size_t pos = 0;
480  pos < _countof(_cached_previous_capsuledata.cabins); ++pos)
481  {
482  int dist_q2[2];
483  int angle_q6[2];
484  int syncBit[2];
485 
486  dist_q2[0] =
487  (_cached_previous_capsuledata.cabins[pos].distance_angle_1 &
488  0xFFFC);
489  dist_q2[1] =
490  (_cached_previous_capsuledata.cabins[pos].distance_angle_2 &
491  0xFFFC);
492 
493  int angle_offset1_q3 =
494  ((_cached_previous_capsuledata.cabins[pos].offset_angles_q3 &
495  0xF) |
496  ((_cached_previous_capsuledata.cabins[pos].distance_angle_1 &
497  0x3)
498  << 4));
499  int angle_offset2_q3 =
500  ((_cached_previous_capsuledata.cabins[pos].offset_angles_q3 >>
501  4) |
502  ((_cached_previous_capsuledata.cabins[pos].distance_angle_2 &
503  0x3)
504  << 4));
505 
506  angle_q6[0] =
507  ((currentAngle_raw_q16 - (angle_offset1_q3 << 13)) >> 10);
508  syncBit[0] = (((currentAngle_raw_q16 + angleInc_q16) %
509  (360 << 16)) < angleInc_q16)
510  ? 1
511  : 0;
512  currentAngle_raw_q16 += angleInc_q16;
513 
514  angle_q6[1] =
515  ((currentAngle_raw_q16 - (angle_offset2_q3 << 13)) >> 10);
516  syncBit[1] = (((currentAngle_raw_q16 + angleInc_q16) %
517  (360 << 16)) < angleInc_q16)
518  ? 1
519  : 0;
520  currentAngle_raw_q16 += angleInc_q16;
521 
522  for (int cpos = 0; cpos < 2; ++cpos)
523  {
524  if (angle_q6[cpos] < 0) angle_q6[cpos] += (360 << 6);
525  if (angle_q6[cpos] >= (360 << 6)) angle_q6[cpos] -= (360 << 6);
526 
527  rplidar_response_measurement_node_t node;
528 
529  node.sync_quality = (syncBit[cpos] | ((!syncBit[cpos]) << 1));
530  if (dist_q2[cpos])
531  node.sync_quality |=
533 
534  node.angle_q6_checkbit = (1 | (angle_q6[cpos] << 1));
535  node.distance_q2 = dist_q2[cpos];
536 
537  nodebuffer[nodeCount++] = node;
538  }
539  }
540  }
541 
544 }
545 
547 {
548  rplidar_response_capsule_measurement_nodes_t capsule_node;
549  rplidar_response_measurement_node_t local_buf[128];
550  size_t count = 128;
551  rplidar_response_measurement_node_t local_scan[MAX_SCAN_NODES];
552  size_t scan_count = 0;
553  u_result ans;
554  memset(local_scan, 0, sizeof(local_scan));
555 
556  _waitCapsuledNode(capsule_node); // // always discard the first data since
557  // it may be incomplete
558 
559  while (_isScanning)
560  {
561  if (IS_FAIL(ans = _waitCapsuledNode(capsule_node)))
562  {
563  if (ans != RESULT_OPERATION_TIMEOUT && ans != RESULT_INVALID_DATA)
564  {
565  _isScanning = false;
566  return RESULT_OPERATION_FAIL;
567  }
568  else
569  {
570  // current data is invalid, do not use it.
571  continue;
572  }
573  }
574 
575  _capsuleToNormal(capsule_node, local_buf, count);
576 
577  for (size_t pos = 0; pos < count; ++pos)
578  {
579  if (local_buf[pos].sync_quality & RPLIDAR_RESP_MEASUREMENT_SYNCBIT)
580  {
581  // only publish the data when it contains a full 360 degree scan
582 
583  if ((local_scan[0].sync_quality &
585  {
586  _lock.lock();
587  memcpy(
588  _cached_scan_node_buf, local_scan,
589  scan_count *
590  sizeof(rplidar_response_measurement_node_t));
591  _cached_scan_node_count = scan_count;
592  _dataEvt.set();
593  _lock.unlock();
594  }
595  scan_count = 0;
596  }
597  local_scan[scan_count++] = local_buf[pos];
598  if (scan_count == _countof(local_scan))
599  scan_count -= 1; // prevent overflow
600  }
601  }
602  _isScanning = false;
603 
604  return RESULT_OK;
605 }
606 
608  rplidar_response_measurement_node_t* nodebuffer, size_t& count,
609  _u32 timeout)
610 {
611  switch (_dataEvt.wait(timeout))
612  {
614  count = 0;
617  {
618  if (_cached_scan_node_count == 0)
619  return RESULT_OPERATION_TIMEOUT; // consider as timeout
620 
622 
623  size_t size_to_copy = min(count, _cached_scan_node_count);
624 
625  memcpy(
626  nodebuffer, _cached_scan_node_buf,
627  size_to_copy * sizeof(rplidar_response_measurement_node_t));
628  count = size_to_copy;
630  }
631  return RESULT_OK;
632 
633  default:
634  count = 0;
635  return RESULT_OPERATION_FAIL;
636  }
637 }
638 
640  rplidar_response_measurement_node_t* nodebuffer, size_t count)
641 {
642  float inc_origin_angle = 360.0f / count;
643  size_t i = 0;
644 
645  // Tune head
646  for (i = 0; i < count && nodebuffer[i].distance_q2 == 0; i++)
647  ;
648 
649  // all the data is invalid
650  if (i == count) return RESULT_OPERATION_FAIL;
651 
652  while (i != 0)
653  {
654  i--;
655  float expect_angle = (nodebuffer[i + 1].angle_q6_checkbit >>
657  64.0f -
658  inc_origin_angle;
659  if (expect_angle < 0.0f) expect_angle = 0.0f;
660  _u16 checkbit =
661  nodebuffer[i].angle_q6_checkbit & RPLIDAR_RESP_MEASUREMENT_CHECKBIT;
662  nodebuffer[i].angle_q6_checkbit =
663  (((_u16)(expect_angle * 64.0f))
665  checkbit;
666  }
667 
668  // Tune tail
669  for (i = count - 1; nodebuffer[i].distance_q2 == 0; i--)
670  ;
671 
672  while (i != (count - 1))
673  {
674  i++;
675  float expect_angle = (nodebuffer[i - 1].angle_q6_checkbit >>
677  64.0f +
678  inc_origin_angle;
679  if (expect_angle > 360.0f) expect_angle -= 360.0f;
680  _u16 checkbit =
681  nodebuffer[i].angle_q6_checkbit & RPLIDAR_RESP_MEASUREMENT_CHECKBIT;
682  nodebuffer[i].angle_q6_checkbit =
683  (((_u16)(expect_angle * 64.0f))
685  checkbit;
686  }
687 
688  // Fill invalid angle in the scan
689  float frontAngle = (nodebuffer[0].angle_q6_checkbit >>
691  64.0f;
692  for (i = 1; i < count; i++)
693  {
694  if (nodebuffer[i].distance_q2 == 0)
695  {
696  float expect_angle = frontAngle + i * inc_origin_angle;
697  if (expect_angle > 360.0f) expect_angle -= 360.0f;
698  _u16 checkbit = nodebuffer[i].angle_q6_checkbit &
700  nodebuffer[i].angle_q6_checkbit =
701  (((_u16)(expect_angle * 64.0f))
703  checkbit;
704  }
705  }
706 
707  // Reorder the scan according to the angle value
708  for (i = 0; i < (count - 1); i++)
709  {
710  for (size_t j = (i + 1); j < count; j++)
711  {
712  if (nodebuffer[i].angle_q6_checkbit >
713  nodebuffer[j].angle_q6_checkbit)
714  {
715  rplidar_response_measurement_node_t temp = nodebuffer[i];
716  nodebuffer[i] = nodebuffer[j];
717  nodebuffer[j] = temp;
718  }
719  }
720  }
721 
722  return RESULT_OK;
723 }
724 
726  rplidar_response_measurement_node_t* node, _u32 timeout)
727 {
728  int recvPos = 0;
729  _u32 startTs = getms();
730  _u8 recvBuffer[sizeof(rplidar_response_measurement_node_t)];
731  _u8* nodeBuffer = (_u8*)node;
732  _u32 waitTime;
733 
734  while ((waitTime = getms() - startTs) <= timeout)
735  {
736  size_t remainSize =
737  sizeof(rplidar_response_measurement_node_t) - recvPos;
738  size_t recvSize;
739 
740  int ans = _rxtx->waitfordata(remainSize, timeout - waitTime, &recvSize);
742  return RESULT_OPERATION_FAIL;
743  else if (ans == rp::hal::serial_rxtx::ANS_TIMEOUT)
745 
746  if (recvSize > remainSize) recvSize = remainSize;
747 
748  _rxtx->recvdata(recvBuffer, recvSize);
749 
750  for (size_t pos = 0; pos < recvSize; ++pos)
751  {
752  _u8 currentByte = recvBuffer[pos];
753  switch (recvPos)
754  {
755  case 0: // expect the sync bit and its reverse in this byte
756  {
757  _u8 tmp = (currentByte >> 1);
758  if ((tmp ^ currentByte) & 0x1)
759  {
760  // pass
761  }
762  else
763  {
764  continue;
765  }
766  }
767  break;
768  case 1: // expect the highest bit to be 1
769  {
770  if (currentByte & RPLIDAR_RESP_MEASUREMENT_CHECKBIT)
771  {
772  // pass
773  }
774  else
775  {
776  recvPos = 0;
777  continue;
778  }
779  }
780  break;
781  }
782  nodeBuffer[recvPos++] = currentByte;
783 
784  if (recvPos == sizeof(rplidar_response_measurement_node_t))
785  {
786  return RESULT_OK;
787  }
788  }
789  }
790 
792 }
793 
795  rplidar_response_measurement_node_t* nodebuffer, size_t& count,
796  _u32 timeout)
797 {
798  if (!_isConnected)
799  {
800  count = 0;
801  return RESULT_OPERATION_FAIL;
802  }
803 
804  size_t recvNodeCount = 0;
805  _u32 startTs = getms();
806  _u32 waitTime;
807  u_result ans;
808 
809  while ((waitTime = getms() - startTs) <= timeout && recvNodeCount < count)
810  {
811  rplidar_response_measurement_node_t node;
812  if (IS_FAIL(ans = _waitNode(&node, timeout - waitTime)))
813  {
814  return ans;
815  }
816 
817  nodebuffer[recvNodeCount++] = node;
818 
819  if (recvNodeCount == count) return RESULT_OK;
820  }
821  count = recvNodeCount;
823 }
824 
826  rplidar_response_capsule_measurement_nodes_t& node, _u32 timeout)
827 {
828  int recvPos = 0;
829  _u32 startTs = getms();
830  _u8 recvBuffer[sizeof(rplidar_response_capsule_measurement_nodes_t)];
831  _u8* nodeBuffer = (_u8*)&node;
832  _u32 waitTime;
833 
834  while ((waitTime = getms() - startTs) <= timeout)
835  {
836  size_t remainSize =
837  sizeof(rplidar_response_capsule_measurement_nodes_t) - recvPos;
838  size_t recvSize;
839 
840  int ans = _rxtx->waitfordata(remainSize, timeout - waitTime, &recvSize);
842  return RESULT_OPERATION_FAIL;
843  else if (ans == rp::hal::serial_rxtx::ANS_TIMEOUT)
845 
846  if (recvSize > remainSize) recvSize = remainSize;
847 
848  _rxtx->recvdata(recvBuffer, recvSize);
849 
850  for (size_t pos = 0; pos < recvSize; ++pos)
851  {
852  _u8 currentByte = recvBuffer[pos];
853  switch (recvPos)
854  {
855  case 0: // expect the sync bit 1
856  {
857  _u8 tmp = (currentByte >> 4);
859  {
860  // pass
861  }
862  else
863  {
865  continue;
866  }
867  }
868  break;
869  case 1: // expect the sync bit 2
870  {
871  _u8 tmp = (currentByte >> 4);
873  {
874  // pass
875  }
876  else
877  {
878  recvPos = 0;
880  continue;
881  }
882  }
883  break;
884  }
885  nodeBuffer[recvPos++] = currentByte;
886 
887  if (recvPos == sizeof(rplidar_response_capsule_measurement_nodes_t))
888  {
889  // calc the checksum ...
890  _u8 checksum = 0;
891  _u8 recvChecksum =
892  ((node.s_checksum_1 & 0xF) | (node.s_checksum_2 << 4));
893  for (size_t cpos = offsetof(
894  rplidar_response_capsule_measurement_nodes_t,
896  cpos <
897  sizeof(rplidar_response_capsule_measurement_nodes_t);
898  ++cpos)
899  {
900  checksum ^= nodeBuffer[cpos];
901  }
902  if (recvChecksum == checksum)
903  {
904  // only consider vaild if the checksum matches...
905  if (node.start_angle_sync_q6 &
907  {
908  // this is the first capsule frame in logic, discard the
909  // previous cached data...
911  return RESULT_OK;
912  }
913  return RESULT_OK;
914  }
916  return RESULT_INVALID_DATA;
917  }
918  }
919  }
922 }
923 
925  _u8 cmd, const void* payload, size_t payloadsize)
926 {
927  _u8 pkt_header[10];
928  rplidar_cmd_packet_t* header =
929  reinterpret_cast<rplidar_cmd_packet_t*>(pkt_header);
930  _u8 checksum = 0;
931 
932  if (!_isConnected) return RESULT_OPERATION_FAIL;
933 
934  if (payloadsize && payload)
935  {
937  }
938 
939  header->syncByte = RPLIDAR_CMD_SYNC_BYTE;
940  header->cmd_flag = cmd;
941 
942  // send header first
943  _rxtx->senddata(pkt_header, 2);
944 
945  if (cmd & RPLIDAR_CMDFLAG_HAS_PAYLOAD)
946  {
947  checksum ^= RPLIDAR_CMD_SYNC_BYTE;
948  checksum ^= cmd;
949  checksum ^= (payloadsize & 0xFF);
950 
951  // calc checksum
952  for (size_t pos = 0; pos < payloadsize; ++pos)
953  {
954  checksum ^= ((_u8*)payload)[pos];
955  }
956 
957  // send size
958  _u8 sizebyte = payloadsize;
959  _rxtx->senddata(&sizebyte, 1);
960 
961  // send payload
962  _rxtx->senddata((const _u8*)payload, sizebyte);
963 
964  // send checksum
965  _rxtx->senddata(&checksum, 1);
966  }
967 
968  return RESULT_OK;
969 }
970 
972  rplidar_ans_header_t* header, _u32 timeout)
973 {
974  int recvPos = 0;
975  _u32 startTs = getms();
976  _u8 recvBuffer[sizeof(rplidar_ans_header_t)];
977  _u8* headerBuffer = reinterpret_cast<_u8*>(header);
978  _u32 waitTime;
979 
980  while ((waitTime = getms() - startTs) <= timeout)
981  {
982  size_t remainSize = sizeof(rplidar_ans_header_t) - recvPos;
983  size_t recvSize;
984 
985  int ans = _rxtx->waitfordata(remainSize, timeout - waitTime, &recvSize);
987  return RESULT_OPERATION_FAIL;
988  else if (ans == rp::hal::serial_rxtx::ANS_TIMEOUT)
990 
991  if (recvSize > remainSize) recvSize = remainSize;
992 
993  _rxtx->recvdata(recvBuffer, recvSize);
994 
995  for (size_t pos = 0; pos < recvSize; ++pos)
996  {
997  _u8 currentByte = recvBuffer[pos];
998  switch (recvPos)
999  {
1000  case 0:
1001  if (currentByte != RPLIDAR_ANS_SYNC_BYTE1)
1002  {
1003  continue;
1004  }
1005 
1006  break;
1007  case 1:
1008  if (currentByte != RPLIDAR_ANS_SYNC_BYTE2)
1009  {
1010  recvPos = 0;
1011  continue;
1012  }
1013  break;
1014  }
1015  headerBuffer[recvPos++] = currentByte;
1016 
1017  if (recvPos == sizeof(rplidar_ans_header_t))
1018  {
1019  return RESULT_OK;
1020  }
1021  }
1022  }
1023 
1024  return RESULT_OPERATION_TIMEOUT;
1025 }
1026 
1028 {
1029  _isScanning = false;
1030  _cachethread.join();
1031 }
1032 
1034  rplidar_response_sample_rate_t& rateInfo, _u32 timeout)
1035 {
1036  if (!isConnected()) return RESULT_OPERATION_FAIL;
1037 
1039 
1040  rplidar_response_device_info_t devinfo;
1041  // 1. fetch the device version first...
1042  u_result ans = getDeviceInfo(devinfo, timeout);
1043 
1044  rateInfo.express_sample_duration_us = _cached_sampleduration_express;
1045  rateInfo.std_sample_duration_us = _cached_sampleduration_std;
1046 
1047  if (devinfo.firmware_version < ((0x1 << 8) | 17))
1048  {
1049  // provide fake data...
1050 
1051  return RESULT_OK;
1052  }
1053 
1054  {
1056 
1058  {
1059  return ans;
1060  }
1061 
1062  rplidar_ans_header_t response_header;
1063  if (IS_FAIL(ans = _waitResponseHeader(&response_header, timeout)))
1064  {
1065  return ans;
1066  }
1067 
1068  // verify whether we got a correct header
1069  if (response_header.type != RPLIDAR_ANS_TYPE_SAMPLE_RATE)
1070  {
1071  return RESULT_INVALID_DATA;
1072  }
1073 
1074  _u32 header_size =
1075  (response_header.size_q30_subtype & RPLIDAR_ANS_HEADER_SIZE_MASK);
1076  if (header_size < sizeof(rplidar_response_sample_rate_t))
1077  {
1078  return RESULT_INVALID_DATA;
1079  }
1080 
1081  if (_rxtx->waitfordata(header_size, timeout) !=
1083  {
1084  return RESULT_OPERATION_TIMEOUT;
1085  }
1086  _rxtx->recvdata(reinterpret_cast<_u8*>(&rateInfo), sizeof(rateInfo));
1087  }
1088  return RESULT_OK;
1089 }
1090 
1092  bool& support, _u32 timeout)
1093 {
1094  u_result ans;
1095  support = false;
1096 
1097  if (!isConnected()) return RESULT_OPERATION_FAIL;
1098 
1100 
1101  {
1103 
1104  rplidar_payload_acc_board_flag_t flag;
1105  flag.reserved = 0;
1106 
1107  if (IS_FAIL(
1108  ans = _sendCommand(
1109  RPLIDAR_CMD_GET_ACC_BOARD_FLAG, &flag, sizeof(flag))))
1110  {
1111  return ans;
1112  }
1113 
1114  rplidar_ans_header_t response_header;
1115  if (IS_FAIL(ans = _waitResponseHeader(&response_header, timeout)))
1116  {
1117  return ans;
1118  }
1119 
1120  // verify whether we got a correct header
1121  if (response_header.type != RPLIDAR_ANS_TYPE_ACC_BOARD_FLAG)
1122  {
1123  return RESULT_INVALID_DATA;
1124  }
1125 
1126  _u32 header_size =
1127  (response_header.size_q30_subtype & RPLIDAR_ANS_HEADER_SIZE_MASK);
1128  if (header_size < sizeof(rplidar_response_acc_board_flag_t))
1129  {
1130  return RESULT_INVALID_DATA;
1131  }
1132 
1133  if (_rxtx->waitfordata(header_size, timeout) !=
1135  {
1136  return RESULT_OPERATION_TIMEOUT;
1137  }
1138  rplidar_response_acc_board_flag_t acc_board_flag;
1139  _rxtx->recvdata(
1140  reinterpret_cast<_u8*>(&acc_board_flag), sizeof(acc_board_flag));
1141 
1142  if (acc_board_flag.support_flag &
1144  {
1145  support = true;
1146  }
1147  }
1148  return RESULT_OK;
1149 }
1150 
1152 {
1153  u_result ans;
1154  rplidar_payload_motor_pwm_t motor_pwm;
1155  motor_pwm.pwm_value = pwm;
1156 
1157  {
1159 
1160  if (IS_FAIL(
1161  ans = _sendCommand(
1162  RPLIDAR_CMD_SET_MOTOR_PWM, (const _u8*)&motor_pwm,
1163  sizeof(motor_pwm))))
1164  {
1165  return ans;
1166  }
1167  }
1168 
1169  return RESULT_OK;
1170 }
1171 
1173 {
1175  { // RPLIDAR A2
1177  delay(500);
1178  return RESULT_OK;
1179  }
1180  else
1181  { // RPLIDAR A1
1183  _rxtx->clearDTR();
1184  delay(500);
1185  return RESULT_OK;
1186  }
1187 }
1188 
1190 {
1192  { // RPLIDAR A2
1193  setMotorPWM(0);
1194  delay(500);
1195  return RESULT_OK;
1196  }
1197  else
1198  { // RPLIDAR A1
1200  _rxtx->setDTR();
1201  delay(500);
1202  return RESULT_OK;
1203  }
1204 }
1205 }
1206 
1207 
virtual int recvdata(unsigned char *data, size_t size)=0
#define offsetof(_structure, _field)
Definition: util.h:52
#define RPLIDAR_RESP_MEASUREMENT_CHECKBIT
Definition: rplidar_cmd.h:112
#define CLASS_THREAD(c, x)
Definition: thread.h:37
#define RPLIDAR_RESP_MEASUREMENT_EXP_SYNCBIT
Definition: rplidar_cmd.h:142
virtual bool bind(const char *portname, _u32 baudrate, _u32 flags=0)=0
GLuint GLuint GLsizei count
Definition: glext.h:3528
#define RPLIDAR_CMD_FORCE_SCAN
Definition: rplidar_cmd.h:44
#define RPLIDAR_EXPRESS_SCAN_MODE_FIXANGLE
Definition: rplidar_cmd.h:67
virtual u_result startScanNormal(bool force, _u32 timeout=DEFAULT_TIMEOUT)
virtual bool isConnected()
Returns TRUE when the connection has been established.
#define min(a, b)
#define RPLIDAR_RESP_MEASUREMENT_ANGLE_SHIFT
Definition: rplidar_cmd.h:113
#define RPLIDAR_ANS_TYPE_MEASUREMENT_CAPSULED
Definition: rplidar_cmd.h:93
_u16 angle_q6_checkbit
Definition: rplidar_cmd.h:20
virtual u_result ascendScanData(rplidar_response_measurement_node_t *nodebuffer, size_t count)
Ascending the scan data according to the angle value in the scan.
void unlock()
Definition: locker.h:115
void _capsuleToNormal(const rplidar_response_capsule_measurement_nodes_t &capsule, rplidar_response_measurement_node_t *nodebuffer, size_t &nodeCount)
virtual u_result getFrequency(bool inExpressMode, size_t count, float &frequency, bool &is4kmode)
Calcuate RPLIDAR&#39;s current scanning frequency from the given scan data Please refer to the applicatio...
_u16 start_angle_sync_q6
Definition: rplidar_cmd.h:21
#define RPLIDAR_ANS_TYPE_SAMPLE_RATE
Definition: rplidar_cmd.h:96
void set(bool isSignal=true)
Definition: event.h:65
virtual u_result getSampleDuration_uS(rplidar_response_sample_rate_t &rateInfo, _u32 timeout=DEFAULT_TIMEOUT)
Get the sample duration information of the RPLIDAR.
#define RPLIDAR_ANS_HEADER_SIZE_MASK
_word_size_t getHandle()
Definition: thread.h:69
#define RESULT_OK
Definition: rptypes.h:97
virtual u_result connect(const char *port_path, _u32 baudrate, _u32 flag)
Open the specified serial port and connect to a target RPLIDAR device.
virtual u_result startScanExpress(bool fixedAngle, _u32 timeout=DEFAULT_TIMEOUT)
#define RPLIDAR_CMD_GET_DEVICE_INFO
Definition: rplidar_cmd.h:48
#define RPLIDAR_ANS_TYPE_DEVHEALTH
Definition: rplidar_cmd.h:89
#define RPLIDAR_CMD_SYNC_BYTE
#define RPLIDAR_RESP_MEASUREMENT_SYNCBIT
Definition: rplidar_cmd.h:110
virtual void setDTR()=0
virtual int senddata(const unsigned char *data, size_t size)=0
static serial_rxtx * CreateRxTx()
#define RESULT_INSUFFICIENT_MEMORY
Definition: rptypes.h:106
#define RPLIDAR_ANS_SYNC_BYTE1
virtual void disconnect()
Disconnect with the RPLIDAR and close the serial port.
#define delay(x)
Definition: win32/timer.h:38
#define RPLIDAR_CMD_GET_SAMPLERATE
Definition: rplidar_cmd.h:51
static void ReleaseRxTx(serial_rxtx *)
#define IS_FAIL(x)
Definition: rptypes.h:109
rplidar_response_capsule_measurement_nodes_t _cached_previous_capsuledata
virtual u_result grabScanData(rplidar_response_measurement_node_t *nodebuffer, size_t &count, _u32 timeout=DEFAULT_TIMEOUT)
Wait and grab a complete 0-360 degree scan data previously received.
uint8_t _u8
Definition: rptypes.h:60
virtual u_result stopMotor()
Stop RPLIDAR&#39;s motor when using accessory board.
u_result join(unsigned long timeout=-1)
#define RPLIDAR_CMD_RESET
Definition: rplidar_cmd.h:45
nv_oem6_header_t header
Novatel frame: NV_OEM6_BESTPOS.
#define RPLIDAR_RESP_ACC_BOARD_FLAG_MOTOR_CTRL_SUPPORT_MASK
Definition: rplidar_cmd.h:100
virtual bool open()=0
#define RPLIDAR_CMDFLAG_HAS_PAYLOAD
#define RPLIDAR_ANS_TYPE_ACC_BOARD_FLAG
Definition: rplidar_cmd.h:98
virtual void close()=0
virtual u_result checkMotorCtrlSupport(bool &support, _u32 timeout=DEFAULT_TIMEOUT)
Check whether the device support motor control.
virtual u_result startScan(bool force=false, bool autoExpressMode=true)
Ask the RPLIDAR core system to enter the scan mode(Normal/Express, Express mode is 4k mode) A backgro...
#define RPLIDAR_CMD_SET_MOTOR_PWM
Definition: rplidar_cmd.h:57
_u8 sync_quality
Definition: rplidar_cmd.h:19
#define getms()
Definition: linux/timer.h:55
#define RPLIDAR_CMD_EXPRESS_SCAN
Definition: rplidar_cmd.h:54
virtual u_result startMotor()
Start RPLIDAR&#39;s motor when using accessory board.
virtual u_result setMotorPWM(_u16 pwm)
Set the RPLIDAR&#39;s motor pwm when using accessory board, currently valid for A2 only.
Locker::LOCK_STATUS lock(unsigned long timeout=0xFFFFFFFF)
Definition: locker.h:56
u_result _waitResponseHeader(rplidar_ans_header_t *header, _u32 timeout=DEFAULT_TIMEOUT)
#define RESULT_OPERATION_TIMEOUT
Definition: rptypes.h:102
u_result _waitNode(rplidar_response_measurement_node_t *node, _u32 timeout=DEFAULT_TIMEOUT)
#define RPLIDAR_ANS_TYPE_MEASUREMENT
Definition: rplidar_cmd.h:91
#define RPLIDAR_CMD_GET_ACC_BOARD_FLAG
Definition: rplidar_cmd.h:58
_u16 distance_q2
Definition: rplidar_cmd.h:21
virtual u_result checkExpressScanSupported(bool &support, _u32 timeout=DEFAULT_TIMEOUT)
Check whether the device support express mode.
u_result _sendCommand(_u8 cmd, const void *payload=nullptr, size_t payloadsize=0)
#define RPLIDAR_RESP_MEASUREMENT_QUALITY_SHIFT
Definition: rplidar_cmd.h:111
virtual void clearDTR()=0
virtual u_result getDeviceInfo(rplidar_response_device_info_t &, _u32 timeout=DEFAULT_TIMEOUT)
Get the device information of the RPLIDAR include the serial number, firmware version, device model etc.
virtual u_result reset(_u32 timeout=DEFAULT_TIMEOUT)
Ask the RPLIDAR core system to reset it self The host system can use the Reset operation to help RPLI...
rplidar_response_measurement_node_t _cached_scan_node_buf[2048]
uint32_t _u32
Definition: rptypes.h:66
unsigned long wait(unsigned long timeout=0xFFFFFFFF)
Definition: event.h:94
u_result _waitCapsuledNode(rplidar_response_capsule_measurement_nodes_t &node, _u32 timeout=DEFAULT_TIMEOUT)
#define RPLIDAR_RESP_MEASUREMENT_EXP_SYNC_1
Definition: rplidar_cmd.h:139
#define DEFAULT_MOTOR_PWM
Definition: rplidar_cmd.h:75
virtual u_result stop(_u32 timeout=DEFAULT_TIMEOUT)
Ask the RPLIDAR core system to stop the current scan operation and enter idle state.
virtual u_result getHealth(rplidar_response_device_health_t &, _u32 timeout=DEFAULT_TIMEOUT)
Retrieve the health status of the RPLIDAR The host system can use this operation to check whether RPL...
#define RESULT_OPERATION_FAIL
Definition: rptypes.h:101
#define RESULT_ALREADY_DONE
Definition: rptypes.h:99
#define RPLIDAR_CMD_STOP
Definition: rplidar_cmd.h:42
virtual void flush(_u32 flags)=0
#define RPLIDAR_RESP_MEASUREMENT_EXP_SYNC_2
Definition: rplidar_cmd.h:140
#define RPLIDAR_CMD_GET_DEVICE_HEALTH
Definition: rplidar_cmd.h:49
uint16_t _u16
Definition: rptypes.h:63
static RPlidarDriver * CreateDriver(_u32 drivertype=DRIVER_TYPE_SERIALPORT)
Create an RPLIDAR Driver Instance This interface should be invoked first before any other operations...
#define RPLIDAR_EXPRESS_SCAN_MODE_NORMAL
Definition: rplidar_cmd.h:66
#define RPLIDAR_ANS_SYNC_BYTE2
#define _countof(_Array)
Definition: util.h:40
virtual int waitfordata(size_t data_count, _u32 timeout=-1, size_t *returned_size=nullptr)=0
#define RESULT_INVALID_DATA
Definition: rptypes.h:100
static void DisposeDriver(RPlidarDriver *drv)
Dispose the RPLIDAR Driver Instance specified by the drv parameter Applications should invoke this in...
void memcpy(void *dest, size_t destSize, const void *src, size_t copyCount) noexcept
An OS and compiler independent version of "memcpy".
Definition: os.cpp:356
uint32_t u_result
Definition: rptypes.h:95
#define RPLIDAR_ANS_TYPE_DEVINFO
Definition: rplidar_cmd.h:88
#define RPLIDAR_CMD_SCAN
Definition: rplidar_cmd.h:43
u_result _waitScanData(rplidar_response_measurement_node_t *nodebuffer, size_t &count, _u32 timeout=DEFAULT_TIMEOUT)



Page generated by Doxygen 1.8.14 for MRPT 1.9.9 Git: 7d5e6d718 Fri Aug 24 01:51:28 2018 +0200 at lun nov 2 08:35:50 CET 2020