Public Types | Public Member Functions | Protected Member Functions | Private Member Functions | Private Attributes | List of all members
sl::SlamtecLidarDriver Class Reference
Inheritance diagram for sl::SlamtecLidarDriver:
Inheritance graph
[legend]

Public Types

enum  { LEGACY_SAMPLE_DURATION = 476 }
 
enum  { NORMAL_CAPSULE = 0, DENSE_CAPSULE = 1 }
 
enum  { A2A3_LIDAR_MINUM_MAJOR_ID = 2, TOF_LIDAR_MINUM_MAJOR_ID = 6 }
 
- Public Types inherited from sl::ILidarDriver
enum  { DEFAULT_TIMEOUT = 2000 }
 

Public Member Functions

sl_result ascendScanData (sl_lidar_response_measurement_node_hq_t *nodebuffer, size_t count)
 
sl_result checkMotorCtrlSupport (MotorCtrlSupport &support, sl_u32 timeout=DEFAULT_TIMEOUT)
 
sl_result connect (IChannel *channel)
 
void disconnect ()
 
sl_result getAllSupportedScanModes (std::vector< LidarScanMode > &outModes, sl_u32 timeoutInMs=DEFAULT_TIMEOUT)
 Get all scan modes that supported by lidar. More...
 
sl_result getDeviceInfo (sl_lidar_response_device_info_t &info, sl_u32 timeout=DEFAULT_TIMEOUT)
 
sl_result getDeviceMacAddr (sl_u8 *macAddrArray, sl_u32 timeoutInMs)
 
sl_result getFrequency (const LidarScanMode &scanMode, const sl_lidar_response_measurement_node_hq_t *nodes, size_t count, float &frequency)
 
sl_result getHealth (sl_lidar_response_device_health_t &health, sl_u32 timeout=DEFAULT_TIMEOUT)
 
sl_result getMotorInfo (LidarMotorInfo &motorInfo, sl_u32 timeoutInMs)
 
sl_result getScanDataWithIntervalHq (sl_lidar_response_measurement_node_hq_t *nodebuffer, size_t &count)
 
sl_result getTypicalScanMode (sl_u16 &outMode, sl_u32 timeoutInMs=DEFAULT_TIMEOUT)
 Get typical scan mode of lidar. More...
 
sl_result grabScanDataHq (sl_lidar_response_measurement_node_hq_t *nodebuffer, size_t &count, sl_u32 timeout=DEFAULT_TIMEOUT)
 
bool isConnected ()
 
sl_result reset (sl_u32 timeoutInMs=DEFAULT_TIMEOUT)
 
sl_result setLidarIpConf (const sl_lidar_ip_conf_t &conf, sl_u32 timeout)
 
sl_result setMotorSpeed (sl_u16 speed=DEFAULT_MOTOR_SPEED)
 
 SlamtecLidarDriver ()
 
sl_result startScan (bool force, bool useTypicalScan, sl_u32 options=0, LidarScanMode *outUsedScanMode=nullptr)
 
sl_result startScanExpress (bool force, sl_u16 scanMode, sl_u32 options=0, LidarScanMode *outUsedScanMode=nullptr, sl_u32 timeout=DEFAULT_TIMEOUT)
 
sl_result startScanNormal (bool force, sl_u32 timeout=DEFAULT_TIMEOUT)
 
sl_result stop (sl_u32 timeout=DEFAULT_TIMEOUT)
 
- Public Member Functions inherited from sl::ILidarDriver
virtual ~ILidarDriver ()
 

Protected Member Functions

sl_result checkSupportConfigCommands (bool &outSupport, sl_u32 timeoutInMs=DEFAULT_TIMEOUT)
 
sl_result getDesiredSpeed (sl_lidar_response_desired_rot_speed_t &motorSpeed, sl_u32 timeoutInMs=DEFAULT_TIMEOUT)
 
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)
 
sl_result getLidarSampleDuration (float &sampleDurationRes, sl_u16 scanModeID, sl_u32 timeoutInMs=DEFAULT_TIMEOUT)
 
sl_result getMaxDistance (float &maxDistance, sl_u16 scanModeID, sl_u32 timeoutInMs=DEFAULT_TIMEOUT)
 
sl_result getScanModeAnsType (sl_u8 &ansType, sl_u16 scanModeID, sl_u32 timeoutInMs=DEFAULT_TIMEOUT)
 
sl_result getScanModeCount (sl_u16 &modeCount, sl_u32 timeoutInMs=DEFAULT_TIMEOUT)
 
sl_result getScanModeName (char *modeName, sl_u16 scanModeID, sl_u32 timeoutInMs=DEFAULT_TIMEOUT)
 
sl_result negotiateSerialBaudRate (sl_u32 requiredBaudRate, sl_u32 *baudRateDetected)
 
sl_result setLidarConf (sl_u32 type, const void *payload, size_t payloadSize, sl_u32 timeout)
 
sl_result startMotor ()
 

Private Member Functions

sl_result _cacheCapsuledScanData ()
 
sl_result _cacheHqScanData ()
 
sl_result _cacheScanData ()
 
sl_result _cacheUltraCapsuledScanData ()
 
void _capsuleToNormal (const sl_lidar_response_capsule_measurement_nodes_t &capsule, sl_lidar_response_measurement_node_hq_t *nodebuffer, size_t &nodeCount)
 
sl_result _clearRxDataCache ()
 
void _dense_capsuleToNormal (const sl_lidar_response_capsule_measurement_nodes_t &capsule, sl_lidar_response_measurement_node_hq_t *nodebuffer, size_t &nodeCount)
 
void _disableDataGrabbing ()
 
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_result _sendCommand (sl_u16 cmd, const void *payload=NULL, size_t payloadsize=0)
 
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 _waitCapsuledNode (sl_lidar_response_capsule_measurement_nodes_t &node, sl_u32 timeout=DEFAULT_TIMEOUT)
 
sl_result _waitHqNode (sl_lidar_response_hq_capsule_measurement_nodes_t &node, sl_u32 timeout=DEFAULT_TIMEOUT)
 
sl_result _waitNode (sl_lidar_response_measurement_node_t *node, sl_u32 timeout=DEFAULT_TIMEOUT)
 
template<typename T >
sl_result _waitResponse (T &payload, sl_u8 ansType, sl_u32 timeout=DEFAULT_TIMEOUT)
 
sl_result _waitResponseHeader (sl_lidar_ans_header_t *header, sl_u32 timeout=DEFAULT_TIMEOUT)
 
sl_result _waitScanData (sl_lidar_response_measurement_node_t *nodebuffer, size_t &count, sl_u32 timeout=DEFAULT_TIMEOUT)
 
sl_result _waitUltraCapsuledNode (sl_lidar_response_ultra_capsule_measurement_nodes_t &node, sl_u32 timeout=DEFAULT_TIMEOUT)
 

Private Attributes

sl_u8 _cached_capsule_flag
 
sl_lidar_response_capsule_measurement_nodes_t _cached_previous_capsuledata
 
sl_lidar_response_dense_capsule_measurement_nodes_t _cached_previous_dense_capsuledata
 
sl_lidar_response_hq_capsule_measurement_nodes_t _cached_previous_Hqdata
 
sl_lidar_response_ultra_capsule_measurement_nodes_t _cached_previous_ultracapsuledata
 
sl_u16 _cached_sampleduration_express
 
sl_u16 _cached_sampleduration_std
 
sl_lidar_response_measurement_node_hq_t _cached_scan_node_hq_buf [8192]
 
sl_lidar_response_measurement_node_hq_t _cached_scan_node_hq_buf_for_interval_retrieve [8192]
 
size_t _cached_scan_node_hq_count
 
size_t _cached_scan_node_hq_count_for_interval_retrieve
 
rp::hal::Thread _cachethread
 
IChannel_channel
 
rp::hal::Event _dataEvt
 
bool _is_previous_capsuledataRdy
 
bool _is_previous_HqdataRdy
 
bool _isConnected
 
bool _isScanning
 
MotorCtrlSupport _isSupportingMotorCtrl
 
rp::hal::Locker _lock
 
bool _scan_node_synced
 

Detailed Description

Definition at line 209 of file sl_lidar_driver.cpp.

Member Enumeration Documentation

◆ anonymous enum

anonymous enum
Enumerator
LEGACY_SAMPLE_DURATION 

Definition at line 212 of file sl_lidar_driver.cpp.

◆ anonymous enum

anonymous enum
Enumerator
NORMAL_CAPSULE 
DENSE_CAPSULE 

Definition at line 216 of file sl_lidar_driver.cpp.

◆ anonymous enum

anonymous enum
Enumerator
A2A3_LIDAR_MINUM_MAJOR_ID 
TOF_LIDAR_MINUM_MAJOR_ID 

Definition at line 221 of file sl_lidar_driver.cpp.

Constructor & Destructor Documentation

◆ SlamtecLidarDriver()

sl::SlamtecLidarDriver::SlamtecLidarDriver ( )
inline

Definition at line 227 of file sl_lidar_driver.cpp.

Member Function Documentation

◆ _cacheCapsuledScanData()

sl_result sl::SlamtecLidarDriver::_cacheCapsuledScanData ( )
inlineprivate

Definition at line 1612 of file sl_lidar_driver.cpp.

◆ _cacheHqScanData()

sl_result sl::SlamtecLidarDriver::_cacheHqScanData ( )
inlineprivate

Definition at line 1759 of file sl_lidar_driver.cpp.

◆ _cacheScanData()

sl_result sl::SlamtecLidarDriver::_cacheScanData ( )
inlineprivate

Definition at line 1258 of file sl_lidar_driver.cpp.

◆ _cacheUltraCapsuledScanData()

sl_result sl::SlamtecLidarDriver::_cacheUltraCapsuledScanData ( )
inlineprivate

Definition at line 1892 of file sl_lidar_driver.cpp.

◆ _capsuleToNormal()

void sl::SlamtecLidarDriver::_capsuleToNormal ( const sl_lidar_response_capsule_measurement_nodes_t &  capsule,
sl_lidar_response_measurement_node_hq_t nodebuffer,
size_t &  nodeCount 
)
inlineprivate

Definition at line 1499 of file sl_lidar_driver.cpp.

◆ _clearRxDataCache()

sl_result sl::SlamtecLidarDriver::_clearRxDataCache ( )
inlineprivate

Definition at line 1948 of file sl_lidar_driver.cpp.

◆ _dense_capsuleToNormal()

void sl::SlamtecLidarDriver::_dense_capsuleToNormal ( const sl_lidar_response_capsule_measurement_nodes_t &  capsule,
sl_lidar_response_measurement_node_hq_t nodebuffer,
size_t &  nodeCount 
)
inlineprivate

Definition at line 1556 of file sl_lidar_driver.cpp.

◆ _disableDataGrabbing()

void sl::SlamtecLidarDriver::_disableDataGrabbing ( )
inlineprivate

Definition at line 1168 of file sl_lidar_driver.cpp.

◆ _HqToNormal()

void sl::SlamtecLidarDriver::_HqToNormal ( const sl_lidar_response_hq_capsule_measurement_nodes_t &  node_hq,
sl_lidar_response_measurement_node_hq_t nodebuffer,
size_t &  nodeCount 
)
inlineprivate

Definition at line 1746 of file sl_lidar_driver.cpp.

◆ _sendCommand()

sl_result sl::SlamtecLidarDriver::_sendCommand ( sl_u16  cmd,
const void *  payload = NULL,
size_t  payloadsize = 0 
)
inlineprivate

Definition at line 1056 of file sl_lidar_driver.cpp.

◆ _ultraCapsuleToNormal()

void sl::SlamtecLidarDriver::_ultraCapsuleToNormal ( const sl_lidar_response_ultra_capsule_measurement_nodes_t &  capsule,
sl_lidar_response_measurement_node_hq_t nodebuffer,
size_t &  nodeCount 
)
inlineprivate

Definition at line 1311 of file sl_lidar_driver.cpp.

◆ _waitCapsuledNode()

sl_result sl::SlamtecLidarDriver::_waitCapsuledNode ( sl_lidar_response_capsule_measurement_nodes_t &  node,
sl_u32  timeout = DEFAULT_TIMEOUT 
)
inlineprivate

Definition at line 1424 of file sl_lidar_driver.cpp.

◆ _waitHqNode()

sl_result sl::SlamtecLidarDriver::_waitHqNode ( sl_lidar_response_hq_capsule_measurement_nodes_t &  node,
sl_u32  timeout = DEFAULT_TIMEOUT 
)
inlineprivate

Definition at line 1675 of file sl_lidar_driver.cpp.

◆ _waitNode()

sl_result sl::SlamtecLidarDriver::_waitNode ( sl_lidar_response_measurement_node_t *  node,
sl_u32  timeout = DEFAULT_TIMEOUT 
)
inlineprivate

Definition at line 1176 of file sl_lidar_driver.cpp.

◆ _waitResponse()

template<typename T >
sl_result sl::SlamtecLidarDriver::_waitResponse ( T &  payload,
sl_u8  ansType,
sl_u32  timeout = DEFAULT_TIMEOUT 
)
inlineprivate

Definition at line 1144 of file sl_lidar_driver.cpp.

◆ _waitResponseHeader()

sl_result sl::SlamtecLidarDriver::_waitResponseHeader ( sl_lidar_ans_header_t header,
sl_u32  timeout = DEFAULT_TIMEOUT 
)
inlineprivate

Definition at line 1097 of file sl_lidar_driver.cpp.

◆ _waitScanData()

sl_result sl::SlamtecLidarDriver::_waitScanData ( sl_lidar_response_measurement_node_t *  nodebuffer,
size_t &  count,
sl_u32  timeout = DEFAULT_TIMEOUT 
)
inlineprivate

Definition at line 1233 of file sl_lidar_driver.cpp.

◆ _waitUltraCapsuledNode()

sl_result sl::SlamtecLidarDriver::_waitUltraCapsuledNode ( sl_lidar_response_ultra_capsule_measurement_nodes_t &  node,
sl_u32  timeout = DEFAULT_TIMEOUT 
)
inlineprivate

Definition at line 1809 of file sl_lidar_driver.cpp.

◆ ascendScanData()

sl_result sl::SlamtecLidarDriver::ascendScanData ( sl_lidar_response_measurement_node_hq_t nodebuffer,
size_t  count 
)
inlinevirtual

Ascending the scan data according to the angle value in the scan.

Parameters
nodebufferBuffer provided by the caller application to do the reorder. Should be retrived from the grabScanData
countThe 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 SL_RESULT_OPERATION_FAIL when all the scan data is invalid.

Implements sl::ILidarDriver.

Definition at line 675 of file sl_lidar_driver.cpp.

◆ checkMotorCtrlSupport()

sl_result sl::SlamtecLidarDriver::checkMotorCtrlSupport ( MotorCtrlSupport motorCtrlSupport,
sl_u32  timeout = DEFAULT_TIMEOUT 
)
inlinevirtual

Check whether the device support motor control Note: this API will disable grab.

Parameters
motorCtrlSupportReturn the result.
timeoutThe operation timeout value (in millisecond) for the serial port communication.

Implements sl::ILidarDriver.

Definition at line 592 of file sl_lidar_driver.cpp.

◆ checkSupportConfigCommands()

sl_result sl::SlamtecLidarDriver::checkSupportConfigCommands ( bool &  outSupport,
sl_u32  timeoutInMs = DEFAULT_TIMEOUT 
)
inlineprotected

Definition at line 781 of file sl_lidar_driver.cpp.

◆ connect()

sl_result sl::SlamtecLidarDriver::connect ( IChannel channel)
inlinevirtual

Connect to LIDAR via channel

Parameters
channelThe communication channel Note: you should manage the lifecycle of the channel object, make sure it is alive during lidar driver's lifecycle

Implements sl::ILidarDriver.

Definition at line 238 of file sl_lidar_driver.cpp.

◆ disconnect()

void sl::SlamtecLidarDriver::disconnect ( )
inlinevirtual

Disconnect from the LIDAR

Implements sl::ILidarDriver.

Definition at line 262 of file sl_lidar_driver.cpp.

◆ getAllSupportedScanModes()

sl_result sl::SlamtecLidarDriver::getAllSupportedScanModes ( std::vector< LidarScanMode > &  outModes,
sl_u32  timeoutInMs = DEFAULT_TIMEOUT 
)
inlinevirtual

Get all scan modes that supported by lidar.

Implements sl::ILidarDriver.

Definition at line 286 of file sl_lidar_driver.cpp.

◆ getDesiredSpeed()

sl_result sl::SlamtecLidarDriver::getDesiredSpeed ( sl_lidar_response_desired_rot_speed_t &  motorSpeed,
sl_u32  timeoutInMs = DEFAULT_TIMEOUT 
)
inlineprotected

Definition at line 768 of file sl_lidar_driver.cpp.

◆ getDeviceInfo()

sl_result sl::SlamtecLidarDriver::getDeviceInfo ( sl_lidar_response_device_info_t &  info,
sl_u32  timeout = DEFAULT_TIMEOUT 
)
inlinevirtual

Get the device information of the RPLIDAR include the serial number, firmware version, device model etc.

Parameters
infoThe device information returned from the RPLIDAR
timeoutThe operation timeout value (in millisecond) for the serial port communication

Implements sl::ILidarDriver.

Definition at line 579 of file sl_lidar_driver.cpp.

◆ getDeviceMacAddr()

sl_result sl::SlamtecLidarDriver::getDeviceMacAddr ( sl_u8 *  macAddrArray,
sl_u32  timeoutInMs 
)
inlinevirtual

Get LPX series lidar's MAC address

Parameters
macAddrArrayThe device MAC information returned from the LPX series lidar

Implements sl::ILidarDriver.

Definition at line 661 of file sl_lidar_driver.cpp.

◆ getFrequency()

sl_result sl::SlamtecLidarDriver::getFrequency ( const LidarScanMode scanMode,
const sl_lidar_response_measurement_node_hq_t nodes,
size_t  count,
float &  frequency 
)
inlinevirtual

Calculate LIDAR'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

Parameters
scanModeLidar's current scan mode
nodesCurrent scan's measurements
countThe number of sample nodes inside the given buffer

Implements sl::ILidarDriver.

Definition at line 627 of file sl_lidar_driver.cpp.

◆ getHealth()

sl_result sl::SlamtecLidarDriver::getHealth ( sl_lidar_response_device_health_t &  health,
sl_u32  timeout = DEFAULT_TIMEOUT 
)
inlinevirtual

Retrieve the health status of the RPLIDAR The host system can use this operation to check whether RPLIDAR is in the self-protection mode.

Parameters
healthThe health status info returned from the RPLIDAR
timeoutThe operation timeout value (in millisecond) for the serial port communication

Implements sl::ILidarDriver.

Definition at line 640 of file sl_lidar_driver.cpp.

◆ getLidarConf()

sl_result sl::SlamtecLidarDriver::getLidarConf ( sl_u32  type,
std::vector< sl_u8 > &  outputBuf,
const std::vector< sl_u8 > &  reserve = std::vector<sl_u8>(),
sl_u32  timeout = DEFAULT_TIMEOUT 
)
inlineprotected

Definition at line 859 of file sl_lidar_driver.cpp.

◆ getLidarSampleDuration()

sl_result sl::SlamtecLidarDriver::getLidarSampleDuration ( float &  sampleDurationRes,
sl_u16  scanModeID,
sl_u32  timeoutInMs = DEFAULT_TIMEOUT 
)
inlineprotected

Definition at line 923 of file sl_lidar_driver.cpp.

◆ getMaxDistance()

sl_result sl::SlamtecLidarDriver::getMaxDistance ( float &  maxDistance,
sl_u16  scanModeID,
sl_u32  timeoutInMs = DEFAULT_TIMEOUT 
)
inlineprotected

Definition at line 942 of file sl_lidar_driver.cpp.

◆ getMotorInfo()

sl_result sl::SlamtecLidarDriver::getMotorInfo ( LidarMotorInfo motorInfo,
sl_u32  timeoutInMs 
)
inlinevirtual

Get the motor information of the RPLIDAR include the max speed, min speed, desired speed.

Parameters
motorInfoThe motor information returned from the RPLIDAR

Implements sl::ILidarDriver.

Definition at line 730 of file sl_lidar_driver.cpp.

◆ getScanDataWithIntervalHq()

sl_result sl::SlamtecLidarDriver::getScanDataWithIntervalHq ( sl_lidar_response_measurement_node_hq_t nodebuffer,
size_t &  count 
)
inlinevirtual

Return received scan points even if it's not complete scan

Parameters
nodebufferBuffer provided by the caller application to store the scan data
countOnce the interface returns, this parameter will store the actual received data count.

The interface will return SL_RESULT_OPERATION_TIMEOUT to indicate that not even a single node can be retrieved since last call.

Implements sl::ILidarDriver.

Definition at line 680 of file sl_lidar_driver.cpp.

◆ getScanModeAnsType()

sl_result sl::SlamtecLidarDriver::getScanModeAnsType ( sl_u8 &  ansType,
sl_u16  scanModeID,
sl_u32  timeoutInMs = DEFAULT_TIMEOUT 
)
inlineprotected

Definition at line 960 of file sl_lidar_driver.cpp.

◆ getScanModeCount()

sl_result sl::SlamtecLidarDriver::getScanModeCount ( sl_u16 &  modeCount,
sl_u32  timeoutInMs = DEFAULT_TIMEOUT 
)
inlineprotected

Definition at line 796 of file sl_lidar_driver.cpp.

◆ getScanModeName()

sl_result sl::SlamtecLidarDriver::getScanModeName ( char *  modeName,
sl_u16  scanModeID,
sl_u32  timeoutInMs = DEFAULT_TIMEOUT 
)
inlineprotected

Definition at line 979 of file sl_lidar_driver.cpp.

◆ getTypicalScanMode()

sl_result sl::SlamtecLidarDriver::getTypicalScanMode ( sl_u16 &  outMode,
sl_u32  timeoutInMs = DEFAULT_TIMEOUT 
)
inlinevirtual

Get typical scan mode of lidar.

Implements sl::ILidarDriver.

Definition at line 320 of file sl_lidar_driver.cpp.

◆ grabScanDataHq()

sl_result sl::SlamtecLidarDriver::grabScanDataHq ( sl_lidar_response_measurement_node_hq_t nodebuffer,
size_t &  count,
sl_u32  timeout = DEFAULT_TIMEOUT 
)
inlinevirtual

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.

Parameters
nodebufferBuffer provided by the caller application to store the scan data
countThe 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.
timeoutMax 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 SL_RESULT_OPERATION_TIMEOUT to indicate that no complete 360-degrees' scan can be retrieved withing the given timeout duration.

caller application can set the timeout value to Zero(0) to make this interface always returns immediately to achieve non-block operation.

Implements sl::ILidarDriver.

Definition at line 552 of file sl_lidar_driver.cpp.

◆ isConnected()

bool sl::SlamtecLidarDriver::isConnected ( )
inlinevirtual

Check if the connection is established

Implements sl::ILidarDriver.

Definition at line 268 of file sl_lidar_driver.cpp.

◆ negotiateSerialBaudRate()

sl_result sl::SlamtecLidarDriver::negotiateSerialBaudRate ( sl_u32  requiredBaudRate,
sl_u32 *  baudRateDetected 
)
inlineprotectedvirtual

Ask the LIDAR to use a new baudrate for serial communication The target LIDAR system must support such feature to work. This function does NOT check whether the target LIDAR works with the requiredBaudRate or not. In order to verifiy the result, use getDeviceInfo or other getXXXX functions instead.

Parameters
requiredBaudRateThe new baudrate required to be used. It MUST matches with the baudrate of the binded channel.
baudRateDetectedThe actual baudrate detected by the LIDAR system

Implements sl::ILidarDriver.

Definition at line 994 of file sl_lidar_driver.cpp.

◆ reset()

sl_result sl::SlamtecLidarDriver::reset ( sl_u32  timeoutInMs = DEFAULT_TIMEOUT)
inlinevirtual

Ask the LIDAR core system to reset it self The host system can use the Reset operation to help LIDAR escape the self-protection mode.

Parameters
timeoutThe operation timeout value (in millisecond)

Implements sl::ILidarDriver.

Definition at line 273 of file sl_lidar_driver.cpp.

◆ setLidarConf()

sl_result sl::SlamtecLidarDriver::setLidarConf ( sl_u32  type,
const void *  payload,
size_t  payloadSize,
sl_u32  timeout 
)
inlineprotected

Definition at line 809 of file sl_lidar_driver.cpp.

◆ setLidarIpConf()

sl_result sl::SlamtecLidarDriver::setLidarIpConf ( const sl_lidar_ip_conf_t &  conf,
sl_u32  timeout 
)
inlinevirtual

Set LPX series lidar's static IP address

Parameters
confNetwork parameter that LPX series lidar owned
timeoutThe operation timeout value (in millisecond) for the ethernet udp communication

Implements sl::ILidarDriver.

Definition at line 634 of file sl_lidar_driver.cpp.

◆ setMotorSpeed()

sl_result sl::SlamtecLidarDriver::setMotorSpeed ( sl_u16  speed = DEFAULT_MOTOR_SPEED)
inlinevirtual

Set lidar motor speed The host system can use this operation to set lidar motor speed.

Parameters
speedThe speed value set to lidar

Note: The function will stop scan if speed is DEFAULT_MOTOR_SPEED.

Implements sl::ILidarDriver.

Definition at line 697 of file sl_lidar_driver.cpp.

◆ startMotor()

sl_result sl::SlamtecLidarDriver::startMotor ( )
inlineprotected

Definition at line 763 of file sl_lidar_driver.cpp.

◆ startScan()

sl_result sl::SlamtecLidarDriver::startScan ( bool  force,
bool  useTypicalScan,
sl_u32  options = 0,
LidarScanMode outUsedScanMode = nullptr 
)
inlinevirtual

Start scan

Parameters
forceForce the core system to output scan data regardless whether the scanning motor is rotating or not.
useTypicalScanUse lidar's typical scan mode or use the compatibility mode (2k sps)
optionsScan options (please use 0)
outUsedScanModeThe scan mode selected by lidar

Implements sl::ILidarDriver.

Definition at line 347 of file sl_lidar_driver.cpp.

◆ startScanExpress()

sl_result sl::SlamtecLidarDriver::startScanExpress ( bool  force,
sl_u16  scanMode,
sl_u32  options = 0,
LidarScanMode outUsedScanMode = nullptr,
sl_u32  timeout = DEFAULT_TIMEOUT 
)
inlinevirtual

Start scan in specific mode

Parameters
forceForce the core system to output scan data regardless whether the scanning motor is rotating or not.
scanModeThe scan mode id (use getAllSupportedScanModes to get supported modes)
optionsScan options (please use 0)
outUsedScanModeThe scan mode selected by lidar

Implements sl::ILidarDriver.

Definition at line 416 of file sl_lidar_driver.cpp.

◆ startScanNormal()

sl_result sl::SlamtecLidarDriver::startScanNormal ( bool  force,
sl_u32  timeout = DEFAULT_TIMEOUT 
)
inline

Definition at line 381 of file sl_lidar_driver.cpp.

◆ stop()

sl_result sl::SlamtecLidarDriver::stop ( sl_u32  timeout = DEFAULT_TIMEOUT)
inlinevirtual

Ask the LIDAR core system to stop the current scan operation and enter idle state. The background thread will be terminated

Parameters
timeoutThe operation timeout value (in millisecond) for the serial port communication

Implements sl::ILidarDriver.

Definition at line 534 of file sl_lidar_driver.cpp.

Member Data Documentation

◆ _cached_capsule_flag

sl_u8 sl::SlamtecLidarDriver::_cached_capsule_flag
private

Definition at line 1970 of file sl_lidar_driver.cpp.

◆ _cached_previous_capsuledata

sl_lidar_response_capsule_measurement_nodes_t sl::SlamtecLidarDriver::_cached_previous_capsuledata
private

Definition at line 1975 of file sl_lidar_driver.cpp.

◆ _cached_previous_dense_capsuledata

sl_lidar_response_dense_capsule_measurement_nodes_t sl::SlamtecLidarDriver::_cached_previous_dense_capsuledata
private

Definition at line 1976 of file sl_lidar_driver.cpp.

◆ _cached_previous_Hqdata

sl_lidar_response_hq_capsule_measurement_nodes_t sl::SlamtecLidarDriver::_cached_previous_Hqdata
private

Definition at line 1978 of file sl_lidar_driver.cpp.

◆ _cached_previous_ultracapsuledata

sl_lidar_response_ultra_capsule_measurement_nodes_t sl::SlamtecLidarDriver::_cached_previous_ultracapsuledata
private

Definition at line 1977 of file sl_lidar_driver.cpp.

◆ _cached_sampleduration_express

sl_u16 sl::SlamtecLidarDriver::_cached_sampleduration_express
private

Definition at line 1965 of file sl_lidar_driver.cpp.

◆ _cached_sampleduration_std

sl_u16 sl::SlamtecLidarDriver::_cached_sampleduration_std
private

Definition at line 1964 of file sl_lidar_driver.cpp.

◆ _cached_scan_node_hq_buf

sl_lidar_response_measurement_node_hq_t sl::SlamtecLidarDriver::_cached_scan_node_hq_buf[8192]
private

Definition at line 1968 of file sl_lidar_driver.cpp.

◆ _cached_scan_node_hq_buf_for_interval_retrieve

sl_lidar_response_measurement_node_hq_t sl::SlamtecLidarDriver::_cached_scan_node_hq_buf_for_interval_retrieve[8192]
private

Definition at line 1972 of file sl_lidar_driver.cpp.

◆ _cached_scan_node_hq_count

size_t sl::SlamtecLidarDriver::_cached_scan_node_hq_count
private

Definition at line 1969 of file sl_lidar_driver.cpp.

◆ _cached_scan_node_hq_count_for_interval_retrieve

size_t sl::SlamtecLidarDriver::_cached_scan_node_hq_count_for_interval_retrieve
private

Definition at line 1973 of file sl_lidar_driver.cpp.

◆ _cachethread

rp::hal::Thread sl::SlamtecLidarDriver::_cachethread
private

Definition at line 1963 of file sl_lidar_driver.cpp.

◆ _channel

IChannel* sl::SlamtecLidarDriver::_channel
private

Definition at line 1957 of file sl_lidar_driver.cpp.

◆ _dataEvt

rp::hal::Event sl::SlamtecLidarDriver::_dataEvt
private

Definition at line 1962 of file sl_lidar_driver.cpp.

◆ _is_previous_capsuledataRdy

bool sl::SlamtecLidarDriver::_is_previous_capsuledataRdy
private

Definition at line 1979 of file sl_lidar_driver.cpp.

◆ _is_previous_HqdataRdy

bool sl::SlamtecLidarDriver::_is_previous_HqdataRdy
private

Definition at line 1980 of file sl_lidar_driver.cpp.

◆ _isConnected

bool sl::SlamtecLidarDriver::_isConnected
private

Definition at line 1958 of file sl_lidar_driver.cpp.

◆ _isScanning

bool sl::SlamtecLidarDriver::_isScanning
private

Definition at line 1959 of file sl_lidar_driver.cpp.

◆ _isSupportingMotorCtrl

MotorCtrlSupport sl::SlamtecLidarDriver::_isSupportingMotorCtrl
private

Definition at line 1960 of file sl_lidar_driver.cpp.

◆ _lock

rp::hal::Locker sl::SlamtecLidarDriver::_lock
private

Definition at line 1961 of file sl_lidar_driver.cpp.

◆ _scan_node_synced

bool sl::SlamtecLidarDriver::_scan_node_synced
private

Definition at line 1966 of file sl_lidar_driver.cpp.


The documentation for this class was generated from the following file:


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