diff --git a/CHANGELOG.rst b/CHANGELOG.rst index 79ff5522..dafad8a7 100644 --- a/CHANGELOG.rst +++ b/CHANGELOG.rst @@ -2,6 +2,12 @@ Changelog for package rplidar_ros ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +1.10.0 (2019-02-22) +------------------ +* Update RPLIDAR SDK to 1.10.0 +* [new feature] support Rplidar S1 +* Contributors: tony,WubinXia + 1.9.0 (2018-08-24) ------------------ * Update RPLIDAR SDK to 1.9.0 diff --git a/README.md b/README.md index 2dc72c1d..12d2a236 100644 --- a/README.md +++ b/README.md @@ -25,22 +25,26 @@ There're two ways to run rplidar ros package I. Run rplidar node and view in the rviz ------------------------------------------------------------ roslaunch rplidar_ros view_rplidar.launch (for RPLIDAR A1/A2) -or +, roslaunch rplidar_ros view_rplidar_a3.launch (for RPLIDAR A3) +or +roslaunch rplidar_ros view_rplidar_s1.launch (for RPLIDAR S1) You should see rplidar's scan result in the rviz. II. Run rplidar node and view using test application ------------------------------------------------------------ roslaunch rplidar_ros rplidar.launch (for RPLIDAR A1/A2) -or +, roslaunch rplidar_ros rplidar_a3.launch (for RPLIDAR A3) +or +roslaunch rplidar_ros rplidar_s1.launch (for RPLIDAR S1) rosrun rplidar_ros rplidarNodeClient You should see rplidar's scan result in the console -Notice: the different is serial_baudrate between A1/A2 and A3 +Notice: the different is serial_baudrate between A1/A2 and A3/S1 RPLidar frame ===================================================================== diff --git a/launch/rplidar_s1.launch b/launch/rplidar_s1.launch new file mode 100644 index 00000000..11753abd --- /dev/null +++ b/launch/rplidar_s1.launch @@ -0,0 +1,10 @@ + + + + + + + + + + diff --git a/launch/view_rplidar_s1.launch b/launch/view_rplidar_s1.launch new file mode 100644 index 00000000..e3c3127e --- /dev/null +++ b/launch/view_rplidar_s1.launch @@ -0,0 +1,10 @@ + + + + + + diff --git a/package.xml b/package.xml index 9954fde6..78c1a295 100644 --- a/package.xml +++ b/package.xml @@ -1,8 +1,8 @@ rplidar_ros - 1.9.0 - The rplidar ros package, support rplidar A2/A1 and A3 + 1.10.0 + The rplidar ros package, support rplidar A2/A1 and A3/S1 Slamtec ROS Maintainer BSD diff --git a/sdk/README.txt b/sdk/README.txt index 689bb8da..b05d81fd 100644 --- a/sdk/README.txt +++ b/sdk/README.txt @@ -1,5 +1,5 @@ Copyright (c) 2009 - 2014 RoboPeak Team -Copyright (c) 2014 - 2018 Shanghai Slamtec Co., Ltd. +Copyright (c) 2014 - 2019 Shanghai Slamtec Co., Ltd. All rights reserved. Redistribution and use in source and binary forms, with or without @@ -29,6 +29,6 @@ This folder contains RPLIDAR SDK source code which is provided by RoboPeak. RoboPeak Website: http://www.robopeak.com SlamTec HomePage: http://www.slamtec.com -RPLIDAR_SDK_VERSION: 1.9.0 +RPLIDAR_SDK_VERSION: 1.10.0 Note: The SDK version may not up-to-date. rplidar product: http://www.slamtec.com/en/Lidar diff --git a/sdk/include/rplidar.h b/sdk/include/rplidar.h index 660a5e1a..4e14aa06 100644 --- a/sdk/include/rplidar.h +++ b/sdk/include/rplidar.h @@ -3,7 +3,7 @@ * * Copyright (c) 2009 - 2014 RoboPeak Team * http://www.robopeak.com - * Copyright (c) 2014 - 2018 Shanghai Slamtec Co., Ltd. + * Copyright (c) 2014 - 2019 Shanghai Slamtec Co., Ltd. * http://www.slamtec.com * */ @@ -41,4 +41,4 @@ #include "rplidar_driver.h" -#define RPLIDAR_SDK_VERSION "1.9.0" +#define RPLIDAR_SDK_VERSION "1.10.0" diff --git a/sdk/include/rplidar_cmd.h b/sdk/include/rplidar_cmd.h index 2aadfbb0..cfe07604 100644 --- a/sdk/include/rplidar_cmd.h +++ b/sdk/include/rplidar_cmd.h @@ -3,7 +3,7 @@ * * Copyright (c) 2009 - 2014 RoboPeak Team * http://www.robopeak.com - * Copyright (c) 2014 - 2018 Shanghai Slamtec Co., Ltd. + * Copyright (c) 2014 - 2019 Shanghai Slamtec Co., Ltd. * http://www.slamtec.com * */ @@ -127,7 +127,7 @@ typedef struct _rplidar_payload_acc_board_flag_t { //added in FW ver 1.24 #define RPLIDAR_ANS_TYPE_GET_LIDAR_CONF 0x20 #define RPLIDAR_ANS_TYPE_SET_LIDAR_CONF 0x21 - +#define RPLIDAR_ANS_TYPE_MEASUREMENT_DENSE_CAPSULED 0x85 #define RPLIDAR_ANS_TYPE_ACC_BOARD_FLAG 0xFF #define RPLIDAR_RESP_ACC_BOARD_FLAG_MOTOR_CTRL_SUPPORT_MASK (0x1) @@ -183,6 +183,18 @@ typedef struct _rplidar_response_capsule_measurement_nodes_t { _u16 start_angle_sync_q6; rplidar_response_cabin_nodes_t cabins[16]; } __attribute__((packed)) rplidar_response_capsule_measurement_nodes_t; + +typedef struct _rplidar_response_dense_cabin_nodes_t { + _u16 distance; +} __attribute__((packed)) rplidar_response_dense_cabin_nodes_t; + +typedef struct _rplidar_response_dense_capsule_measurement_nodes_t { + _u8 s_checksum_1; // see [s_checksum_1] + _u8 s_checksum_2; // see [s_checksum_1] + _u16 start_angle_sync_q6; + rplidar_response_dense_cabin_nodes_t cabins[40]; +} __attribute__((packed)) rplidar_response_dense_capsule_measurement_nodes_t; + // ext1 : x2 boost mode #define RPLIDAR_RESP_MEASUREMENT_EXP_ULTRA_MAJOR_BITS 12 diff --git a/sdk/include/rplidar_driver.h b/sdk/include/rplidar_driver.h index 8db32280..b73b8459 100644 --- a/sdk/include/rplidar_driver.h +++ b/sdk/include/rplidar_driver.h @@ -3,7 +3,7 @@ * * Copyright (c) 2009 - 2014 RoboPeak Team * http://www.robopeak.com - * Copyright (c) 2014 - 2018 Shanghai Slamtec Co., Ltd. + * Copyright (c) 2014 - 2019 Shanghai Slamtec Co., Ltd. * http://www.slamtec.com * */ @@ -132,6 +132,7 @@ class RPlidarDriver { /// \param timeout The operation timeout value (in millisecond) for the serial port communication virtual u_result reset(_u32 timeout = DEFAULT_TIMEOUT) = 0; + virtual u_result clearNetSerialRxCache() = 0; // FW1.24 /// Get all scan modes that supported by lidar virtual u_result getAllSupportedScanModes(std::vector& outModes, _u32 timeoutInMs = DEFAULT_TIMEOUT) = 0; diff --git a/sdk/include/rplidar_protocol.h b/sdk/include/rplidar_protocol.h index be2dba34..2f8231b7 100644 --- a/sdk/include/rplidar_protocol.h +++ b/sdk/include/rplidar_protocol.h @@ -3,7 +3,7 @@ * * Copyright (c) 2009 - 2014 RoboPeak Team * http://www.robopeak.com - * Copyright (c) 2014 - 2018 Shanghai Slamtec Co., Ltd. + * Copyright (c) 2014 - 2019 Shanghai Slamtec Co., Ltd. * http://www.slamtec.com * */ diff --git a/sdk/include/rptypes.h b/sdk/include/rptypes.h index 5036eeff..34d8ecb1 100644 --- a/sdk/include/rptypes.h +++ b/sdk/include/rptypes.h @@ -3,7 +3,7 @@ * * Copyright (c) 2009 - 2014 RoboPeak Team * http://www.robopeak.com - * Copyright (c) 2014 - 2018 Shanghai Slamtec Co., Ltd. + * Copyright (c) 2014 - 2019 Shanghai Slamtec Co., Ltd. * http://www.slamtec.com * */ diff --git a/sdk/src/arch/win32/arch_win32.h b/sdk/src/arch/win32/arch_win32.h index d17b0b41..10852f36 100644 --- a/sdk/src/arch/win32/arch_win32.h +++ b/sdk/src/arch/win32/arch_win32.h @@ -3,7 +3,7 @@ * * Copyright (c) 2009 - 2014 RoboPeak Team * http://www.robopeak.com - * Copyright (c) 2014 - 2018 Shanghai Slamtec Co., Ltd. + * Copyright (c) 2014 - 2019 Shanghai Slamtec Co., Ltd. * http://www.slamtec.com * */ diff --git a/sdk/src/arch/win32/net_serial.cpp b/sdk/src/arch/win32/net_serial.cpp index a0a68247..7a35a172 100644 --- a/sdk/src/arch/win32/net_serial.cpp +++ b/sdk/src/arch/win32/net_serial.cpp @@ -3,7 +3,7 @@ * * Copyright (c) 2009 - 2014 RoboPeak Team * http://www.robopeak.com - * Copyright (c) 2014 - 2018 Shanghai Slamtec Co., Ltd. + * Copyright (c) 2014 - 2019 Shanghai Slamtec Co., Ltd. * http://www.slamtec.com * */ diff --git a/sdk/src/arch/win32/net_serial.h b/sdk/src/arch/win32/net_serial.h index ffa4265d..a390f94c 100644 --- a/sdk/src/arch/win32/net_serial.h +++ b/sdk/src/arch/win32/net_serial.h @@ -3,7 +3,7 @@ * * Copyright (c) 2009 - 2014 RoboPeak Team * http://www.robopeak.com - * Copyright (c) 2014 - 2018 Shanghai Slamtec Co., Ltd. + * Copyright (c) 2014 - 2019 Shanghai Slamtec Co., Ltd. * http://www.slamtec.com * */ diff --git a/sdk/src/arch/win32/timer.cpp b/sdk/src/arch/win32/timer.cpp index f85a15b1..b95c0542 100644 --- a/sdk/src/arch/win32/timer.cpp +++ b/sdk/src/arch/win32/timer.cpp @@ -3,7 +3,7 @@ * * Copyright (c) 2009 - 2014 RoboPeak Team * http://www.robopeak.com - * Copyright (c) 2014 - 2018 Shanghai Slamtec Co., Ltd. + * Copyright (c) 2014 - 2019 Shanghai Slamtec Co., Ltd. * http://www.slamtec.com * */ diff --git a/sdk/src/arch/win32/timer.h b/sdk/src/arch/win32/timer.h index 11bba613..59b3982f 100644 --- a/sdk/src/arch/win32/timer.h +++ b/sdk/src/arch/win32/timer.h @@ -3,7 +3,7 @@ * * Copyright (c) 2009 - 2014 RoboPeak Team * http://www.robopeak.com - * Copyright (c) 2014 - 2018 Shanghai Slamtec Co., Ltd. + * Copyright (c) 2014 - 2019 Shanghai Slamtec Co., Ltd. * http://www.slamtec.com * */ diff --git a/sdk/src/arch/win32/winthread.hpp b/sdk/src/arch/win32/winthread.hpp index 673eeaf2..604f1d39 100644 --- a/sdk/src/arch/win32/winthread.hpp +++ b/sdk/src/arch/win32/winthread.hpp @@ -3,7 +3,7 @@ * * Copyright (c) 2009 - 2014 RoboPeak Team * http://www.robopeak.com - * Copyright (c) 2014 - 2018 Shanghai Slamtec Co., Ltd. + * Copyright (c) 2014 - 2019 Shanghai Slamtec Co., Ltd. * http://www.slamtec.com * */ diff --git a/sdk/src/hal/abs_rxtx.h b/sdk/src/hal/abs_rxtx.h index 4cb7832d..3c0e8373 100644 --- a/sdk/src/hal/abs_rxtx.h +++ b/sdk/src/hal/abs_rxtx.h @@ -3,7 +3,7 @@ * * Copyright (c) 2009 - 2014 RoboPeak Team * http://www.robopeak.com - * Copyright (c) 2014 - 2018 Shanghai Slamtec Co., Ltd. + * Copyright (c) 2014 - 2019 Shanghai Slamtec Co., Ltd. * http://www.slamtec.com * */ diff --git a/sdk/src/hal/event.h b/sdk/src/hal/event.h index 27362eeb..5e05234d 100644 --- a/sdk/src/hal/event.h +++ b/sdk/src/hal/event.h @@ -3,7 +3,7 @@ * * Copyright (c) 2009 - 2014 RoboPeak Team * http://www.robopeak.com - * Copyright (c) 2014 - 2018 Shanghai Slamtec Co., Ltd. + * Copyright (c) 2014 - 2019 Shanghai Slamtec Co., Ltd. * http://www.slamtec.com * */ diff --git a/sdk/src/hal/locker.h b/sdk/src/hal/locker.h index ce8d98ff..d7a13fbf 100644 --- a/sdk/src/hal/locker.h +++ b/sdk/src/hal/locker.h @@ -3,7 +3,7 @@ * * Copyright (c) 2009 - 2014 RoboPeak Team * http://www.robopeak.com - * Copyright (c) 2014 - 2018 Shanghai Slamtec Co., Ltd. + * Copyright (c) 2014 - 2019 Shanghai Slamtec Co., Ltd. * http://www.slamtec.com * */ diff --git a/sdk/src/hal/thread.cpp b/sdk/src/hal/thread.cpp index 28064af3..16ccb905 100644 --- a/sdk/src/hal/thread.cpp +++ b/sdk/src/hal/thread.cpp @@ -3,7 +3,7 @@ * * Copyright (c) 2009 - 2014 RoboPeak Team * http://www.robopeak.com - * Copyright (c) 2014 - 2018 Shanghai Slamtec Co., Ltd. + * Copyright (c) 2014 - 2019 Shanghai Slamtec Co., Ltd. * http://www.slamtec.com * */ diff --git a/sdk/src/hal/thread.h b/sdk/src/hal/thread.h index 167c5a4c..94074b8c 100644 --- a/sdk/src/hal/thread.h +++ b/sdk/src/hal/thread.h @@ -3,7 +3,7 @@ * * Copyright (c) 2009 - 2014 RoboPeak Team * http://www.robopeak.com - * Copyright (c) 2014 - 2018 Shanghai Slamtec Co., Ltd. + * Copyright (c) 2014 - 2019 Shanghai Slamtec Co., Ltd. * http://www.slamtec.com * */ diff --git a/sdk/src/hal/util.h b/sdk/src/hal/util.h index 72700aab..2882b1d6 100644 --- a/sdk/src/hal/util.h +++ b/sdk/src/hal/util.h @@ -3,7 +3,7 @@ * * Copyright (c) 2009 - 2014 RoboPeak Team * http://www.robopeak.com - * Copyright (c) 2014 - 2018 Shanghai Slamtec Co., Ltd. + * Copyright (c) 2014 - 2019 Shanghai Slamtec Co., Ltd. * http://www.slamtec.com * */ diff --git a/sdk/src/rplidar_driver.cpp b/sdk/src/rplidar_driver.cpp index c8a08b82..1cc6774f 100644 --- a/sdk/src/rplidar_driver.cpp +++ b/sdk/src/rplidar_driver.cpp @@ -3,7 +3,7 @@ * * Copyright (c) 2009 - 2014 RoboPeak Team * http://www.robopeak.com - * Copyright (c) 2014 - 2018 Shanghai Slamtec Co., Ltd. + * Copyright (c) 2014 - 2019 Shanghai Slamtec Co., Ltd. * http://www.slamtec.com * */ @@ -132,6 +132,16 @@ u_result RPlidarDriverImplCommon::reset(_u32 timeout) return RESULT_OK; } + +u_result RPlidarDriverImplCommon::clearNetSerialRxCache() +{ + if (!isConnected()) return RESULT_OPERATION_FAIL; + + _chanDev->flush(); + + return RESULT_OK; +} + u_result RPlidarDriverImplCommon::_waitResponseHeader(rplidar_ans_header_t * header, _u32 timeout) { int recvPos = 0; @@ -671,9 +681,17 @@ u_result RPlidarDriverImplCommon::_cacheCapsuledScanData() continue; } } + switch (_cached_express_flag) + { + case 0: + _capsuleToNormal(capsule_node, local_buf, count); + break; + case 1: + _dense_capsuleToNormal(capsule_node, local_buf, count); + break; + } + // - _capsuleToNormal(capsule_node, local_buf, count); - for (size_t pos = 0; pos < count; ++pos) { if (local_buf[pos].flag & RPLIDAR_RESP_MEASUREMENT_SYNCBIT) @@ -821,7 +839,55 @@ void RPlidarDriverImplCommon::_capsuleToNormal(const rplidar_response_capsul _is_previous_capsuledataRdy = true; } -//*******************************************HQ support******************************** +void RPlidarDriverImplCommon::_dense_capsuleToNormal(const rplidar_response_capsule_measurement_nodes_t & capsule, rplidar_response_measurement_node_hq_t *nodebuffer, size_t &nodeCount) +{ + const rplidar_response_dense_capsule_measurement_nodes_t *dense_capsule = reinterpret_cast(&capsule); + nodeCount = 0; + if (_is_previous_capsuledataRdy) { + int diffAngle_q8; + int currentStartAngle_q8 = ((dense_capsule->start_angle_sync_q6 & 0x7FFF) << 2); + int prevStartAngle_q8 = ((_cached_previous_dense_capsuledata.start_angle_sync_q6 & 0x7FFF) << 2); + + diffAngle_q8 = (currentStartAngle_q8)-(prevStartAngle_q8); + if (prevStartAngle_q8 > currentStartAngle_q8) { + diffAngle_q8 += (360 << 8); + } + + int angleInc_q16 = (diffAngle_q8 << 8)/40; + int currentAngle_raw_q16 = (prevStartAngle_q8 << 8); + for (size_t pos = 0; pos < _countof(_cached_previous_dense_capsuledata.cabins); ++pos) + { + int dist_q2; + int angle_q6; + int syncBit; + const int dist = static_cast(_cached_previous_dense_capsuledata.cabins[pos].distance); + dist_q2 = dist << 2; + angle_q6 = (currentAngle_raw_q16 >> 10); + syncBit = (((currentAngle_raw_q16 + angleInc_q16) % (360 << 16)) < angleInc_q16) ? 1 : 0; + currentAngle_raw_q16 += angleInc_q16; + + if (angle_q6 < 0) angle_q6 += (360 << 6); + if (angle_q6 >= (360 << 6)) angle_q6 -= (360 << 6); + + + + rplidar_response_measurement_node_hq_t node; + + node.angle_z_q14 = _u16((angle_q6 << 8) / 90); + node.flag = (syncBit | ((!syncBit) << 1)); + node.quality = dist_q2 ? (0x2f << RPLIDAR_RESP_MEASUREMENT_QUALITY_SHIFT) : 0; + node.dist_mm_q2 = dist_q2; + + nodebuffer[nodeCount++] = node; + + + } + } + + _cached_previous_dense_capsuledata = *dense_capsule; + _is_previous_capsuledataRdy = true; +} + u_result RPlidarDriverImplCommon::_cacheHqScanData() { rplidar_response_hq_capsule_measurement_nodes_t hq_node; @@ -1601,6 +1667,8 @@ u_result RPlidarDriverImplCommon::startScanExpress(bool force, _u16 scanMode, _u { return RESULT_INVALID_DATA; } + + } else { @@ -1618,9 +1686,13 @@ u_result RPlidarDriverImplCommon::startScanExpress(bool force, _u16 scanMode, _u //get scan answer type to specify how to wait data _u8 scanAnsType; if (ifSupportLidarConf) + { getScanModeAnsType(scanAnsType, scanMode); + } else + { scanAnsType = RPLIDAR_ANS_TYPE_MEASUREMENT_CAPSULED; + } { rp::hal::AutoLocker l(_lock); @@ -1630,7 +1702,7 @@ u_result RPlidarDriverImplCommon::startScanExpress(bool force, _u16 scanMode, _u if (scanMode != RPLIDAR_CONF_SCAN_COMMAND_STD && scanMode != RPLIDAR_CONF_SCAN_COMMAND_EXPRESS) scanReq.working_mode = _u8(scanMode); scanReq.working_flags = options; - + if (IS_FAIL(ans = _sendCommand(RPLIDAR_CMD_EXPRESS_SCAN, &scanReq, sizeof(scanReq)))) { return ans; } @@ -1647,22 +1719,32 @@ u_result RPlidarDriverImplCommon::startScanExpress(bool force, _u16 scanMode, _u } _u32 header_size = (response_header.size_q30_subtype & RPLIDAR_ANS_HEADER_SIZE_MASK); - + if (scanAnsType == RPLIDAR_ANS_TYPE_MEASUREMENT_CAPSULED) { if (header_size < sizeof(rplidar_response_capsule_measurement_nodes_t)) { return RESULT_INVALID_DATA; } + _cached_express_flag = 0; + _isScanning = true; + _cachethread = CLASS_THREAD(RPlidarDriverImplCommon, _cacheCapsuledScanData); + } + else if (scanAnsType == RPLIDAR_ANS_TYPE_MEASUREMENT_DENSE_CAPSULED) + { + if (header_size < sizeof(rplidar_response_capsule_measurement_nodes_t)) { + return RESULT_INVALID_DATA; + } + _cached_express_flag = 1; _isScanning = true; _cachethread = CLASS_THREAD(RPlidarDriverImplCommon, _cacheCapsuledScanData); - }else if(scanAnsType ==RPLIDAR_ANS_TYPE_MEASUREMENT_HQ ){ - if (header_size < sizeof(rplidar_response_hq_capsule_measurement_nodes_t)) { + } + else if (scanAnsType == RPLIDAR_ANS_TYPE_MEASUREMENT_HQ) { + if (header_size < sizeof(rplidar_response_hq_capsule_measurement_nodes_t)) { return RESULT_INVALID_DATA; } - _isScanning = true; - _cachethread = CLASS_THREAD(RPlidarDriverImplCommon, _cacheHqScanData); - - } + _isScanning = true; + _cachethread = CLASS_THREAD(RPlidarDriverImplCommon, _cacheHqScanData); + } else { if (header_size < sizeof(rplidar_response_ultra_capsule_measurement_nodes_t)) { diff --git a/sdk/src/rplidar_driver_TCP.h b/sdk/src/rplidar_driver_TCP.h index 8de2343d..0bd7ffdb 100644 --- a/sdk/src/rplidar_driver_TCP.h +++ b/sdk/src/rplidar_driver_TCP.h @@ -3,7 +3,7 @@ * * Copyright (c) 2009 - 2014 RoboPeak Team * http://www.robopeak.com - * Copyright (c) 2014 - 2018 Shanghai Slamtec Co., Ltd. + * Copyright (c) 2014 - 2019 Shanghai Slamtec Co., Ltd. * http://www.slamtec.com * */ diff --git a/sdk/src/rplidar_driver_impl.h b/sdk/src/rplidar_driver_impl.h index b25cf3fa..a8db47d7 100644 --- a/sdk/src/rplidar_driver_impl.h +++ b/sdk/src/rplidar_driver_impl.h @@ -3,7 +3,7 @@ * * Copyright (c) 2009 - 2014 RoboPeak Team * http://www.robopeak.com - * Copyright (c) 2014 - 2018 Shanghai Slamtec Co., Ltd. + * Copyright (c) 2014 - 2019 Shanghai Slamtec Co., Ltd. * http://www.slamtec.com * */ @@ -41,7 +41,7 @@ namespace rp { namespace standalone{ namespace rplidar { virtual bool isConnected(); virtual u_result reset(_u32 timeout = DEFAULT_TIMEOUT); - + virtual u_result clearNetSerialRxCache(); virtual u_result getAllSupportedScanModes(std::vector& outModes, _u32 timeoutInMs = DEFAULT_TIMEOUT); virtual u_result getTypicalScanMode(_u16& outMode, _u32 timeoutInMs = DEFAULT_TIMEOUT); virtual u_result checkSupportConfigCommands(bool& outSupport, _u32 timeoutInMs = DEFAULT_TIMEOUT); @@ -56,6 +56,7 @@ namespace rp { namespace standalone{ namespace rplidar { virtual u_result startScan(bool force, bool useTypicalScan, _u32 options = 0, RplidarScanMode* outUsedScanMode = NULL); virtual u_result startScanExpress(bool force, _u16 scanMode, _u32 options = 0, RplidarScanMode* outUsedScanMode = NULL, _u32 timeout = DEFAULT_TIMEOUT); + virtual u_result getHealth(rplidar_response_device_health_t & health, _u32 timeout = DEFAULT_TIMEOUT); virtual u_result getDeviceInfo(rplidar_response_device_info_t & info, _u32 timeout = DEFAULT_TIMEOUT); virtual u_result getSampleDuration_uS(rplidar_response_sample_rate_t & rateInfo, _u32 timeout = DEFAULT_TIMEOUT); @@ -87,6 +88,7 @@ namespace rp { namespace standalone{ namespace rplidar { virtual u_result _cacheCapsuledScanData(); virtual u_result _waitCapsuledNode(rplidar_response_capsule_measurement_nodes_t & node, _u32 timeout = DEFAULT_TIMEOUT); virtual void _capsuleToNormal(const rplidar_response_capsule_measurement_nodes_t & capsule, rplidar_response_measurement_node_hq_t *nodebuffer, size_t &nodeCount); + virtual void _dense_capsuleToNormal(const rplidar_response_capsule_measurement_nodes_t & capsule, rplidar_response_measurement_node_hq_t *nodebuffer, size_t &nodeCount); //FW1.23 virtual u_result _cacheUltraCapsuledScanData(); @@ -109,12 +111,15 @@ namespace rp { namespace standalone{ namespace rplidar { _u16 _cached_sampleduration_std; _u16 _cached_sampleduration_express; + _u8 _cached_express_flag; rplidar_response_capsule_measurement_nodes_t _cached_previous_capsuledata; + rplidar_response_dense_capsule_measurement_nodes_t _cached_previous_dense_capsuledata; rplidar_response_ultra_capsule_measurement_nodes_t _cached_previous_ultracapsuledata; rplidar_response_hq_capsule_measurement_nodes_t _cached_previous_Hqdata; bool _is_previous_capsuledataRdy; bool _is_previous_HqdataRdy; + rp::hal::Locker _lock; diff --git a/sdk/src/rplidar_driver_serial.h b/sdk/src/rplidar_driver_serial.h index 5ec017e4..abc1468a 100644 --- a/sdk/src/rplidar_driver_serial.h +++ b/sdk/src/rplidar_driver_serial.h @@ -3,7 +3,7 @@ * * Copyright (c) 2009 - 2014 RoboPeak Team * http://www.robopeak.com - * Copyright (c) 2014 - 2018 Shanghai Slamtec Co., Ltd. + * Copyright (c) 2014 - 2019 Shanghai Slamtec Co., Ltd. * http://www.slamtec.com * */ diff --git a/sdk/src/sdkcommon.h b/sdk/src/sdkcommon.h index afb53737..d025dfb1 100644 --- a/sdk/src/sdkcommon.h +++ b/sdk/src/sdkcommon.h @@ -3,7 +3,7 @@ * * Copyright (c) 2009 - 2014 RoboPeak Team * http://www.robopeak.com - * Copyright (c) 2014 - 2018 Shanghai Slamtec Co., Ltd. + * Copyright (c) 2014 - 2019 Shanghai Slamtec Co., Ltd. * http://www.slamtec.com * */