sl_lidar_driver.cpp
Go to the documentation of this file.
1 /*
2  * Slamtec LIDAR SDK
3  *
4  * Copyright (c) 2014 - 2020 Shanghai Slamtec Co., Ltd.
5  * http://www.slamtec.com
6  *
7  */
8  /*
9  * Redistribution and use in source and binary forms, with or without
10  * modification, are permitted provided that the following conditions are met:
11  *
12  * 1. Redistributions of source code must retain the above copyright notice,
13  * this list of conditions and the following disclaimer.
14  *
15  * 2. Redistributions in binary form must reproduce the above copyright notice,
16  * this list of conditions and the following disclaimer in the documentation
17  * and/or other materials provided with the distribution.
18  *
19  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
20  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO,
21  * THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
22  * PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
23  * CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL,
24  * EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO,
25  * PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS;
26  * OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY,
27  * WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR
28  * OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE,
29  * EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
30  *
31  */
32 
33 #include "sdkcommon.h"
34 #include "hal/abs_rxtx.h"
35 #include "hal/thread.h"
36 #include "hal/types.h"
37 #include "hal/assert.h"
38 #include "hal/locker.h"
39 #include "hal/socket.h"
40 #include "hal/event.h"
41 #include "sl_lidar_driver.h"
42 #include "sl_crc.h"
43 #include <algorithm>
44 
45 #ifdef _WIN32
46 #define NOMINMAX
47 #undef min
48 #undef max
49 #endif
50 
51 #if defined(__cplusplus) && __cplusplus >= 201103L
52 #ifndef _GXX_NULLPTR_T
53 #define _GXX_NULLPTR_T
54 typedef decltype(nullptr) nullptr_t;
55 #endif
56 #endif /* C++11. */
57 
58 namespace sl {
59  static void printDeprecationWarn(const char* fn, const char* replacement)
60  {
61  fprintf(stderr, "*WARN* YOU ARE USING DEPRECATED API: %s, PLEASE MOVE TO %s\n", fn, replacement);
62  }
63 
64  static void convert(const sl_lidar_response_measurement_node_t& from, sl_lidar_response_measurement_node_hq_t& to)
65  {
66  to.angle_z_q14 = (((from.angle_q6_checkbit) >> SL_LIDAR_RESP_MEASUREMENT_ANGLE_SHIFT) << 8) / 90; //transfer to q14 Z-angle
67  to.dist_mm_q2 = from.distance_q2;
68  to.flag = (from.sync_quality & SL_LIDAR_RESP_MEASUREMENT_SYNCBIT); // trasfer syncbit to HQ flag field
69  to.quality = (from.sync_quality >> SL_LIDAR_RESP_MEASUREMENT_QUALITY_SHIFT) << SL_LIDAR_RESP_MEASUREMENT_QUALITY_SHIFT; //remove the last two bits and then make quality from 0-63 to 0-255
70  }
71 
72  static void convert(const sl_lidar_response_measurement_node_hq_t& from, sl_lidar_response_measurement_node_t& to)
73  {
75  to.angle_q6_checkbit = 1 | (((from.angle_z_q14 * 90) >> 8) << SL_LIDAR_RESP_MEASUREMENT_ANGLE_SHIFT);
76  to.distance_q2 = from.dist_mm_q2 > sl_u16(-1) ? sl_u16(0) : sl_u16(from.dist_mm_q2);
77  }
78 
79  static sl_u32 _varbitscale_decode(sl_u32 scaled, sl_u32 & scaleLevel)
80  {
81  static const sl_u32 VBS_SCALED_BASE[] = {
86  0,
87  };
88 
89  static const sl_u32 VBS_SCALED_LVL[] = {
90  4,
91  3,
92  2,
93  1,
94  0,
95  };
96 
97  static const sl_u32 VBS_TARGET_BASE[] = {
102  0,
103  };
104 
105  for (size_t i = 0; i < _countof(VBS_SCALED_BASE); ++i) {
106  int remain = ((int)scaled - (int)VBS_SCALED_BASE[i]);
107  if (remain >= 0) {
108  scaleLevel = VBS_SCALED_LVL[i];
109  return VBS_TARGET_BASE[i] + (remain << scaleLevel);
110  }
111  }
112  return 0;
113  }
114 
115  static inline float getAngle(const sl_lidar_response_measurement_node_t& node)
116  {
117  return (node.angle_q6_checkbit >> SL_LIDAR_RESP_MEASUREMENT_ANGLE_SHIFT) / 64.f;
118  }
119 
120  static inline void setAngle(sl_lidar_response_measurement_node_t& node, float v)
121  {
122  sl_u16 checkbit = node.angle_q6_checkbit & SL_LIDAR_RESP_MEASUREMENT_CHECKBIT;
123  node.angle_q6_checkbit = (((sl_u16)(v * 64.0f)) << SL_LIDAR_RESP_MEASUREMENT_ANGLE_SHIFT) | checkbit;
124  }
125 
126  static inline float getAngle(const sl_lidar_response_measurement_node_hq_t& node)
127  {
128  return node.angle_z_q14 * 90.f / 16384.f;
129  }
130 
131  static inline void setAngle(sl_lidar_response_measurement_node_hq_t& node, float v)
132  {
133  node.angle_z_q14 = sl_u32(v * 16384.f / 90.f);
134  }
135 
136  static inline sl_u16 getDistanceQ2(const sl_lidar_response_measurement_node_t& node)
137  {
138  return node.distance_q2;
139  }
140 
141  static inline sl_u32 getDistanceQ2(const sl_lidar_response_measurement_node_hq_t& node)
142  {
143  return node.dist_mm_q2;
144  }
145 
146  template <class TNode>
147  static bool angleLessThan(const TNode& a, const TNode& b)
148  {
149  return getAngle(a) < getAngle(b);
150  }
151 
152  template < class TNode >
153  static sl_result ascendScanData_(TNode * nodebuffer, size_t count)
154  {
155  float inc_origin_angle = 360.f / count;
156  size_t i = 0;
157 
158  //Tune head
159  for (i = 0; i < count; i++) {
160  if (getDistanceQ2(nodebuffer[i]) == 0) {
161  continue;
162  }
163  else {
164  while (i != 0) {
165  i--;
166  float expect_angle = getAngle(nodebuffer[i + 1]) - inc_origin_angle;
167  if (expect_angle < 0.0f) expect_angle = 0.0f;
168  setAngle(nodebuffer[i], expect_angle);
169  }
170  break;
171  }
172  }
173 
174  // all the data is invalid
175  if (i == count) return SL_RESULT_OPERATION_FAIL;
176 
177  //Tune tail
178  for (i = count - 1; i >= 0; i--) {
179  if (getDistanceQ2(nodebuffer[i]) == 0) {
180  continue;
181  }
182  else {
183  while (i != (count - 1)) {
184  i++;
185  float expect_angle = getAngle(nodebuffer[i - 1]) + inc_origin_angle;
186  if (expect_angle > 360.0f) expect_angle -= 360.0f;
187  setAngle(nodebuffer[i], expect_angle);
188  }
189  break;
190  }
191  }
192 
193  //Fill invalid angle in the scan
194  float frontAngle = getAngle(nodebuffer[0]);
195  for (i = 1; i < count; i++) {
196  if (getDistanceQ2(nodebuffer[i]) == 0) {
197  float expect_angle = frontAngle + i * inc_origin_angle;
198  if (expect_angle > 360.0f) expect_angle -= 360.0f;
199  setAngle(nodebuffer[i], expect_angle);
200  }
201  }
202 
203  // Reorder the scan according to the angle value
204  std::sort(nodebuffer, nodebuffer + count, &angleLessThan<TNode>);
205 
206  return SL_RESULT_OK;
207  }
208 
210  {
211  public:
212  enum {
214  };
215 
216  enum {
219  };
220 
221  enum {
224  };
225 
226  public:
228  : _channel(NULL)
229  , _isConnected(false)
230  , _isScanning(false)
236  {}
237 
239  {
241 
242  if (!channel) return SL_RESULT_OPERATION_FAIL;
243  if (isConnected()) return SL_RESULT_ALREADY_DONE;
244  _channel = channel;
245 
246  {
248  ans = _channel->open();
249  if (!ans)
251 
252  _channel->flush();
253  }
254 
255  _isConnected = true;
256 
258  return SL_RESULT_OK;
259 
260  }
261 
262  void disconnect()
263  {
264  if (_isConnected)
265  _channel->close();
266  }
267 
268  bool isConnected()
269  {
270  return _isConnected;
271  }
272 
273  sl_result reset(sl_u32 timeoutInMs = DEFAULT_TIMEOUT)
274  {
276  {
279  if (!ans) {
280  return ans;
281  }
282  }
283  return SL_RESULT_OK;
284  }
285 
286  sl_result getAllSupportedScanModes(std::vector<LidarScanMode>& outModes, sl_u32 timeoutInMs = DEFAULT_TIMEOUT)
287  {
289  bool confProtocolSupported = false;
290  ans = checkSupportConfigCommands(confProtocolSupported);
291  if (!ans) return SL_RESULT_INVALID_DATA;
292 
293  if (confProtocolSupported) {
294  // 1. get scan mode count
295  sl_u16 modeCount;
296  ans = getScanModeCount(modeCount);
297  if (!ans) return ans;
298  // 2. for loop to get all fields of each scan mode
299  for (sl_u16 i = 0; i < modeCount; i++) {
300  LidarScanMode scanModeInfoTmp;
301  memset(&scanModeInfoTmp, 0, sizeof(scanModeInfoTmp));
302  scanModeInfoTmp.id = i;
303  ans = getLidarSampleDuration(scanModeInfoTmp.us_per_sample, i);
304  if (!ans) return ans;
305  ans = getMaxDistance(scanModeInfoTmp.max_distance, i);
306  if (!ans) return ans;
307  ans = getScanModeAnsType(scanModeInfoTmp.ans_type, i);
308  if (!ans) return ans;
309  ans = getScanModeName(scanModeInfoTmp.scan_mode, i);
310  if (!ans) return ans;
311  outModes.push_back(scanModeInfoTmp);
312 
313  }
314  return ans;
315  }
316 
317  return ans;
318  }
319 
320  sl_result getTypicalScanMode(sl_u16& outMode, sl_u32 timeoutInMs = DEFAULT_TIMEOUT)
321  {
323  std::vector<sl_u8> answer;
324  bool lidarSupportConfigCmds = false;
325  ans = checkSupportConfigCommands(lidarSupportConfigCmds);
326  if (!ans) return ans;
327 
328  if (lidarSupportConfigCmds) {
329  ans = getLidarConf(SL_LIDAR_CONF_SCAN_MODE_TYPICAL, answer, std::vector<sl_u8>(), timeoutInMs);
330  if (!ans) return ans;
331  if (answer.size() < sizeof(sl_u16)) {
332  return SL_RESULT_INVALID_DATA;
333  }
334  const sl_u16 *p_answer = reinterpret_cast<const sl_u16*>(&answer[0]);
335  outMode = *p_answer;
336  return ans;
337  }
338  //old version of triangle lidar
339  else {
341  return ans;
342  }
343  return ans;
344 
345  }
346 
347  sl_result startScan(bool force, bool useTypicalScan, sl_u32 options = 0, LidarScanMode* outUsedScanMode = nullptr)
348  {
350  bool ifSupportLidarConf = false;
351  startMotor();
352  ans = checkSupportConfigCommands(ifSupportLidarConf);
353  if (!ans) return ans;
354  if (useTypicalScan){
355  sl_u16 typicalMode;
356  ans = getTypicalScanMode(typicalMode);
357  if (!ans) return ans;
358 
359  //call startScanExpress to do the job
360  return startScanExpress(false, typicalMode, 0, outUsedScanMode);
361  }
362 
363  // 'useTypicalScan' is false, just use normal scan mode
364  if (ifSupportLidarConf) {
365  if (outUsedScanMode) {
366  outUsedScanMode->id = SL_LIDAR_CONF_SCAN_COMMAND_STD;
367  ans = getLidarSampleDuration(outUsedScanMode->us_per_sample, outUsedScanMode->id);
368  if (!ans) return ans;
369  ans = getMaxDistance(outUsedScanMode->max_distance, outUsedScanMode->id);
370  if (!ans) return ans;
371  ans = getScanModeAnsType(outUsedScanMode->ans_type, outUsedScanMode->id);
372  if (!ans) return ans;
373  ans = getScanModeName(outUsedScanMode->scan_mode, outUsedScanMode->id);
374  if (!ans) return ans;
375  }
376  }
377 
378  return startScanNormal(force);
379  }
380 
381  sl_result startScanNormal(bool force, sl_u32 timeout = DEFAULT_TIMEOUT)
382  {
384  if (!isConnected()) return SL_RESULT_OPERATION_FAIL;
386 
387  stop(); //force the previous operation to stop
388  setMotorSpeed();
389  {
392  if (!ans) return ans;
393  // waiting for confirmation
394  sl_lidar_ans_header_t response_header;
395  ans = _waitResponseHeader(&response_header, timeout);
396  if (!ans) return ans;
397 
398  // verify whether we got a correct header
399  if (response_header.type != SL_LIDAR_ANS_TYPE_MEASUREMENT) {
400  return SL_RESULT_INVALID_DATA;
401  }
402 
403  sl_u32 header_size = (response_header.size_q30_subtype & SL_LIDAR_ANS_HEADER_SIZE_MASK);
404  if (header_size < sizeof(sl_lidar_response_measurement_node_t)) {
405  return SL_RESULT_INVALID_DATA;
406  }
407  _isScanning = true;
409  if (_cachethread.getHandle() == 0) {
411  }
412  }
413  return SL_RESULT_OK;
414  }
415 
416  sl_result startScanExpress(bool force, sl_u16 scanMode, sl_u32 options = 0, LidarScanMode* outUsedScanMode = nullptr, sl_u32 timeout = DEFAULT_TIMEOUT)
417  {
419  if (!isConnected()) return SL_RESULT_OPERATION_FAIL;
421  stop(); //force the previous operation to stop
422 
423  bool ifSupportLidarConf = false;
424  ans = checkSupportConfigCommands(ifSupportLidarConf);
425  if (!ans) return SL_RESULT_INVALID_DATA;
426 
427 
428  if (outUsedScanMode) {
429  outUsedScanMode->id = scanMode;
430  if (ifSupportLidarConf) {
431  ans = getLidarSampleDuration(outUsedScanMode->us_per_sample, outUsedScanMode->id);
432  if (!ans) return SL_RESULT_INVALID_DATA;
433 
434  ans = getMaxDistance(outUsedScanMode->max_distance, outUsedScanMode->id);
435  if (!ans) return SL_RESULT_INVALID_DATA;
436 
437  ans = getScanModeAnsType(outUsedScanMode->ans_type, outUsedScanMode->id);
438  if (!ans) return SL_RESULT_INVALID_DATA;
439 
440  ans = getScanModeName(outUsedScanMode->scan_mode, outUsedScanMode->id);
441  if (!ans) return SL_RESULT_INVALID_DATA;
442 
443 
444  }
445 
446  }
447 
448  //get scan answer type to specify how to wait data
449  sl_u8 scanAnsType;
450  if (ifSupportLidarConf) {
451  getScanModeAnsType(scanAnsType, scanMode);
452  }
453  else {
455  }
456  if (!ifSupportLidarConf || scanAnsType == SL_LIDAR_ANS_TYPE_MEASUREMENT) {
457  if (scanMode == SL_LIDAR_CONF_SCAN_COMMAND_STD) {
458  return startScan(force, false, 0, outUsedScanMode);
459  }
460  }
461  {
463 
464  startMotor();
465  sl_lidar_payload_express_scan_t scanReq;
466  memset(&scanReq, 0, sizeof(scanReq));
467  if (!ifSupportLidarConf){
469  scanReq.working_mode = sl_u8(scanMode);
470  }else
471  scanReq.working_mode = sl_u8(scanMode);
472 
473  scanReq.working_flags = options;
474  delay(5);
475  ans = _sendCommand(SL_LIDAR_CMD_EXPRESS_SCAN, &scanReq, sizeof(scanReq));
476  if (!ans) {
477  ans = _sendCommand(SL_LIDAR_CMD_EXPRESS_SCAN, &scanReq, sizeof(scanReq));
478  if (!ans)
479  return SL_RESULT_INVALID_DATA;
480  }
481 
482 
483  // waiting for confirmation
484  sl_lidar_ans_header_t response_header;
485  ans = _waitResponseHeader(&response_header, timeout);
486  if (!ans) return ans;
487 
488  // verify whether we got a correct header
489  if (response_header.type != scanAnsType) {
490  return SL_RESULT_INVALID_DATA;
491  }
492 
493  sl_u32 header_size = (response_header.size_q30_subtype & SL_LIDAR_ANS_HEADER_SIZE_MASK);
494 
495  if (scanAnsType == SL_LIDAR_ANS_TYPE_MEASUREMENT_CAPSULED) {
496  if (header_size < sizeof(sl_lidar_response_capsule_measurement_nodes_t)) {
497  return SL_RESULT_INVALID_DATA;
498  }
500  _isScanning = true;
502  }
503  else if (scanAnsType == SL_LIDAR_ANS_TYPE_MEASUREMENT_DENSE_CAPSULED) {
504  if (header_size < sizeof(sl_lidar_response_capsule_measurement_nodes_t)) {
505  return SL_RESULT_INVALID_DATA;
506  }
508  _isScanning = true;
510  }
511  else if (scanAnsType == SL_LIDAR_ANS_TYPE_MEASUREMENT_HQ) {
512  if (header_size < sizeof(sl_lidar_response_hq_capsule_measurement_nodes_t)) {
513  return SL_RESULT_INVALID_DATA;
514  }
515  _isScanning = true;
517  }
518  else {
519  if (header_size < sizeof(sl_lidar_response_ultra_capsule_measurement_nodes_t)) {
520  return SL_RESULT_INVALID_DATA;
521  }
522  _isScanning = true;
524  }
525 
526  if (_cachethread.getHandle() == 0) {
528  }
529  }
530  return SL_RESULT_OK;
531 
532  }
533 
534  sl_result stop(sl_u32 timeout = DEFAULT_TIMEOUT)
535  {
538 
539  {
542  if (!ans) return ans;
543  }
544  delay(100);
545 
547  setMotorSpeed(0);
548 
549  return SL_RESULT_OK;
550  }
551 
553  {
554  switch (_dataEvt.wait(timeout))
555  {
557  count = 0;
560  {
561  if (_cached_scan_node_hq_count == 0) return SL_RESULT_OPERATION_TIMEOUT; //consider as timeout
562 
564 
565  size_t size_to_copy = std::min(count, _cached_scan_node_hq_count);
566  memcpy(nodebuffer, _cached_scan_node_hq_buf, size_to_copy * sizeof(sl_lidar_response_measurement_node_hq_t));
567 
568  count = size_to_copy;
570  }
571  return SL_RESULT_OK;
572 
573  default:
574  count = 0;
576  }
577  }
578 
579  sl_result getDeviceInfo(sl_lidar_response_device_info_t& info, sl_u32 timeout = DEFAULT_TIMEOUT)
580  {
583  delay(20);
584  {
587  if (!ans) return ans;
589  }
590  }
591 
593  {
595  support = MotorCtrlSupportNone;
597  {
598  sl_lidar_response_device_info_t devInfo;
599  ans = getDeviceInfo(devInfo, 500);
600  if (!ans) return ans;
601  sl_u8 majorId = devInfo.model >> 4;
602  if (majorId >= TOF_LIDAR_MINUM_MAJOR_ID) {
603  support = MotorCtrlSupportRpm;
604  return ans;
605  }
606  else if(majorId >= A2A3_LIDAR_MINUM_MAJOR_ID){
607 
609  sl_lidar_payload_acc_board_flag_t flag;
610  flag.reserved = 0;
611  ans = _sendCommand(SL_LIDAR_CMD_GET_ACC_BOARD_FLAG, &flag, sizeof(flag));
612  if (!ans) return ans;
613 
614  sl_lidar_response_acc_board_flag_t acc_board_flag;
615  ans = _waitResponse(acc_board_flag, SL_LIDAR_ANS_TYPE_ACC_BOARD_FLAG);
616  if (acc_board_flag.support_flag & SL_LIDAR_RESP_ACC_BOARD_FLAG_MOTOR_CTRL_SUPPORT_MASK) {
617  support = MotorCtrlSupportPwm;
618  }
619  return ans;
620  }
621 
622  }
623  return SL_RESULT_OK;
624 
625  }
626 
627  sl_result getFrequency(const LidarScanMode& scanMode, const sl_lidar_response_measurement_node_hq_t* nodes, size_t count, float& frequency)
628  {
629  float sample_duration = scanMode.us_per_sample;
630  frequency = 1000000.0f / (count * sample_duration);
631  return SL_RESULT_OK;
632  }
633 
634  sl_result setLidarIpConf(const sl_lidar_ip_conf_t& conf, sl_u32 timeout)
635  {
636  sl_result ans = setLidarConf(SL_LIDAR_CONF_LIDAR_STATIC_IP_ADDR, &conf, sizeof(sl_lidar_ip_conf_t), timeout);
637  return ans;
638  }
639 
640  sl_result getHealth(sl_lidar_response_device_health_t& health, sl_u32 timeout = DEFAULT_TIMEOUT)
641  {
643 
644  if (!isConnected())
646 
648 
649  {
652  if (!ans) return ans;
653  delay(50);
655 
656  }
657  return ans;
658 
659  }
660 
661  sl_result getDeviceMacAddr(sl_u8* macAddrArray, sl_u32 timeoutInMs)
662  {
664 
665  std::vector<sl_u8> answer;
666  ans = getLidarConf(SL_LIDAR_CONF_LIDAR_MAC_ADDR, answer, std::vector<sl_u8>(), timeoutInMs);
667  if (!ans) return ans;
668 
669  int len = answer.size();
670  if (0 == len) return SL_RESULT_INVALID_DATA;
671  memcpy(macAddrArray, &answer[0], len);
672  return ans;
673  }
674 
676  {
677  return ascendScanData_<sl_lidar_response_measurement_node_hq_t>(nodebuffer, count);
678  }
679 
681  {
682  size_t size_to_copy = 0;
683  {
687  }
688  //copy all the nodes(_cached_scan_node_count_for_interval_retrieve nodes) in _cached_scan_node_buf_for_interval_retrieve
692  }
693  count = size_to_copy;
694 
695  return SL_RESULT_OK;
696  }
698  {
700 
701  if(speed == DEFAULT_MOTOR_SPEED){
702  sl_lidar_response_desired_rot_speed_t desired_speed;
703  ans = getDesiredSpeed(desired_speed);
704  if (!ans) return ans;
706  speed = desired_speed.pwm_ref;
707  else
708  speed = desired_speed.rpm;
709  }
710  switch (_isSupportingMotorCtrl)
711  {
713  break;
714  case MotorCtrlSupportPwm:
715  sl_lidar_payload_motor_pwm_t motor_pwm;
716  motor_pwm.pwm_value = speed;
717  ans = _sendCommand(SL_LIDAR_CMD_SET_MOTOR_PWM, (const sl_u8 *)&motor_pwm, sizeof(motor_pwm));
718  if (!ans) return ans;
719  break;
720  case MotorCtrlSupportRpm:
721  sl_lidar_payload_motor_pwm_t motor_rpm;
722  motor_rpm.pwm_value = speed;
723  ans = _sendCommand(SL_LIDAR_CMD_HQ_MOTOR_SPEED_CTRL, (const sl_u8 *)&motor_rpm, sizeof(motor_rpm));
724  if (!ans) return ans;
725  break;
726  }
727  return SL_RESULT_OK;
728  }
729 
730  sl_result getMotorInfo(LidarMotorInfo &motorInfo, sl_u32 timeoutInMs)
731  {
734  {
735  std::vector<sl_u8> answer;
736 
737  ans = getLidarConf(RPLIDAR_CONF_MIN_ROT_FREQ, answer, std::vector<sl_u8>());
738  if (!ans) return ans;
739 
740  const sl_u16 *min_answer = reinterpret_cast<const sl_u16*>(&answer[0]);
741  motorInfo.min_speed = *min_answer;
742 
743 
744  ans = getLidarConf(RPLIDAR_CONF_MAX_ROT_FREQ, answer, std::vector<sl_u8>());
745  if (!ans) return ans;
746 
747  const sl_u16 *max_answer = reinterpret_cast<const sl_u16*>(&answer[0]);
748  motorInfo.max_speed = *max_answer;
749 
750  sl_lidar_response_desired_rot_speed_t desired_speed;
751  ans = getDesiredSpeed(desired_speed);
752  if (!ans) return ans;
753  if(motorInfo.motorCtrlSupport == MotorCtrlSupportPwm)
754  motorInfo.desired_speed = desired_speed.pwm_ref;
755  else
756  motorInfo.desired_speed = desired_speed.rpm;
757 
758  }
759  return SL_RESULT_OK;
760  }
761 
762  protected:
764  {
765  return setMotorSpeed(600);
766  }
767 
768  sl_result getDesiredSpeed(sl_lidar_response_desired_rot_speed_t & motorSpeed, sl_u32 timeoutInMs = DEFAULT_TIMEOUT)
769  {
771  std::vector<sl_u8> answer;
772  ans = getLidarConf(SL_LIDAR_CONF_DESIRED_ROT_FREQ, answer, std::vector<sl_u8>(), timeoutInMs);
773 
774  if (!ans) return ans;
775 
776  const sl_lidar_response_desired_rot_speed_t *p_answer = reinterpret_cast<const sl_lidar_response_desired_rot_speed_t*>(&answer[0]);
777  motorSpeed = *p_answer;
778  return SL_RESULT_OK;
779  }
780 
781  sl_result checkSupportConfigCommands(bool& outSupport, sl_u32 timeoutInMs = DEFAULT_TIMEOUT)
782  {
784  sl_lidar_response_device_info_t devinfo;
785  ans = getDeviceInfo(devinfo, timeoutInMs);
786  if (!ans) return ans;
787 
788  sl_u16 modecount;
789  ans = getScanModeCount(modecount, 250);
790  if ((sl_result)ans == SL_RESULT_OK)
791  outSupport = true;
792 
793  return SL_RESULT_OK;
794  }
795 
796  sl_result getScanModeCount(sl_u16& modeCount, sl_u32 timeoutInMs = DEFAULT_TIMEOUT)
797  {
799  std::vector<sl_u8> answer;
800  ans = getLidarConf(SL_LIDAR_CONF_SCAN_MODE_COUNT, answer, std::vector<sl_u8>(), timeoutInMs);
801 
802  if (!ans) return ans;
803 
804  const sl_u16 *p_answer = reinterpret_cast<const sl_u16*>(&answer[0]);
805  modeCount = *p_answer;
806  return SL_RESULT_OK;
807  }
808 
809  sl_result setLidarConf(sl_u32 type, const void* payload, size_t payloadSize, sl_u32 timeout)
810  {
811  if (type < 0x00010000 || type >0x0001FFFF)
812  return SL_RESULT_INVALID_DATA;
813  std::vector<sl_u8> requestPkt;
814  requestPkt.resize(sizeof(sl_lidar_payload_set_scan_conf_t) + payloadSize);
815  if (!payload) payloadSize = 0;
816  sl_lidar_payload_set_scan_conf_t* query = reinterpret_cast<sl_lidar_payload_set_scan_conf_t*>(&requestPkt[0]);
817 
818  query->type = type;
819 
820  if (payloadSize)
821  memcpy(&query[1], payload, payloadSize);
822 
823  sl_result ans;
824  {
826  if (IS_FAIL(ans = _sendCommand(SL_LIDAR_CMD_SET_LIDAR_CONF, &requestPkt[0], requestPkt.size()))) {//
827  return ans;
828  }
829  delay(20);
830  // waiting for confirmation
831  sl_lidar_ans_header_t response_header;
832  if (IS_FAIL(ans = _waitResponseHeader(&response_header, timeout))) {
833  return ans;
834  }
835  // verify whether we got a correct header
836  if (response_header.type != SL_LIDAR_ANS_TYPE_SET_LIDAR_CONF) {
837  return SL_RESULT_INVALID_DATA;
838  }
839  sl_u32 header_size = (response_header.size_q30_subtype & SL_LIDAR_ANS_HEADER_SIZE_MASK);
840  if (header_size < sizeof(type)) {
841  return SL_RESULT_INVALID_DATA;
842  }
843  if (!_channel->waitForData(header_size, timeout)) {
845  }
846  delay(100);
848  sl_u32 type;
849  sl_u32 result;
850  } answer;
851 
852  _channel->read(reinterpret_cast<sl_u8*>(&answer), header_size);
853  return answer.result;
854 
855  }
856 
857  }
858 
859  sl_result getLidarConf(sl_u32 type, std::vector<sl_u8> &outputBuf, const std::vector<sl_u8> &reserve = std::vector<sl_u8>(), sl_u32 timeout = DEFAULT_TIMEOUT)
860  {
861  sl_lidar_payload_get_scan_conf_t query;
862  query.type = type;
863  int sizeVec = reserve.size();
864 
865  int maxLen = sizeof(query.reserved) / sizeof(query.reserved[0]);
866  if (sizeVec > maxLen) sizeVec = maxLen;
867 
868  if (sizeVec > 0)
869  memcpy(query.reserved, &reserve[0], reserve.size());
870 
872  {
874  ans = _sendCommand(SL_LIDAR_CMD_GET_LIDAR_CONF, &query, sizeof(query));
875  if (!ans) return ans;
876  //delay(50);
877  // waiting for confirmation
878  sl_lidar_ans_header_t response_header;
879  ans = _waitResponseHeader(&response_header, timeout);
880  if (!ans)return ans;
881 
882  // verify whether we got a correct header
883  if (response_header.type != SL_LIDAR_ANS_TYPE_GET_LIDAR_CONF) {
884  return SL_RESULT_INVALID_DATA;
885  }
886 
887  sl_u32 header_size = (response_header.size_q30_subtype & SL_LIDAR_ANS_HEADER_SIZE_MASK);
888  if (header_size < sizeof(type)) {
889  return SL_RESULT_INVALID_DATA;
890  }
891  //delay(100);
892  if (!_channel->waitForData(header_size, timeout)) {
894  }
895 
896  std::vector<sl_u8> dataBuf;
897  dataBuf.resize(header_size);
898  _channel->read(reinterpret_cast<sl_u8 *>(&dataBuf[0]), header_size);
899 
900  //check if returned type is same as asked type
901  sl_u32 replyType = -1;
902  memcpy(&replyType, &dataBuf[0], sizeof(type));
903  if (replyType != type) {
904  return SL_RESULT_INVALID_DATA;
905  }
906 
907  //copy all the payload into &outputBuf
908  int payLoadLen = header_size - sizeof(type);
909 
910  //do consistency check
911  if (payLoadLen <= 0) {
912  return SL_RESULT_INVALID_DATA;
913  }
914  //copy all payLoadLen bytes to outputBuf
915  outputBuf.resize(payLoadLen);
916  memcpy(&outputBuf[0], &dataBuf[0] + sizeof(type), payLoadLen);
917 
918  }
919 
920  return SL_RESULT_OK;
921  }
922 
923  sl_result getLidarSampleDuration(float& sampleDurationRes, sl_u16 scanModeID, sl_u32 timeoutInMs = DEFAULT_TIMEOUT)
924  {
926  std::vector<sl_u8> reserve(2);
927  memcpy(&reserve[0], &scanModeID, sizeof(scanModeID));
928 
929  std::vector<sl_u8> answer;
930  ans = getLidarConf(SL_LIDAR_CONF_SCAN_MODE_US_PER_SAMPLE, answer, reserve, timeoutInMs);
931 
932  if (!ans) return ans;
933 
934  if (answer.size() < sizeof(sl_u32)){
935  return SL_RESULT_INVALID_DATA;
936  }
937  const sl_u32 *result = reinterpret_cast<const sl_u32*>(&answer[0]);
938  sampleDurationRes = (float)(*result >> 8);
939  return ans;
940  }
941 
942  sl_result getMaxDistance(float &maxDistance, sl_u16 scanModeID, sl_u32 timeoutInMs = DEFAULT_TIMEOUT)
943  {
945  std::vector<sl_u8> reserve(2);
946  memcpy(&reserve[0], &scanModeID, sizeof(scanModeID));
947 
948  std::vector<sl_u8> answer;
949  ans = getLidarConf(SL_LIDAR_CONF_SCAN_MODE_MAX_DISTANCE, answer, reserve, timeoutInMs);
950  if (!ans) return ans;
951 
952  if (answer.size() < sizeof(sl_u32)){
953  return SL_RESULT_INVALID_DATA;
954  }
955  const sl_u32 *result = reinterpret_cast<const sl_u32*>(&answer[0]);
956  maxDistance = (float)(*result >> 8);
957  return ans;
958  }
959 
960  sl_result getScanModeAnsType(sl_u8 &ansType, sl_u16 scanModeID, sl_u32 timeoutInMs = DEFAULT_TIMEOUT)
961  {
963  std::vector<sl_u8> reserve(2);
964  memcpy(&reserve[0], &scanModeID, sizeof(scanModeID));
965 
966  std::vector<sl_u8> answer;
967  ans = getLidarConf(SL_LIDAR_CONF_SCAN_MODE_ANS_TYPE, answer, reserve, timeoutInMs);
968  if (!ans) return ans;
969 
970  if (answer.size() < sizeof(sl_u8)){
971  return SL_RESULT_INVALID_DATA;
972  }
973  const sl_u8 *result = reinterpret_cast<const _u8*>(&answer[0]);
974  ansType = *result;
975  return ans;
976 
977  }
978 
979  sl_result getScanModeName(char* modeName, sl_u16 scanModeID, sl_u32 timeoutInMs = DEFAULT_TIMEOUT)
980  {
982  std::vector<sl_u8> reserve(2);
983  memcpy(&reserve[0], &scanModeID, sizeof(scanModeID));
984 
985  std::vector<sl_u8> answer;
986  ans = getLidarConf(SL_LIDAR_CONF_SCAN_MODE_NAME, answer, reserve, timeoutInMs);
987  if (!ans) return ans;
988  int len = answer.size();
989  if (0 == len) return SL_RESULT_INVALID_DATA;
990  memcpy(modeName, &answer[0], len);
991  return ans;
992  }
993 
994  sl_result negotiateSerialBaudRate(sl_u32 requiredBaudRate, sl_u32 * baudRateDetected)
995  {
996  // ask the LIDAR to stop working first...
997  stop();
998  _channel->flush();
999 
1000  // wait for a while
1001  delay(10);
1003 
1004  // sending magic byte to let the target LIDAR start baudrate measurement
1005  // More than 100 bytes per second datarate is required to trigger the measurements
1006  {
1007 
1008 
1009  sl_u8 magicByteSeq[16];
1010 
1011  memset(magicByteSeq, SL_LIDAR_AUTOBAUD_MAGICBYTE, sizeof(magicByteSeq));
1012 
1013  sl_u64 startTS = getms();
1014 
1015  while (getms() - startTS < 1500 ) //lasting for 1.5sec
1016  {
1017  if (_channel->write(magicByteSeq, sizeof(magicByteSeq)) < 0)
1018  {
1019  return SL_RESULT_OPERATION_FAIL;
1020  }
1021 
1022  size_t dataCountGot;
1023  if (_channel->waitForData(1, 1, &dataCountGot)) {
1024  //got reply, stop
1025  break;
1026  }
1027  }
1028  }
1029 
1030  // getback the bps measured
1031  _u32 bpsDetected = 0;
1032  size_t dataCountGot;
1033  if (_channel->waitForData(4, 500, &dataCountGot)) {
1034  //got reply, stop
1035  _channel->read(&bpsDetected, 4);
1036  if (baudRateDetected) *baudRateDetected = bpsDetected;
1037 
1038 
1039  // send a confirmation to the LIDAR, otherwise, the previous baudrate will be reverted back
1040  sl_lidar_payload_new_bps_confirmation_t confirmation;
1041  confirmation.flag = 0x5F5F;
1042  confirmation.required_bps = requiredBaudRate;
1043  confirmation.param = 0;
1044  if (SL_IS_FAIL(_sendCommand(RPLIDAR_CMD_NEW_BAUDRATE_CONFIRM, &confirmation, sizeof(confirmation))))
1045  return RESULT_OPERATION_FAIL;
1046 
1047 
1048  return RESULT_OK;
1049  }
1050 
1051  return RESULT_OPERATION_TIMEOUT;
1052  }
1053 
1054  private:
1055 
1056  sl_result _sendCommand(sl_u16 cmd, const void * payload = NULL, size_t payloadsize = 0 )
1057  {
1058  sl_u8 pkt_header[10];
1059  sl_u8 checksum = 0;
1060 
1061  std::vector<sl_u8> cmd_packet;
1062  cmd_packet.clear();
1063 
1064  if (payloadsize && payload) {
1066  }
1067  _channel->flush();
1068  cmd_packet.push_back(SL_LIDAR_CMD_SYNC_BYTE);
1069  cmd_packet.push_back(cmd);
1070 
1071  if (cmd & SL_LIDAR_CMDFLAG_HAS_PAYLOAD) {
1072  std::vector<sl_u8> payloadMsg;
1073  checksum ^= SL_LIDAR_CMD_SYNC_BYTE;
1074  checksum ^= cmd;
1075  checksum ^= (payloadsize & 0xFF);
1076 
1077  // send size
1078  sl_u8 sizebyte = payloadsize;
1079  cmd_packet.push_back(sizebyte);
1080  // calc checksum
1081  for (size_t pos = 0; pos < payloadsize; ++pos) {
1082  checksum ^= ((sl_u8 *)payload)[pos];
1083  cmd_packet.push_back(((sl_u8 *)payload)[pos]);
1084  }
1085  cmd_packet.push_back(checksum);
1086 
1087  }
1088  sl_u8 packet[1024];
1089  for (int pos = 0; pos < cmd_packet.size(); pos++) {
1090  packet[pos] = cmd_packet[pos];
1091  }
1092  _channel->write(packet, cmd_packet.size());
1093  delay(1);
1094  return SL_RESULT_OK;
1095  }
1096 
1098  {
1099  int recvPos = 0;
1100  sl_u32 startTs = getms();
1101  sl_u8 recvBuffer[sizeof(sl_lidar_ans_header_t)];
1102  sl_u8 *headerBuffer = reinterpret_cast<sl_u8 *>(header);
1103  sl_u32 waitTime;
1104 
1105  while ((waitTime = getms() - startTs) <= timeout) {
1106  size_t remainSize = sizeof(sl_lidar_ans_header_t) - recvPos;
1107  size_t recvSize;
1108 
1109  bool ans = _channel->waitForData(remainSize, timeout - waitTime, &recvSize);
1110  if (!ans) return SL_RESULT_OPERATION_TIMEOUT;
1111 
1112  if (recvSize > remainSize) recvSize = remainSize;
1113 
1114  recvSize = _channel->read(recvBuffer, recvSize);
1115 
1116  for (size_t pos = 0; pos < recvSize; ++pos) {
1117  sl_u8 currentByte = recvBuffer[pos];
1118  switch (recvPos) {
1119  case 0:
1120  if (currentByte != SL_LIDAR_ANS_SYNC_BYTE1) {
1121  continue;
1122  }
1123 
1124  break;
1125  case 1:
1126  if (currentByte != SL_LIDAR_ANS_SYNC_BYTE2) {
1127  recvPos = 0;
1128  continue;
1129  }
1130  break;
1131  }
1132  headerBuffer[recvPos++] = currentByte;
1133 
1134  if (recvPos == sizeof(sl_lidar_ans_header_t)) {
1135  return SL_RESULT_OK;
1136  }
1137  }
1138  }
1139 
1141  }
1142 
1143  template <typename T>
1144  sl_result _waitResponse(T &payload ,sl_u8 ansType, sl_u32 timeout = DEFAULT_TIMEOUT)
1145  {
1146  sl_lidar_ans_header_t response_header;
1148  //delay(100);
1149  ans = _waitResponseHeader(&response_header, timeout);
1150  if (!ans)
1151  return ans;
1152  // verify whether we got a correct header
1153  if (response_header.type != ansType) {
1154  return SL_RESULT_INVALID_DATA;
1155  }
1156  // delay(50);
1157  sl_u32 header_size = (response_header.size_q30_subtype & SL_LIDAR_ANS_HEADER_SIZE_MASK);
1158  if (header_size < sizeof(T)) {
1159  return SL_RESULT_INVALID_DATA;
1160  }
1161  if (!_channel->waitForData(header_size, timeout)) {
1163  }
1164  _channel->read(reinterpret_cast<sl_u8 *>(&payload), sizeof(T));
1165  return SL_RESULT_OK;
1166  }
1167 
1169  {
1170  //_clearRxDataCache();
1171  _isScanning = false;
1172  _cachethread.join();
1173  }
1174 
1175 #define MAX_SCAN_NODES (8192)
1176  sl_result _waitNode(sl_lidar_response_measurement_node_t * node, sl_u32 timeout = DEFAULT_TIMEOUT)
1177  {
1178  int recvPos = 0;
1179  sl_u32 startTs = getms();
1180  sl_u8 recvBuffer[sizeof(sl_lidar_response_measurement_node_t)];
1181  sl_u8 *nodeBuffer = (sl_u8*)node;
1182  sl_u32 waitTime;
1183 
1184  while ((waitTime = getms() - startTs) <= timeout) {
1185  size_t remainSize = sizeof(sl_lidar_response_measurement_node_t) - recvPos;
1186  size_t recvSize;
1187 
1188  bool ans = _channel->waitForData(remainSize, timeout - waitTime, &recvSize);
1189  if (!ans) return SL_RESULT_OPERATION_FAIL;
1190 
1191  if (recvSize > remainSize) recvSize = remainSize;
1192 
1193  recvSize = _channel->read(recvBuffer, recvSize);
1194 
1195  for (size_t pos = 0; pos < recvSize; ++pos) {
1196  sl_u8 currentByte = recvBuffer[pos];
1197  switch (recvPos) {
1198  case 0: // expect the sync bit and its reverse in this byte
1199  {
1200  sl_u8 tmp = (currentByte >> 1);
1201  if ((tmp ^ currentByte) & 0x1) {
1202  // pass
1203  }
1204  else {
1205  continue;
1206  }
1207 
1208  }
1209  break;
1210  case 1: // expect the highest bit to be 1
1211  {
1212  if (currentByte & SL_LIDAR_RESP_MEASUREMENT_CHECKBIT) {
1213  // pass
1214  }
1215  else {
1216  recvPos = 0;
1217  continue;
1218  }
1219  }
1220  break;
1221  }
1222  nodeBuffer[recvPos++] = currentByte;
1223 
1224  if (recvPos == sizeof(sl_lidar_response_measurement_node_t)) {
1225  return SL_RESULT_OK;
1226  }
1227  }
1228  }
1229 
1231  }
1232 
1233  sl_result _waitScanData(sl_lidar_response_measurement_node_t * nodebuffer, size_t & count, sl_u32 timeout = DEFAULT_TIMEOUT)
1234  {
1235  if (!_isConnected) {
1236  count = 0;
1237  return SL_RESULT_OPERATION_FAIL;
1238  }
1239 
1240  size_t recvNodeCount = 0;
1241  sl_u32 startTs = getms();
1242  sl_u32 waitTime;
1244 
1245  while ((waitTime = getms() - startTs) <= timeout && recvNodeCount < count) {
1246  sl_lidar_response_measurement_node_t node;
1247  ans = _waitNode(&node, timeout - waitTime);
1248  if (!ans) return ans;
1249 
1250  nodebuffer[recvNodeCount++] = node;
1251 
1252  if (recvNodeCount == count) return SL_RESULT_OK;
1253  }
1254  count = recvNodeCount;
1256  }
1257 
1259  {
1260 
1261  sl_lidar_response_measurement_node_t local_buf[256];
1262  size_t count = 256;
1264  size_t scan_count = 0;
1266  memset(local_scan, 0, sizeof(local_scan));
1267 
1268  _waitScanData(local_buf, count); // // always discard the first data since it may be incomplete
1269 
1270  while (_isScanning) {
1271  ans = _waitScanData(local_buf, count);
1272 
1273  if (!ans) {
1274  if ((sl_result)ans != SL_RESULT_OPERATION_TIMEOUT) {
1275  _isScanning = false;
1276  return SL_RESULT_OPERATION_FAIL;
1277  }
1278  }
1279 
1280  for (size_t pos = 0; pos < count; ++pos) {
1281  if (local_buf[pos].sync_quality & SL_LIDAR_RESP_MEASUREMENT_SYNCBIT) {
1282  // only publish the data when it contains a full 360 degree scan
1283 
1284  if ((local_scan[0].flag & SL_LIDAR_RESP_MEASUREMENT_SYNCBIT)) {
1285  _lock.lock();
1286  memcpy(_cached_scan_node_hq_buf, local_scan, scan_count * sizeof(sl_lidar_response_measurement_node_hq_t));
1287  _cached_scan_node_hq_count = scan_count;
1288  _dataEvt.set();
1289  _lock.unlock();
1290  }
1291  scan_count = 0;
1292  }
1293 
1295  convert(local_buf[pos], nodeHq);
1296  local_scan[scan_count++] = nodeHq;
1297  if (scan_count == _countof(local_scan)) scan_count -= 1; // prevent overflow
1298 
1299  //for interval retrieve
1300  {
1304  }
1305  }
1306  }
1307  _isScanning = false;
1308  return SL_RESULT_OK;
1309  }
1310 
1311  void _ultraCapsuleToNormal(const sl_lidar_response_ultra_capsule_measurement_nodes_t & capsule, sl_lidar_response_measurement_node_hq_t *nodebuffer, size_t &nodeCount)
1312  {
1313  nodeCount = 0;
1315  int diffAngle_q8;
1316  int currentStartAngle_q8 = ((capsule.start_angle_sync_q6 & 0x7FFF) << 2);
1317  int prevStartAngle_q8 = ((_cached_previous_ultracapsuledata.start_angle_sync_q6 & 0x7FFF) << 2);
1318 
1319  diffAngle_q8 = (currentStartAngle_q8)-(prevStartAngle_q8);
1320  if (prevStartAngle_q8 > currentStartAngle_q8) {
1321  diffAngle_q8 += (360 << 8);
1322  }
1323 
1324  int angleInc_q16 = (diffAngle_q8 << 3) / 3;
1325  int currentAngle_raw_q16 = (prevStartAngle_q8 << 8);
1326  for (size_t pos = 0; pos < _countof(_cached_previous_ultracapsuledata.ultra_cabins); ++pos) {
1327  int dist_q2[3];
1328  int angle_q6[3];
1329  int syncBit[3];
1330 
1331 
1332  sl_u32 combined_x3 = _cached_previous_ultracapsuledata.ultra_cabins[pos].combined_x3;
1333 
1334  // unpack ...
1335  int dist_major = (combined_x3 & 0xFFF);
1336 
1337  // signed partical integer, using the magic shift here
1338  // DO NOT TOUCH
1339 
1340  int dist_predict1 = (((int)(combined_x3 << 10)) >> 22);
1341  int dist_predict2 = (((int)combined_x3) >> 22);
1342 
1343  int dist_major2;
1344 
1345  sl_u32 scalelvl1, scalelvl2;
1346 
1347  // prefetch next ...
1348  if (pos == _countof(_cached_previous_ultracapsuledata.ultra_cabins) - 1) {
1349  dist_major2 = (capsule.ultra_cabins[0].combined_x3 & 0xFFF);
1350  }
1351  else {
1352  dist_major2 = (_cached_previous_ultracapsuledata.ultra_cabins[pos + 1].combined_x3 & 0xFFF);
1353  }
1354 
1355  // decode with the var bit scale ...
1356  dist_major = _varbitscale_decode(dist_major, scalelvl1);
1357  dist_major2 = _varbitscale_decode(dist_major2, scalelvl2);
1358 
1359 
1360  int dist_base1 = dist_major;
1361  int dist_base2 = dist_major2;
1362 
1363  if ((!dist_major) && dist_major2) {
1364  dist_base1 = dist_major2;
1365  scalelvl1 = scalelvl2;
1366  }
1367 
1368 
1369  dist_q2[0] = (dist_major << 2);
1370  if ((dist_predict1 == 0xFFFFFE00) || (dist_predict1 == 0x1FF)) {
1371  dist_q2[1] = 0;
1372  }
1373  else {
1374  dist_predict1 = (dist_predict1 << scalelvl1);
1375  dist_q2[1] = (dist_predict1 + dist_base1) << 2;
1376 
1377  }
1378 
1379  if ((dist_predict2 == 0xFFFFFE00) || (dist_predict2 == 0x1FF)) {
1380  dist_q2[2] = 0;
1381  }
1382  else {
1383  dist_predict2 = (dist_predict2 << scalelvl2);
1384  dist_q2[2] = (dist_predict2 + dist_base2) << 2;
1385  }
1386 
1387 
1388  for (int cpos = 0; cpos < 3; ++cpos) {
1389  syncBit[cpos] = (((currentAngle_raw_q16 + angleInc_q16) % (360 << 16)) < angleInc_q16) ? 1 : 0;
1390 
1391  int offsetAngleMean_q16 = (int)(7.5 * 3.1415926535 * (1 << 16) / 180.0);
1392 
1393  if (dist_q2[cpos] >= (50 * 4))
1394  {
1395  const int k1 = 98361;
1396  const int k2 = int(k1 / dist_q2[cpos]);
1397 
1398  offsetAngleMean_q16 = (int)(8 * 3.1415926535 * (1 << 16) / 180) - (k2 << 6) - (k2 * k2 * k2) / 98304;
1399  }
1400 
1401  angle_q6[cpos] = ((currentAngle_raw_q16 - int(offsetAngleMean_q16 * 180 / 3.14159265)) >> 10);
1402  currentAngle_raw_q16 += angleInc_q16;
1403 
1404  if (angle_q6[cpos] < 0) angle_q6[cpos] += (360 << 6);
1405  if (angle_q6[cpos] >= (360 << 6)) angle_q6[cpos] -= (360 << 6);
1406 
1408 
1409  node.flag = (syncBit[cpos] | ((!syncBit[cpos]) << 1));
1410  node.quality = dist_q2[cpos] ? (0x2F << SL_LIDAR_RESP_MEASUREMENT_QUALITY_SHIFT) : 0;
1411  node.angle_z_q14 = sl_u16((angle_q6[cpos] << 8) / 90);
1412  node.dist_mm_q2 = dist_q2[cpos];
1413 
1414  nodebuffer[nodeCount++] = node;
1415  }
1416 
1417  }
1418  }
1419 
1422  }
1423 
1424  sl_result _waitCapsuledNode(sl_lidar_response_capsule_measurement_nodes_t & node, sl_u32 timeout = DEFAULT_TIMEOUT)
1425  {
1426  int recvPos = 0;
1427  sl_u32 startTs = getms();
1428  sl_u8 recvBuffer[sizeof(sl_lidar_response_capsule_measurement_nodes_t)];
1429  sl_u8 *nodeBuffer = (sl_u8*)&node;
1430  sl_u32 waitTime;
1431  while ((waitTime = getms() - startTs) <= timeout) {
1432  size_t remainSize = sizeof(sl_lidar_response_capsule_measurement_nodes_t) - recvPos;
1433  size_t recvSize;
1434  bool ans = _channel->waitForData(remainSize, timeout - waitTime, &recvSize);
1435  if (!ans) return SL_RESULT_OPERATION_TIMEOUT;
1436 
1437  if (recvSize > remainSize) recvSize = remainSize;
1438  recvSize = _channel->read(recvBuffer, recvSize);
1439 
1440  for (size_t pos = 0; pos < recvSize; ++pos) {
1441  sl_u8 currentByte = recvBuffer[pos];
1442 
1443  switch (recvPos) {
1444  case 0: // expect the sync bit 1
1445  {
1446  sl_u8 tmp = (currentByte >> 4);
1448  // pass
1449  }
1450  else {
1452  continue;
1453  }
1454 
1455  }
1456  break;
1457  case 1: // expect the sync bit 2
1458  {
1459  sl_u8 tmp = (currentByte >> 4);
1461  // pass
1462  }
1463  else {
1464  recvPos = 0;
1466  continue;
1467  }
1468  }
1469  break;
1470  }
1471  nodeBuffer[recvPos++] = currentByte;
1472  if (recvPos == sizeof(sl_lidar_response_capsule_measurement_nodes_t)) {
1473  // calc the checksum ...
1474  sl_u8 checksum = 0;
1475  sl_u8 recvChecksum = ((node.s_checksum_1 & 0xF) | (node.s_checksum_2 << 4));
1476  for (size_t cpos = offsetof(sl_lidar_response_capsule_measurement_nodes_t, start_angle_sync_q6);
1477  cpos < sizeof(sl_lidar_response_capsule_measurement_nodes_t); ++cpos)
1478  {
1479  checksum ^= nodeBuffer[cpos];
1480  }
1481  if (recvChecksum == checksum) {
1482  // only consider vaild if the checksum matches...
1483  if (node.start_angle_sync_q6 & SL_LIDAR_RESP_MEASUREMENT_EXP_SYNCBIT) {
1484  // this is the first capsule frame in logic, discard the previous cached data...
1485  _scan_node_synced = false;
1487  return SL_RESULT_OK;
1488  }
1489  return SL_RESULT_OK;
1490  }
1492  return SL_RESULT_INVALID_DATA;
1493  }
1494  }
1495  }
1498  }
1499  void _capsuleToNormal(const sl_lidar_response_capsule_measurement_nodes_t & capsule, sl_lidar_response_measurement_node_hq_t *nodebuffer, size_t &nodeCount)
1500  {
1501  nodeCount = 0;
1503  int diffAngle_q8;
1504  int currentStartAngle_q8 = ((capsule.start_angle_sync_q6 & 0x7FFF) << 2);
1505  int prevStartAngle_q8 = ((_cached_previous_capsuledata.start_angle_sync_q6 & 0x7FFF) << 2);
1506 
1507  diffAngle_q8 = (currentStartAngle_q8)-(prevStartAngle_q8);
1508  if (prevStartAngle_q8 > currentStartAngle_q8) {
1509  diffAngle_q8 += (360 << 8);
1510  }
1511 
1512  int angleInc_q16 = (diffAngle_q8 << 3);
1513  int currentAngle_raw_q16 = (prevStartAngle_q8 << 8);
1514  for (size_t pos = 0; pos < _countof(_cached_previous_capsuledata.cabins); ++pos) {
1515  int dist_q2[2];
1516  int angle_q6[2];
1517  int syncBit[2];
1518 
1519  dist_q2[0] = (_cached_previous_capsuledata.cabins[pos].distance_angle_1 & 0xFFFC);
1520  dist_q2[1] = (_cached_previous_capsuledata.cabins[pos].distance_angle_2 & 0xFFFC);
1521 
1522  int angle_offset1_q3 = ((_cached_previous_capsuledata.cabins[pos].offset_angles_q3 & 0xF) | ((_cached_previous_capsuledata.cabins[pos].distance_angle_1 & 0x3) << 4));
1523  int angle_offset2_q3 = ((_cached_previous_capsuledata.cabins[pos].offset_angles_q3 >> 4) | ((_cached_previous_capsuledata.cabins[pos].distance_angle_2 & 0x3) << 4));
1524 
1525  angle_q6[0] = ((currentAngle_raw_q16 - (angle_offset1_q3 << 13)) >> 10);
1526  syncBit[0] = (((currentAngle_raw_q16 + angleInc_q16) % (360 << 16)) < angleInc_q16) ? 1 : 0;
1527  currentAngle_raw_q16 += angleInc_q16;
1528 
1529 
1530  angle_q6[1] = ((currentAngle_raw_q16 - (angle_offset2_q3 << 13)) >> 10);
1531  syncBit[1] = (((currentAngle_raw_q16 + angleInc_q16) % (360 << 16)) < angleInc_q16) ? 1 : 0;
1532  currentAngle_raw_q16 += angleInc_q16;
1533 
1534  for (int cpos = 0; cpos < 2; ++cpos) {
1535 
1536  if (angle_q6[cpos] < 0) angle_q6[cpos] += (360 << 6);
1537  if (angle_q6[cpos] >= (360 << 6)) angle_q6[cpos] -= (360 << 6);
1538 
1540 
1541  node.angle_z_q14 = sl_u16((angle_q6[cpos] << 8) / 90);
1542  node.flag = (syncBit[cpos] | ((!syncBit[cpos]) << 1));
1543  node.quality = dist_q2[cpos] ? (0x2f << SL_LIDAR_RESP_MEASUREMENT_QUALITY_SHIFT) : 0;
1544  node.dist_mm_q2 = dist_q2[cpos];
1545 
1546  nodebuffer[nodeCount++] = node;
1547  }
1548 
1549  }
1550  }
1551 
1552  _cached_previous_capsuledata = capsule;
1554  }
1555 
1556  void _dense_capsuleToNormal(const sl_lidar_response_capsule_measurement_nodes_t & capsule, sl_lidar_response_measurement_node_hq_t *nodebuffer, size_t &nodeCount)
1557  {
1558  static int lastNodeSyncBit = 0;
1559  const sl_lidar_response_dense_capsule_measurement_nodes_t *dense_capsule = reinterpret_cast<const sl_lidar_response_dense_capsule_measurement_nodes_t*>(&capsule);
1560  nodeCount = 0;
1562  int diffAngle_q8;
1563  int currentStartAngle_q8 = ((dense_capsule->start_angle_sync_q6 & 0x7FFF) << 2);
1564  int prevStartAngle_q8 = ((_cached_previous_dense_capsuledata.start_angle_sync_q6 & 0x7FFF) << 2);
1565 
1566  diffAngle_q8 = (currentStartAngle_q8)-(prevStartAngle_q8);
1567  if (prevStartAngle_q8 > currentStartAngle_q8) {
1568  diffAngle_q8 += (360 << 8);
1569  }
1570 
1571  int angleInc_q16 = (diffAngle_q8 << 8) / 40;
1572  int currentAngle_raw_q16 = (prevStartAngle_q8 << 8);
1573  for (size_t pos = 0; pos < _countof(_cached_previous_dense_capsuledata.cabins); ++pos) {
1574  int dist_q2;
1575  int angle_q6;
1576  int syncBit;
1577  const int dist = static_cast<const int>(_cached_previous_dense_capsuledata.cabins[pos].distance);
1578  dist_q2 = dist << 2;
1579  angle_q6 = (currentAngle_raw_q16 >> 10);
1580 
1581  syncBit = (((currentAngle_raw_q16 + angleInc_q16) % (360 << 16)) < (angleInc_q16<<1)) ? 1 : 0;
1582  syncBit = (syncBit^ lastNodeSyncBit)&syncBit;//Ensure that syncBit is exactly detected
1583  if (syncBit) {
1584  _scan_node_synced = true;
1585  }
1586 
1587  currentAngle_raw_q16 += angleInc_q16;
1588 
1589  if (angle_q6 < 0) angle_q6 += (360 << 6);
1590  if (angle_q6 >= (360 << 6)) angle_q6 -= (360 << 6);
1591 
1592 
1594 
1595  node.angle_z_q14 = sl_u16((angle_q6 << 8) / 90);
1596  node.flag = (syncBit | ((!syncBit) << 1));
1597  node.quality = dist_q2 ? (0x2f << SL_LIDAR_RESP_MEASUREMENT_QUALITY_SHIFT) : 0;
1598  node.dist_mm_q2 = dist_q2;
1599  if(_scan_node_synced)
1600  nodebuffer[nodeCount++] = node;
1601  lastNodeSyncBit = syncBit;
1602  }
1603  }
1604  else {
1605  _scan_node_synced = false;
1606  }
1607 
1608  _cached_previous_dense_capsuledata = *dense_capsule;
1610  }
1611 
1613  {
1614  sl_lidar_response_capsule_measurement_nodes_t capsule_node;
1616  size_t count = 256;
1618  size_t scan_count = 0;
1620  memset(local_scan, 0, sizeof(local_scan));
1621 
1622  _waitCapsuledNode(capsule_node); // // always discard the first data since it may be incomplete
1623 
1624  while (_isScanning) {
1625  ans = _waitCapsuledNode(capsule_node);
1626  if (!ans) {
1628  _isScanning = false;
1629  return SL_RESULT_OPERATION_FAIL;
1630  }
1631  else {
1632  // current data is invalid, do not use it.
1633  continue;
1634  }
1635  }
1636  switch (_cached_capsule_flag) {
1637  case NORMAL_CAPSULE:
1638  _capsuleToNormal(capsule_node, local_buf, count);
1639  break;
1640  case DENSE_CAPSULE:
1641  _dense_capsuleToNormal(capsule_node, local_buf, count);
1642  break;
1643  }
1644  //
1645 
1646  for (size_t pos = 0; pos < count; ++pos) {
1647  if (local_buf[pos].flag & SL_LIDAR_RESP_MEASUREMENT_SYNCBIT) {
1648  // only publish the data when it contains a full 360 degree scan
1649 
1650  if ((local_scan[0].flag & SL_LIDAR_RESP_MEASUREMENT_SYNCBIT)) {
1651  _lock.lock();
1652  memcpy(_cached_scan_node_hq_buf, local_scan, scan_count * sizeof(sl_lidar_response_measurement_node_hq_t));
1653  _cached_scan_node_hq_count = scan_count;
1654  _dataEvt.set();
1655  _lock.unlock();
1656  }
1657  scan_count = 0;
1658  }
1659  local_scan[scan_count++] = local_buf[pos];
1660  if (scan_count == _countof(local_scan)) scan_count -= 1; // prevent overflow
1661 
1662  //for interval retrieve
1663  {
1667  }
1668  }
1669  }
1670  _isScanning = false;
1671 
1672  return SL_RESULT_OK;
1673  }
1674 
1675  sl_result _waitHqNode(sl_lidar_response_hq_capsule_measurement_nodes_t & node, sl_u32 timeout = DEFAULT_TIMEOUT)
1676  {
1677  if (!_isConnected) {
1678  return SL_RESULT_OPERATION_FAIL;
1679  }
1680 
1681  int recvPos = 0;
1682  sl_u32 startTs = getms();
1683  sl_u8 recvBuffer[sizeof(sl_lidar_response_hq_capsule_measurement_nodes_t)];
1684  sl_u8 *nodeBuffer = (sl_u8*)&node;
1685  sl_u32 waitTime;
1686 
1687  while ((waitTime = getms() - startTs) <= timeout) {
1688  size_t remainSize = sizeof(sl_lidar_response_hq_capsule_measurement_nodes_t) - recvPos;
1689  size_t recvSize;
1690 
1691  bool ans = _channel->waitForData(remainSize, timeout - waitTime, &recvSize);
1692  if (!ans){
1694  }
1695  if (recvSize > remainSize) recvSize = remainSize;
1696 
1697  recvSize = _channel->read(recvBuffer, recvSize);
1698 
1699  for (size_t pos = 0; pos < recvSize; ++pos) {
1700  sl_u8 currentByte = recvBuffer[pos];
1701  switch (recvPos) {
1702  case 0: // expect the sync byte
1703  {
1704  sl_u8 tmp = (currentByte);
1705  if (tmp == SL_LIDAR_RESP_MEASUREMENT_HQ_SYNC) {
1706  // pass
1707  }
1708  else {
1709  recvPos = 0;
1710  _is_previous_HqdataRdy = false;
1711  continue;
1712  }
1713  }
1714  break;
1715  case sizeof(sl_lidar_response_hq_capsule_measurement_nodes_t) - 1 - 4:
1716  {
1717 
1718  }
1719  break;
1720  case sizeof(sl_lidar_response_hq_capsule_measurement_nodes_t) - 1:
1721  {
1722 
1723  }
1724  break;
1725  }
1726  nodeBuffer[recvPos++] = currentByte;
1727  if (recvPos == sizeof(sl_lidar_response_hq_capsule_measurement_nodes_t)) {
1728  sl_u32 crcCalc2 = crc32::getResult(nodeBuffer, sizeof(sl_lidar_response_hq_capsule_measurement_nodes_t) - 4);
1729 
1730  if (crcCalc2 == node.crc32) {
1731  _is_previous_HqdataRdy = true;
1732  return SL_RESULT_OK;
1733  }
1734  else {
1735  _is_previous_HqdataRdy = false;
1736  return SL_RESULT_INVALID_DATA;
1737  }
1738 
1739  }
1740  }
1741  }
1742  _is_previous_HqdataRdy = false;
1744  }
1745 
1746  void _HqToNormal(const sl_lidar_response_hq_capsule_measurement_nodes_t & node_hq, sl_lidar_response_measurement_node_hq_t *nodebuffer, size_t &nodeCount)
1747  {
1748  nodeCount = 0;
1749  if (_is_previous_HqdataRdy) {
1750  for (size_t pos = 0; pos < _countof(_cached_previous_Hqdata.node_hq); ++pos) {
1751  nodebuffer[nodeCount++] = node_hq.node_hq[pos];
1752  }
1753  }
1755  _is_previous_HqdataRdy = true;
1756 
1757  }
1758 
1760  {
1761  sl_lidar_response_hq_capsule_measurement_nodes_t hq_node;
1763  size_t count = 256;
1765  size_t scan_count = 0;
1767  memset(local_scan, 0, sizeof(local_scan));
1768  _waitHqNode(hq_node);
1769  while (_isScanning) {
1770  ans = _waitHqNode(hq_node);
1771  if (!ans) {
1773  _isScanning = false;
1774  return SL_RESULT_OPERATION_FAIL;
1775  }
1776  else {
1777  // current data is invalid, do not use it.
1778  continue;
1779  }
1780  }
1781 
1782  _HqToNormal(hq_node, local_buf, count);
1783  for (size_t pos = 0; pos < count; ++pos){
1784  if (local_buf[pos].flag & SL_LIDAR_RESP_MEASUREMENT_SYNCBIT){
1785  // only publish the data when it contains a full 360 degree scan
1786  if ((local_scan[0].flag & SL_LIDAR_RESP_MEASUREMENT_SYNCBIT)) {
1787  _lock.lock();
1788  memcpy(_cached_scan_node_hq_buf, local_scan, scan_count * sizeof(sl_lidar_response_measurement_node_hq_t));
1789  _cached_scan_node_hq_count = scan_count;
1790  _dataEvt.set();
1791  _lock.unlock();
1792  }
1793  scan_count = 0;
1794  }
1795  local_scan[scan_count++] = local_buf[pos];
1796  if (scan_count == _countof(local_scan)) scan_count -= 1; // prevent overflow
1797  //for interval retrieve
1798  {
1802  }
1803  }
1804 
1805  }
1806  return SL_RESULT_OK;
1807  }
1808 
1809  sl_result _waitUltraCapsuledNode(sl_lidar_response_ultra_capsule_measurement_nodes_t & node, sl_u32 timeout = DEFAULT_TIMEOUT)
1810  {
1811  if (!_isConnected) {
1812  return SL_RESULT_OPERATION_FAIL;
1813  }
1814 
1815  int recvPos = 0;
1816  sl_u32 startTs = getms();
1817  sl_u8 recvBuffer[sizeof(sl_lidar_response_ultra_capsule_measurement_nodes_t)];
1818  sl_u8 *nodeBuffer = (sl_u8*)&node;
1819  sl_u32 waitTime;
1820 
1821  while ((waitTime = getms() - startTs) <= timeout) {
1822  size_t remainSize = sizeof(sl_lidar_response_ultra_capsule_measurement_nodes_t) - recvPos;
1823  size_t recvSize;
1824 
1825  bool ans = _channel->waitForData(remainSize, timeout - waitTime, &recvSize);
1826  if (!ans) {
1828  }
1829  if (recvSize > remainSize) recvSize = remainSize;
1830 
1831  recvSize = _channel->read(recvBuffer, recvSize);
1832 
1833  for (size_t pos = 0; pos < recvSize; ++pos) {
1834  sl_u8 currentByte = recvBuffer[pos];
1835  switch (recvPos) {
1836  case 0: // expect the sync bit 1
1837  {
1838  sl_u8 tmp = (currentByte >> 4);
1840  // pass
1841  }
1842  else {
1844  continue;
1845  }
1846  }
1847  break;
1848  case 1: // expect the sync bit 2
1849  {
1850  sl_u8 tmp = (currentByte >> 4);
1852  // pass
1853  }
1854  else {
1855  recvPos = 0;
1857  continue;
1858  }
1859  }
1860  break;
1861  }
1862  nodeBuffer[recvPos++] = currentByte;
1863  if (recvPos == sizeof(sl_lidar_response_ultra_capsule_measurement_nodes_t)) {
1864  // calc the checksum ...
1865  sl_u8 checksum = 0;
1866  sl_u8 recvChecksum = ((node.s_checksum_1 & 0xF) | (node.s_checksum_2 << 4));
1867 
1868  for (size_t cpos = offsetof(sl_lidar_response_ultra_capsule_measurement_nodes_t, start_angle_sync_q6);
1869  cpos < sizeof(sl_lidar_response_ultra_capsule_measurement_nodes_t); ++cpos)
1870  {
1871  checksum ^= nodeBuffer[cpos];
1872  }
1873 
1874  if (recvChecksum == checksum) {
1875  // only consider vaild if the checksum matches...
1876  if (node.start_angle_sync_q6 & SL_LIDAR_RESP_MEASUREMENT_EXP_SYNCBIT) {
1877  // this is the first capsule frame in logic, discard the previous cached data...
1879  return SL_RESULT_OK;
1880  }
1881  return SL_RESULT_OK;
1882  }
1884  return SL_RESULT_INVALID_DATA;
1885  }
1886  }
1887  }
1890  }
1891 
1893  {
1894  sl_lidar_response_ultra_capsule_measurement_nodes_t ultra_capsule_node;
1896  size_t count = 256;
1898  size_t scan_count = 0;
1900  memset(local_scan, 0, sizeof(local_scan));
1901 
1902  _waitUltraCapsuledNode(ultra_capsule_node);
1903 
1904  while (_isScanning) {
1905  ans = _waitUltraCapsuledNode(ultra_capsule_node);
1906  if (!ans) {
1908  _isScanning = false;
1909  return SL_RESULT_OPERATION_FAIL;
1910  }
1911  else {
1912  // current data is invalid, do not use it.
1913  continue;
1914  }
1915  }
1916 
1917  _ultraCapsuleToNormal(ultra_capsule_node, local_buf, count);
1918 
1919  for (size_t pos = 0; pos < count; ++pos) {
1920  if (local_buf[pos].flag & SL_LIDAR_RESP_MEASUREMENT_SYNCBIT) {
1921  // only publish the data when it contains a full 360 degree scan
1922 
1923  if ((local_scan[0].flag & SL_LIDAR_RESP_MEASUREMENT_SYNCBIT)) {
1924  _lock.lock();
1925  memcpy(_cached_scan_node_hq_buf, local_scan, scan_count * sizeof(sl_lidar_response_measurement_node_hq_t));
1926  _cached_scan_node_hq_count = scan_count;
1927  _dataEvt.set();
1928  _lock.unlock();
1929  }
1930  scan_count = 0;
1931  }
1932  local_scan[scan_count++] = local_buf[pos];
1933  if (scan_count == _countof(local_scan)) scan_count -= 1; // prevent overflow
1934 
1935  //for interval retrieve
1936  {
1940  }
1941  }
1942  }
1943 
1944  _isScanning = false;
1945 
1946  return SL_RESULT_OK;
1947  }
1949  {
1950  if (!isConnected())
1951  return SL_RESULT_OPERATION_FAIL;
1952  _channel->flush();
1953  return SL_RESULT_OK;
1954  }
1955 
1956  private:
1967 
1971 
1974 
1975  sl_lidar_response_capsule_measurement_nodes_t _cached_previous_capsuledata;
1976  sl_lidar_response_dense_capsule_measurement_nodes_t _cached_previous_dense_capsuledata;
1977  sl_lidar_response_ultra_capsule_measurement_nodes_t _cached_previous_ultracapsuledata;
1978  sl_lidar_response_hq_capsule_measurement_nodes_t _cached_previous_Hqdata;
1981  };
1982 
1984  {
1985  return new SlamtecLidarDriver();
1986  }
1987 }
#define offsetof(_structure, _field)
Definition: util.h:55
virtual void clearReadCache()=0
#define CLASS_THREAD(c, x)
Definition: thread.h:38
#define SL_LIDAR_CMD_GET_DEVICE_HEALTH
Definition: sl_lidar_cmd.h:55
#define SL_LIDAR_ANS_TYPE_GET_LIDAR_CONF
Definition: sl_lidar_cmd.h:151
sl_result negotiateSerialBaudRate(sl_u32 requiredBaudRate, sl_u32 *baudRateDetected)
#define SL_LIDAR_CONF_SCAN_MODE_US_PER_SAMPLE
Definition: sl_lidar_cmd.h:280
sl_result getScanModeAnsType(sl_u8 &ansType, sl_u16 scanModeID, sl_u32 timeoutInMs=DEFAULT_TIMEOUT)
#define SL_LIDAR_CMD_SCAN
Definition: sl_lidar_cmd.h:46
sl_result connect(IChannel *channel)
#define SL_LIDAR_CMD_HQ_MOTOR_SPEED_CTRL
Definition: sl_lidar_cmd.h:59
f
Definition: sl_crc.h:38
#define SL_LIDAR_VARBITSCALE_X16_SRC_BIT
Definition: sl_lidar_cmd.h:337
sl_result _cacheUltraCapsuledScanData()
sl_result getLidarConf(sl_u32 type, std::vector< sl_u8 > &outputBuf, const std::vector< sl_u8 > &reserve=std::vector< sl_u8 >(), sl_u32 timeout=DEFAULT_TIMEOUT)
#define SL_LIDAR_RESP_MEASUREMENT_QUALITY_SHIFT
Definition: sl_lidar_cmd.h:168
size_t _cached_scan_node_hq_count_for_interval_retrieve
sl_result reset(sl_u32 timeoutInMs=DEFAULT_TIMEOUT)
sl_result getDeviceMacAddr(sl_u8 *macAddrArray, sl_u32 timeoutInMs)
void _capsuleToNormal(const sl_lidar_response_capsule_measurement_nodes_t &capsule, sl_lidar_response_measurement_node_hq_t *nodebuffer, size_t &nodeCount)
sl_result getHealth(sl_lidar_response_device_health_t &health, sl_u32 timeout=DEFAULT_TIMEOUT)
static bool angleLessThan(const TNode &a, const TNode &b)
#define SL_LIDAR_CMD_SYNC_BYTE
#define SL_LIDAR_CMD_SET_LIDAR_CONF
Definition: sl_lidar_cmd.h:66
sl_result getMotorInfo(LidarMotorInfo &motorInfo, sl_u32 timeoutInMs)
#define MAX_SCAN_NODES
sl_result getTypicalScanMode(sl_u16 &outMode, sl_u32 timeoutInMs=DEFAULT_TIMEOUT)
Get typical scan mode of lidar.
#define SL_LIDAR_CMD_GET_DEVICE_INFO
Definition: sl_lidar_cmd.h:54
rp::hal::Thread _cachethread
sl_lidar_response_measurement_node_hq_t _cached_scan_node_hq_buf[8192]
#define RESULT_OK
Definition: rptypes.h:102
#define SL_LIDAR_RESP_MEASUREMENT_EXP_SYNCBIT
Definition: sl_lidar_cmd.h:205
#define SL_LIDAR_CMDFLAG_HAS_PAYLOAD
void _ultraCapsuleToNormal(const sl_lidar_response_ultra_capsule_measurement_nodes_t &capsule, sl_lidar_response_measurement_node_hq_t *nodebuffer, size_t &nodeCount)
sl_result setMotorSpeed(sl_u16 speed=DEFAULT_MOTOR_SPEED)
#define SL_LIDAR_CMD_STOP
Definition: sl_lidar_cmd.h:45
sl_u32 result
Definition: sl_lidar_cmd.h:43
sl_result ascendScanData(sl_lidar_response_measurement_node_hq_t *nodebuffer, size_t count)
sl_lidar_response_measurement_node_hq_t _cached_scan_node_hq_buf_for_interval_retrieve[8192]
sl_result _waitHqNode(sl_lidar_response_hq_capsule_measurement_nodes_t &node, sl_u32 timeout=DEFAULT_TIMEOUT)
sl_u32 combined_x3
Definition: sl_lidar_cmd.h:45
sl_lidar_response_ultra_capsule_measurement_nodes_t _cached_previous_ultracapsuledata
sl_result checkMotorCtrlSupport(MotorCtrlSupport &support, sl_u32 timeout=DEFAULT_TIMEOUT)
MotorCtrlSupport motorCtrlSupport
sl_result getMaxDistance(float &maxDistance, sl_u16 scanModeID, sl_u32 timeoutInMs=DEFAULT_TIMEOUT)
#define SL_LIDAR_VARBITSCALE_X2_SRC_BIT
Definition: sl_lidar_cmd.h:334
#define SL_LIDAR_ANS_TYPE_MEASUREMENT_HQ
Definition: sl_lidar_cmd.h:143
#define SL_LIDAR_ANS_TYPE_MEASUREMENT
Definition: sl_lidar_cmd.h:140
#define delay(x)
Definition: win32/timer.h:39
#define SL_LIDAR_RESP_MEASUREMENT_EXP_SYNC_1
Definition: sl_lidar_cmd.h:200
#define IS_FAIL(x)
Definition: rptypes.h:114
MotorCtrlSupport
static void setAngle(sl_lidar_response_measurement_node_t &node, float v)
sl_result stop(sl_u32 timeout=DEFAULT_TIMEOUT)
virtual void close()=0
sl_result setLidarIpConf(const sl_lidar_ip_conf_t &conf, sl_u32 timeout)
#define SL_LIDAR_RESP_ACC_BOARD_FLAG_MOTOR_CTRL_SUPPORT_MASK
Definition: sl_lidar_cmd.h:156
virtual bool waitForData(size_t size, sl_u32 timeoutInMs=-1, size_t *actualReady=nullptr)=0
#define SL_LIDAR_CMD_EXPRESS_SCAN
Definition: sl_lidar_cmd.h:63
#define SL_RESULT_ALREADY_DONE
Definition: sl_types.h:73
int wait(unsigned long timeout=0xFFFFFFFF)
Definition: event.h:98
#define SL_LIDAR_RESP_MEASUREMENT_SYNCBIT
Definition: sl_lidar_cmd.h:167
uint8_t _u8
Definition: rptypes.h:63
#define SL_LIDAR_RESP_MEASUREMENT_ANGLE_SHIFT
Definition: sl_lidar_cmd.h:173
#define SL_LIDAR_ANS_TYPE_DEVINFO
Definition: sl_lidar_cmd.h:137
static sl_result ascendScanData_(TNode *nodebuffer, size_t count)
sl_result setLidarConf(sl_u32 type, const void *payload, size_t payloadSize, sl_u32 timeout)
#define SL_LIDAR_VARBITSCALE_X8_SRC_BIT
Definition: sl_lidar_cmd.h:336
void _HqToNormal(const sl_lidar_response_hq_capsule_measurement_nodes_t &node_hq, sl_lidar_response_measurement_node_hq_t *nodebuffer, size_t &nodeCount)
sl_u8 flag
Definition: sl_lidar_cmd.h:43
#define RPLIDAR_CONF_MAX_ROT_FREQ
Definition: rplidar_cmd.h:175
Result< ILidarDriver * > createLidarDriver()
sl_u32 type
Definition: sl_lidar_cmd.h:43
sl_result getScanModeName(char *modeName, sl_u16 scanModeID, sl_u32 timeoutInMs=DEFAULT_TIMEOUT)
void unlock()
Definition: locker.h:117
#define SL_LIDAR_CONF_SCAN_COMMAND_EXPRESS
Definition: sl_lidar_cmd.h:266
virtual void flush()=0
#define SL_LIDAR_ANS_HEADER_SIZE_MASK
#define DEFAULT_MOTOR_SPEED
Definition: sl_lidar_cmd.h:112
#define SL_LIDAR_CMD_GET_ACC_BOARD_FLAG
Definition: sl_lidar_cmd.h:69
#define SL_LIDAR_VARBITSCALE_X2_DEST_VAL
Definition: sl_lidar_cmd.h:339
sl_result startScan(bool force, bool useTypicalScan, sl_u32 options=0, LidarScanMode *outUsedScanMode=nullptr)
#define getms()
Definition: linux/timer.h:57
#define SL_LIDAR_CONF_LIDAR_MAC_ADDR
Definition: sl_lidar_cmd.h:283
sl_result _waitResponseHeader(sl_lidar_ans_header_t *header, sl_u32 timeout=DEFAULT_TIMEOUT)
#define SL_LIDAR_RESP_MEASUREMENT_EXP_SYNC_2
Definition: sl_lidar_cmd.h:201
#define SL_LIDAR_ANS_TYPE_ACC_BOARD_FLAG
Definition: sl_lidar_cmd.h:154
sl_result _waitCapsuledNode(sl_lidar_response_capsule_measurement_nodes_t &node, sl_u32 timeout=DEFAULT_TIMEOUT)
void set(bool isSignal=true)
Definition: event.h:70
#define RESULT_OPERATION_TIMEOUT
Definition: rptypes.h:107
sl_result getScanDataWithIntervalHq(sl_lidar_response_measurement_node_hq_t *nodebuffer, size_t &count)
virtual int write(const void *data, size_t size)=0
#define SL_LIDAR_VARBITSCALE_X4_SRC_BIT
Definition: sl_lidar_cmd.h:335
#define SL_LIDAR_ANS_SYNC_BYTE2
#define SL_LIDAR_VARBITSCALE_X16_DEST_VAL
Definition: sl_lidar_cmd.h:342
sl_lidar_response_measurement_node_hq_t node_hq[96]
Definition: sl_lidar_cmd.h:45
static void printDeprecationWarn(const char *fn, const char *replacement)
u_result join(unsigned long timeout=-1)
#define SL_LIDAR_ANS_TYPE_SET_LIDAR_CONF
Definition: sl_lidar_cmd.h:152
#define SL_LIDAR_ANS_TYPE_DEVHEALTH
Definition: sl_lidar_cmd.h:138
#define SL_LIDAR_CONF_SCAN_MODE_COUNT
Definition: sl_lidar_cmd.h:279
sl_result getDesiredSpeed(sl_lidar_response_desired_rot_speed_t &motorSpeed, sl_u32 timeoutInMs=DEFAULT_TIMEOUT)
_word_size_t getHandle()
Definition: thread.h:71
static float getAngle(const sl_lidar_response_measurement_node_t &node)
sl_result getLidarSampleDuration(float &sampleDurationRes, sl_u16 scanModeID, sl_u32 timeoutInMs=DEFAULT_TIMEOUT)
#define SL_LIDAR_CMD_SET_MOTOR_PWM
Definition: sl_lidar_cmd.h:68
#define SL_LIDAR_CONF_SCAN_COMMAND_STD
Definition: sl_lidar_cmd.h:265
#define SL_LIDAR_VARBITSCALE_X8_DEST_VAL
Definition: sl_lidar_cmd.h:341
#define SL_LIDAR_ANS_TYPE_MEASUREMENT_DENSE_CAPSULED
Definition: sl_lidar_cmd.h:153
sl_result startScanExpress(bool force, sl_u16 scanMode, sl_u32 options=0, LidarScanMode *outUsedScanMode=nullptr, sl_u32 timeout=DEFAULT_TIMEOUT)
sl_u8 payload[0]
Definition: sl_lidar_cmd.h:44
MotorCtrlSupport _isSupportingMotorCtrl
void _dense_capsuleToNormal(const sl_lidar_response_capsule_measurement_nodes_t &capsule, sl_lidar_response_measurement_node_hq_t *nodebuffer, size_t &nodeCount)
static sl_u32 _varbitscale_decode(sl_u32 scaled, sl_u32 &scaleLevel)
Locker::LOCK_STATUS lock(unsigned long timeout=0xFFFFFFFF)
Definition: locker.h:60
#define SL_LIDAR_CONF_SCAN_MODE_MAX_DISTANCE
Definition: sl_lidar_cmd.h:281
sl_result getScanModeCount(sl_u16 &modeCount, sl_u32 timeoutInMs=DEFAULT_TIMEOUT)
sl_result getResult(sl_u8 *ptr, sl_u32 len)
Definition: sl_crc.cpp:92
sl_result startScanNormal(bool force, sl_u32 timeout=DEFAULT_TIMEOUT)
virtual int read(void *buffer, size_t size)=0
sl_u8 sync_quality
Definition: sl_lidar_cmd.h:43
#define SL_LIDAR_RESP_MEASUREMENT_CHECKBIT
Definition: sl_lidar_cmd.h:172
#define SL_LIDAR_RESP_MEASUREMENT_HQ_SYNC
Definition: sl_lidar_cmd.h:203
#define SL_LIDAR_ANS_SYNC_BYTE1
sl_result _waitResponse(T &payload, sl_u8 ansType, sl_u32 timeout=DEFAULT_TIMEOUT)
uint32_t _u32
Definition: rptypes.h:69
#define RPLIDAR_CMD_NEW_BAUDRATE_CONFIRM
Definition: rplidar_cmd.h:60
sl_lidar_response_dense_capsule_measurement_nodes_t _cached_previous_dense_capsuledata
#define RPLIDAR_CONF_MIN_ROT_FREQ
Definition: rplidar_cmd.h:174
#define SL_LIDAR_CONF_SCAN_MODE_TYPICAL
Definition: sl_lidar_cmd.h:284
sl_lidar_response_capsule_measurement_nodes_t _cached_previous_capsuledata
sl_result getAllSupportedScanModes(std::vector< LidarScanMode > &outModes, sl_u32 timeoutInMs=DEFAULT_TIMEOUT)
Get all scan modes that supported by lidar.
#define SL_RESULT_OPERATION_FAIL
Definition: sl_types.h:75
sl_result getFrequency(const LidarScanMode &scanMode, const sl_lidar_response_measurement_node_hq_t *nodes, size_t count, float &frequency)
#define SL_LIDAR_CONF_DESIRED_ROT_FREQ
Definition: sl_lidar_cmd.h:273
#define RESULT_OPERATION_FAIL
Definition: rptypes.h:106
sl_result getDeviceInfo(sl_lidar_response_device_info_t &info, sl_u32 timeout=DEFAULT_TIMEOUT)
static void convert(const sl_lidar_response_measurement_node_t &from, sl_lidar_response_measurement_node_hq_t &to)
sl_result _sendCommand(sl_u16 cmd, const void *payload=NULL, size_t payloadsize=0)
#define SL_LIDAR_ANS_TYPE_MEASUREMENT_CAPSULED
Definition: sl_lidar_cmd.h:142
#define SL_LIDAR_VARBITSCALE_X4_DEST_VAL
Definition: sl_lidar_cmd.h:340
virtual bool open()=0
uint32_t sl_result
Definition: sl_types.h:69
sl_result grabScanDataHq(sl_lidar_response_measurement_node_hq_t *nodebuffer, size_t &count, sl_u32 timeout=DEFAULT_TIMEOUT)
sl_result checkSupportConfigCommands(bool &outSupport, sl_u32 timeoutInMs=DEFAULT_TIMEOUT)
#define SL_LIDAR_CMD_RESET
Definition: sl_lidar_cmd.h:48
#define SL_LIDAR_CONF_SCAN_MODE_ANS_TYPE
Definition: sl_lidar_cmd.h:282
#define SL_IS_FAIL(x)
Definition: sl_types.h:83
sl_result _waitNode(sl_lidar_response_measurement_node_t *node, sl_u32 timeout=DEFAULT_TIMEOUT)
#define _countof(_Array)
Definition: util.h:42
#define SL_LIDAR_CONF_SCAN_MODE_NAME
Definition: sl_lidar_cmd.h:285
#define SL_LIDAR_CONF_LIDAR_STATIC_IP_ADDR
Definition: sl_lidar_cmd.h:288
#define SL_RESULT_OK
Definition: sl_types.h:71
#define SL_RESULT_INVALID_DATA
Definition: sl_types.h:74
#define SL_LIDAR_AUTOBAUD_MAGICBYTE
Definition: sl_lidar_cmd.h:42
sl_result _waitUltraCapsuledNode(sl_lidar_response_ultra_capsule_measurement_nodes_t &node, sl_u32 timeout=DEFAULT_TIMEOUT)
static sl_u16 getDistanceQ2(const sl_lidar_response_measurement_node_t &node)
#define SL_LIDAR_CMD_FORCE_SCAN
Definition: sl_lidar_cmd.h:47
#define SL_RESULT_OPERATION_TIMEOUT
Definition: sl_types.h:76
sl_u16 start_angle_sync_q6
Definition: sl_lidar_cmd.h:45
#define SL_LIDAR_CMD_GET_LIDAR_CONF
Definition: sl_lidar_cmd.h:65
sl_result _waitScanData(sl_lidar_response_measurement_node_t *nodebuffer, size_t &count, sl_u32 timeout=DEFAULT_TIMEOUT)
sl_lidar_response_hq_capsule_measurement_nodes_t _cached_previous_Hqdata


rplidar_ros
Author(s):
autogenerated on Tue Jun 13 2023 02:07:38