Skip to content

Commit

Permalink
improvements: upgrade RPLIDAR SDK to 1.7.0
Browse files Browse the repository at this point in the history
new feature: support scan points farther than 16.38m
  • Loading branch information
tony-slamtec committed Jul 2, 2018
1 parent 576d9c4 commit e3dac67
Show file tree
Hide file tree
Showing 38 changed files with 1,899 additions and 857 deletions.
2 changes: 1 addition & 1 deletion launch/rplidar_a3.launch
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,6 @@
<param name="frame_id" type="string" value="laser"/>
<param name="inverted" type="bool" value="false"/>
<param name="angle_compensate" type="bool" value="true"/>
<param name="scan_mode" type="string" value="Stability"/>
<param name="scan_mode" type="string" value="Sensitivity"/>
</node>
</launch>
4 changes: 2 additions & 2 deletions sdk/README.txt
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
Copyright (c) 2009 - 2014 RoboPeak Team
Copyright (c) 2014 - 2016 Shanghai Slamtec Co., Ltd.
Copyright (c) 2014 - 2018 Shanghai Slamtec Co., Ltd.
All rights reserved.

Redistribution and use in source and binary forms, with or without
Expand Down Expand Up @@ -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.6.0
RPLIDAR_SDK_VERSION: 1.7.0
Note: The SDK version may not up-to-date.
rplidar product: http://www.slamtec.com/en/Lidar
4 changes: 2 additions & 2 deletions sdk/include/rplidar.h
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
*
* Copyright (c) 2009 - 2014 RoboPeak Team
* http://www.robopeak.com
* Copyright (c) 2014 - 2016 Shanghai Slamtec Co., Ltd.
* Copyright (c) 2014 - 2018 Shanghai Slamtec Co., Ltd.
* http://www.slamtec.com
*
*/
Expand Down Expand Up @@ -41,4 +41,4 @@

#include "rplidar_driver.h"

#define RPLIDAR_SDK_VERSION "1.6.0"
#define RPLIDAR_SDK_VERSION "1.7.0"
12 changes: 11 additions & 1 deletion sdk/include/rplidar_cmd.h
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
*
* Copyright (c) 2009 - 2014 RoboPeak Team
* http://www.robopeak.com
* Copyright (c) 2014 - 2016 Shanghai Slamtec Co., Ltd.
* Copyright (c) 2014 - 2018 Shanghai Slamtec Co., Ltd.
* http://www.slamtec.com
*
*/
Expand Down Expand Up @@ -181,6 +181,14 @@ typedef struct _rplidar_response_ultra_capsule_measurement_nodes_t {
_u16 start_angle_sync_q6;
rplidar_response_ultra_cabin_nodes_t ultra_cabins[32];
} __attribute__((packed)) rplidar_response_ultra_capsule_measurement_nodes_t;

typedef struct rplidar_response_measurement_node_hq_t {
_u16 angle_z_q14;
_u32 dist_mm_q2;
_u8 quality;
_u8 flag;
} __attribute__((packed)) rplidar_response_measurement_node_hq_t;

# define RPLIDAR_CONF_SCAN_COMMAND_STD 0
# define RPLIDAR_CONF_SCAN_COMMAND_EXPRESS 1
# define RPLIDAR_CONF_SCAN_COMMAND_HQ 2
Expand All @@ -199,10 +207,12 @@ typedef struct _rplidar_response_ultra_capsule_measurement_nodes_t {
#define RPLIDAR_CONF_SCAN_MODE_NAME 0x0000007F
#define RPLIDAR_EXPRESS_SCAN_STABILITY_BITMAP 4
#define RPLIDAR_EXPRESS_SCAN_SENSITIVITY_BITMAP 5

typedef struct _rplidar_response_get_lidar_conf{
_u32 type;
_u8 payload[0];
}__attribute__((packed)) rplidar_response_get_lidar_conf_t;

typedef struct _rplidar_response_set_lidar_conf{
_u32 result;
}__attribute__((packed)) rplidar_response_set_lidar_conf_t;
Expand Down
124 changes: 89 additions & 35 deletions sdk/include/rplidar_driver.h
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
*
* Copyright (c) 2009 - 2014 RoboPeak Team
* http://www.robopeak.com
* Copyright (c) 2014 - 2016 Shanghai Slamtec Co., Ltd.
* Copyright (c) 2014 - 2018 Shanghai Slamtec Co., Ltd.
* http://www.slamtec.com
*
*/
Expand Down Expand Up @@ -39,12 +39,23 @@
#error "The RPlidar SDK requires a C++ compiler to be built"
#endif

#ifndef DEPRECATED
#ifdef __GNUC__
#define DEPRECATED(func) func __attribute__ ((deprecated))
#elif defined(_MSC_VER)
#define DEPRECATED(func) __declspec(deprecated) func
#else
#pragma message("WARNING: You need to implement DEPRECATED for this compiler")
#define DEPRECATED(func) func
#endif
#endif

namespace rp { namespace standalone{ namespace rplidar {

struct RplidarScanMode {
_u16 id;
float us_per_sample; // microseconds per sample
float max_distance; // max distance
float us_per_sample; // microseconds per sample
float max_distance; // max distance
_u8 ans_type; // the answer type of the scam mode, its value should be RPLIDAR_ANS_TYPE_MEASUREMENT*
char scan_mode[64]; // name of scan mode, max 63 characters
};
Expand Down Expand Up @@ -118,26 +129,30 @@ class RPlidarDriver {
/// Ask the RPLIDAR core system to reset it self
/// The host system can use the Reset operation to help RPLIDAR escape the self-protection mode.
///
// \param timeout The operation timeout value (in millisecond) for the serial port communication
/// \param timeout The operation timeout value (in millisecond) for the serial port communication
virtual u_result reset(_u32 timeout = DEFAULT_TIMEOUT) = 0;

// FW1.24
/*
* @brief Get all scan modes that supported by lidar
*/
/// Get all scan modes that supported by lidar
virtual u_result getAllSupportedScanModes(std::vector<RplidarScanMode>& outModes, _u32 timeoutInMs = DEFAULT_TIMEOUT) = 0;
virtual u_result getTypicalScanMode(_u16& outMode, _u32 timeoutInMs = DEFAULT_TIMEOUT) = 0;
virtual u_result checkSupportConfigCommands(bool& outSupport, _u32 timeoutInMs = DEFAULT_TIMEOUT) = 0;

virtual u_result getScanModeCount(_u16& modeCount, _u32 timeoutInMs = DEFAULT_TIMEOUT) = 0;
virtual u_result getLidarSampleDuration(float& sampleDurationRes, _u16 scanModeID, _u32 timeoutInMs = DEFAULT_TIMEOUT) = 0;
virtual u_result getMaxDistance(float &maxDistance, _u16 scanModeID, _u32 timeoutInMs = DEFAULT_TIMEOUT) = 0;
virtual u_result getScanModeAnsType(_u8 &ansType, _u16 scanModeID, _u32 timeoutInMs = DEFAULT_TIMEOUT) = 0;
virtual u_result getScanModeName(char* modeName, _u16 scanModeID, _u32 timeoutInMs = DEFAULT_TIMEOUT) = 0;

virtual u_result getLidarConf(_u32 type, std::vector<_u8> &outputBuf, const std::vector<_u8> &reserve = std::vector<_u8>(), _u32 timeout = DEFAULT_TIMEOUT) = 0;
/// Get typical scan mode of lidar
virtual u_result getTypicalScanMode(_u16& outMode, _u32 timeoutInMs = DEFAULT_TIMEOUT) = 0;

/// Start scan
///
/// \param force Force the core system to output scan data regardless whether the scanning motor is rotating or not.
/// \param useTypicalScan Use lidar's typical scan mode or use the compatibility mode (2k sps)
/// \param options Scan options (please use 0)
/// \param outUsedScanMode The scan mode selected by lidar
virtual u_result startScan(bool force, bool useTypicalScan, _u32 options = 0, RplidarScanMode* outUsedScanMode = NULL) = 0;

/// Start scan in specific mode
///
/// \param force Force the core system to output scan data regardless whether the scanning motor is rotating or not.
/// \param scanMode The scan mode id (use getAllSupportedScanModes to get supported modes)
/// \param options Scan options (please use 0)
/// \param outUsedScanMode The scan mode selected by lidar
virtual u_result startScanExpress(bool force, _u16 scanMode, _u32 options = 0, RplidarScanMode* outUsedScanMode = NULL, _u32 timeout = DEFAULT_TIMEOUT) = 0;

/// Retrieve the health status of the RPLIDAR
Expand All @@ -151,16 +166,15 @@ class RPlidarDriver {
/// Get the device information of the RPLIDAR include the serial number, firmware version, device model etc.
///
/// \param info The device information returned from the RPLIDAR
///
/// \param timeout The operation timeout value (in millisecond) for the serial port communication
virtual u_result getDeviceInfo(rplidar_response_device_info_t & info, _u32 timeout = DEFAULT_TIMEOUT) = 0;

/// Get the sample duration information of the RPLIDAR.
///
/// \param rateInfo The sample duration information returned from the RPLIDAR
/// DEPRECATED, please use RplidarScanMode::us_per_sample
///
/// \param rateInfo The sample duration information returned from the RPLIDAR
/// \param timeout The operation timeout value (in millisecond) for the serial port communication
virtual u_result getSampleDuration_uS(rplidar_response_sample_rate_t & rateInfo, _u32 timeout = DEFAULT_TIMEOUT) = 0;
DEPRECATED(virtual u_result getSampleDuration_uS(rplidar_response_sample_rate_t & rateInfo, _u32 timeout = DEFAULT_TIMEOUT)) = 0;

/// Set the RPLIDAR's motor pwm when using accessory board, currently valid for A2 only.
///
Expand All @@ -177,41 +191,43 @@ class RPlidarDriver {
/// Note: this API will disable grab.
///
/// \param support Return the result.
///
/// \param timeout The operation timeout value (in millisecond) for the serial port communication.
virtual u_result checkMotorCtrlSupport(bool & support, _u32 timeout = DEFAULT_TIMEOUT) = 0;

/// Calcuate RPLIDAR's current scanning frequency from the given scan data
/// Calculate RPLIDAR's current scanning frequency from the given scan data
/// DEPRECATED, please use getFrequency(RplidarScanMode, size_t)
///
/// Please refer to the application note doc for details
/// Remark: the calcuation will be incorrect if the specified scan data doesn't contains enough data
///
/// \param inExpressMode Indicate whether the RPLIDAR is in express mode
///
/// \param count The number of sample nodes inside the given buffer
///
/// \param frequency The scanning frequency (in HZ) calcuated by the interface.
///
/// \param is4kmode Return whether the RPLIDAR is working on 4k sample rate mode.
virtual u_result getFrequency(bool inExpressMode, size_t count, float & frequency, bool & is4kmode) = 0;
DEPRECATED(virtual u_result getFrequency(bool inExpressMode, size_t count, float & frequency, bool & is4kmode)) = 0;

/// Calculate RPLIDAR's current scanning frequency from the given scan data
/// Please refer to the application note doc for details
/// Remark: the calcuation will be incorrect if the specified scan data doesn't contains enough data
///
/// \param scanMode Lidar's current scan mode
/// \param count The number of sample nodes inside the given buffer
virtual u_result getFrequency(const RplidarScanMode& scanMode, size_t count, float & frequency) = 0;

/// Ask the RPLIDAR core system to enter the scan mode(Normal/Express, Express mode is 4k mode)
/// A background thread will be created by the RPLIDAR driver to fetch the scan data continuously.
/// User Application can use the grabScanData() interface to retrieved the scan data cached previous by this background thread.
///
/// \param force Force the core system to output scan data regardless whether the scanning motor is rotating or not.
///
/// \param autoExpressMode Force the core system to trying express mode first, if the system does not support express mode, it will use normal mode.
///
/// \param timeout The operation timeout value (in millisecond) for the serial port communication.

virtual u_result startScanNormal(bool force, _u32 timeout = DEFAULT_TIMEOUT) = 0;

/// Check whether the device support express mode.
///
/// \param support Return the result.
/// DEPRECATED, please use getAllSupportedScanModes
///
/// \param support Return the result.
/// \param timeout The operation timeout value (in millisecond) for the serial port communication.
virtual u_result checkExpressScanSupported(bool & support, _u32 timeout = DEFAULT_TIMEOUT) = 0;
DEPRECATED(virtual u_result checkExpressScanSupported(bool & support, _u32 timeout = DEFAULT_TIMEOUT)) = 0;

/// Ask the RPLIDAR core system to stop the current scan operation and enter idle state. The background thread will be terminated
///
Expand All @@ -220,6 +236,7 @@ class RPlidarDriver {


/// Wait and grab a complete 0-360 degree scan data previously received.
/// NOTE: This method only support distance less than 16.38 meters, for longer distance, please use grabScanDataHq
/// The grabbed scan data returned by this interface always has the following charactistics:
///
/// 1) The first node of the grabbed data array (nodebuffer[0]) must be the first sample of a scan, i.e. the start_bit == 1
Expand All @@ -238,6 +255,25 @@ class RPlidarDriver {
/// \The caller application can set the timeout value to Zero(0) to make this interface always returns immediately to achieve non-block operation.
virtual u_result grabScanData(rplidar_response_measurement_node_t * nodebuffer, size_t & count, _u32 timeout = DEFAULT_TIMEOUT) = 0;

/// Wait and grab a complete 0-360 degree scan data previously received.
/// The grabbed scan data returned by this interface always has the following charactistics:
///
/// 1) The first node of the grabbed data array (nodebuffer[0]) must be the first sample of a scan, i.e. the start_bit == 1
/// 2) All data nodes are belong to exactly ONE complete 360-degrees's scan
/// 3) Note, the angle data in one scan may not be ascending. You can use API ascendScanData to reorder the nodebuffer.
///
/// \param nodebuffer Buffer provided by the caller application to store the scan data
///
/// \param count The caller must initialize this parameter to set the max data count of the provided buffer (in unit of rplidar_response_measurement_node_t).
/// Once the interface returns, this parameter will store the actual received data count.
///
/// \param timeout Max duration allowed to wait for a complete scan data, nothing will be stored to the nodebuffer if a complete 360-degrees' scan data cannot to be ready timely.
///
/// The interface will return RESULT_OPERATION_TIMEOUT to indicate that no complete 360-degrees' scan can be retrieved withing the given timeout duration.
///
/// \The caller application can set the timeout value to Zero(0) to make this interface always returns immediately to achieve non-block operation.
virtual u_result grabScanDataHq(rplidar_response_measurement_node_hq_t * nodebuffer, size_t & count, _u32 timeout = DEFAULT_TIMEOUT) = 0;

/// Ascending the scan data according to the angle value in the scan.
///
/// \param nodebuffer Buffer provided by the caller application to do the reorder. Should be retrived from the grabScanData
Expand All @@ -247,15 +283,33 @@ class RPlidarDriver {
/// The interface will return RESULT_OPERATION_FAIL when all the scan data is invalid.
virtual u_result ascendScanData(rplidar_response_measurement_node_t * nodebuffer, size_t count) = 0;

/// Ascending the scan data according to the angle value in the scan.
///
/// \param nodebuffer Buffer provided by the caller application to do the reorder. Should be retrived from the grabScanData
///
/// \param count The caller must initialize this parameter to set the max data count of the provided buffer (in unit of rplidar_response_measurement_node_t).
/// Once the interface returns, this parameter will store the actual received data count.
/// The interface will return RESULT_OPERATION_FAIL when all the scan data is invalid.
virtual u_result ascendScanData(rplidar_response_measurement_node_hq_t * nodebuffer, size_t count) = 0;

/// Return received scan points even if it's not complete scan
///
/// \param nodebuffer Buffer provided by the caller application to store the scan data
///
/// \param count Once the interface returns, this parameter will store the actual received data count.
///
/// The interface will return RESULT_OPERATION_TIMEOUT to indicate that not even a single node can be retrieved since last call.

virtual u_result getScanDataWithInterval(rplidar_response_measurement_node_t * nodebuffer, size_t & count) = 0;


/// Return received scan points even if it's not complete scan
///
/// \param nodebuffer Buffer provided by the caller application to store the scan data
///
/// \param count Once the interface returns, this parameter will store the actual received data count.
///
/// The interface will return RESULT_OPERATION_TIMEOUT to indicate that not even a single node can be retrieved since last call.
virtual u_result getScanDataWithIntervalHq(rplidar_response_measurement_node_hq_t * nodebuffer, size_t & count) = 0;

virtual ~RPlidarDriver() {}
protected:
RPlidarDriver(){}
Expand Down
2 changes: 1 addition & 1 deletion sdk/include/rplidar_protocol.h
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
*
* Copyright (c) 2009 - 2014 RoboPeak Team
* http://www.robopeak.com
* Copyright (c) 2014 - 2016 Shanghai Slamtec Co., Ltd.
* Copyright (c) 2014 - 2018 Shanghai Slamtec Co., Ltd.
* http://www.slamtec.com
*
*/
Expand Down
2 changes: 1 addition & 1 deletion sdk/include/rptypes.h
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
*
* Copyright (c) 2009 - 2014 RoboPeak Team
* http://www.robopeak.com
* Copyright (c) 2014 - 2016 Shanghai Slamtec Co., Ltd.
* Copyright (c) 2014 - 2018 Shanghai Slamtec Co., Ltd.
* http://www.slamtec.com
*
*/
Expand Down
2 changes: 1 addition & 1 deletion sdk/src/arch/linux/arch_linux.h
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
*
* Copyright (c) 2009 - 2014 RoboPeak Team
* http://www.robopeak.com
* Copyright (c) 2014 - 2016 Shanghai Slamtec Co., Ltd.
* Copyright (c) 2014 - 2018 Shanghai Slamtec Co., Ltd.
* http://www.slamtec.com
*
*/
Expand Down
2 changes: 1 addition & 1 deletion sdk/src/arch/linux/net_serial.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
*
* Copyright (c) 2009 - 2014 RoboPeak Team
* http://www.robopeak.com
* Copyright (c) 2014 - 2016 Shanghai Slamtec Co., Ltd.
* Copyright (c) 2014 - 2018 Shanghai Slamtec Co., Ltd.
* http://www.slamtec.com
*
*/
Expand Down
2 changes: 1 addition & 1 deletion sdk/src/arch/linux/net_serial.h
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
*
* Copyright (c) 2009 - 2014 RoboPeak Team
* http://www.robopeak.com
* Copyright (c) 2014 - 2016 Shanghai Slamtec Co., Ltd.
* Copyright (c) 2014 - 2018 Shanghai Slamtec Co., Ltd.
* http://www.slamtec.com
*
*/
Expand Down
Loading

0 comments on commit e3dac67

Please sign in to comment.