Public Types | Public Member Functions | List of all members
sl::ILidarDriver Class Referenceabstract

#include <sl_lidar_driver.h>

Inheritance diagram for sl::ILidarDriver:
Inheritance graph
[legend]

Public Types

enum  { DEFAULT_TIMEOUT = 2000 }
 

Public Member Functions

virtual sl_result ascendScanData (sl_lidar_response_measurement_node_hq_t *nodebuffer, size_t count)=0
 
virtual sl_result checkMotorCtrlSupport (MotorCtrlSupport &motorCtrlSupport, sl_u32 timeout=DEFAULT_TIMEOUT)=0
 
virtual sl_result connect (IChannel *channel)=0
 
virtual void disconnect ()=0
 
virtual sl_result getAllSupportedScanModes (std::vector< LidarScanMode > &outModes, sl_u32 timeoutInMs=DEFAULT_TIMEOUT)=0
 Get all scan modes that supported by lidar. More...
 
virtual sl_result getDeviceInfo (sl_lidar_response_device_info_t &info, sl_u32 timeout=DEFAULT_TIMEOUT)=0
 
virtual sl_result getDeviceMacAddr (sl_u8 *macAddrArray, sl_u32 timeoutInMs=DEFAULT_TIMEOUT)=0
 
virtual sl_result getFrequency (const LidarScanMode &scanMode, const sl_lidar_response_measurement_node_hq_t *nodes, size_t count, float &frequency)=0
 
virtual sl_result getHealth (sl_lidar_response_device_health_t &health, sl_u32 timeout=DEFAULT_TIMEOUT)=0
 
virtual sl_result getLidarIpConf (sl_lidar_ip_conf_t &conf, sl_u32 timeout=DEFAULT_TIMEOUT)=0
 
virtual LIDARMajorType getLIDARMajorType (const sl_lidar_response_device_info_t *devInfo=nullptr)=0
 
virtual LIDARTechnologyType getLIDARTechnologyType (const sl_lidar_response_device_info_t *devInfo=nullptr)=0
 
virtual sl_result getModelNameDescriptionString (std::string &out_description, bool fetchAliasName=true, const sl_lidar_response_device_info_t *devInfo=nullptr, sl_u32 timeout=DEFAULT_TIMEOUT)=0
 
virtual sl_result getMotorInfo (LidarMotorInfo &motorInfo, sl_u32 timeoutInMs=DEFAULT_TIMEOUT)=0
 
virtual sl_result getScanDataWithIntervalHq (sl_lidar_response_measurement_node_hq_t *nodebuffer, size_t &count)=0
 
virtual sl_result getTypicalScanMode (sl_u16 &outMode, sl_u32 timeoutInMs=DEFAULT_TIMEOUT)=0
 Get typical scan mode of lidar. More...
 
virtual sl_result grabScanDataHq (sl_lidar_response_measurement_node_hq_t *nodebuffer, size_t &count, sl_u32 timeout=DEFAULT_TIMEOUT)=0
 
virtual sl_result grabScanDataHqWithTimeStamp (sl_lidar_response_measurement_node_hq_t *nodebuffer, size_t &count, sl_u64 &timestamp_uS, sl_u32 timeout=DEFAULT_TIMEOUT)=0
 
virtual bool isConnected ()=0
 
virtual sl_result negotiateSerialBaudRate (sl_u32 requiredBaudRate, sl_u32 *baudRateDetected=NULL)=0
 
virtual sl_result reset (sl_u32 timeoutInMs=DEFAULT_TIMEOUT)=0
 
virtual sl_result setLidarIpConf (const sl_lidar_ip_conf_t &conf, sl_u32 timeout=DEFAULT_TIMEOUT)=0
 
virtual sl_result setMotorSpeed (sl_u16 speed=DEFAULT_MOTOR_SPEED)=0
 
virtual sl_result startScan (bool force, bool useTypicalScan, sl_u32 options=0, LidarScanMode *outUsedScanMode=nullptr)=0
 
virtual sl_result startScanExpress (bool force, sl_u16 scanMode, sl_u32 options=0, LidarScanMode *outUsedScanMode=nullptr, sl_u32 timeout=DEFAULT_TIMEOUT)=0
 
virtual sl_result stop (sl_u32 timeout=DEFAULT_TIMEOUT)=0
 
virtual ~ILidarDriver ()
 

Detailed Description

Definition at line 306 of file sl_lidar_driver.h.

Member Enumeration Documentation

◆ anonymous enum

anonymous enum
Enumerator
DEFAULT_TIMEOUT 

Definition at line 330 of file sl_lidar_driver.h.

Constructor & Destructor Documentation

◆ ~ILidarDriver()

virtual sl::ILidarDriver::~ILidarDriver ( )
inlinevirtual

Definition at line 309 of file sl_lidar_driver.h.

Member Function Documentation

◆ ascendScanData()

virtual sl_result sl::ILidarDriver::ascendScanData ( sl_lidar_response_measurement_node_hq_t nodebuffer,
size_t  count 
)
pure virtual

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.

Implemented in sl::SlamtecLidarDriver, and sl::SL_LidarDriver.

◆ checkMotorCtrlSupport()

virtual sl_result sl::ILidarDriver::checkMotorCtrlSupport ( MotorCtrlSupport motorCtrlSupport,
sl_u32  timeout = DEFAULT_TIMEOUT 
)
pure virtual

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.

Implemented in sl::SlamtecLidarDriver, and sl::SL_LidarDriver.

◆ connect()

virtual sl_result sl::ILidarDriver::connect ( IChannel channel)
pure virtual

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

Implemented in sl::SlamtecLidarDriver, and sl::SL_LidarDriver.

◆ disconnect()

virtual void sl::ILidarDriver::disconnect ( )
pure virtual

Disconnect from the LIDAR

Implemented in sl::SlamtecLidarDriver, and sl::SL_LidarDriver.

◆ getAllSupportedScanModes()

virtual sl_result sl::ILidarDriver::getAllSupportedScanModes ( std::vector< LidarScanMode > &  outModes,
sl_u32  timeoutInMs = DEFAULT_TIMEOUT 
)
pure virtual

Get all scan modes that supported by lidar.

Implemented in sl::SlamtecLidarDriver, and sl::SL_LidarDriver.

◆ getDeviceInfo()

virtual sl_result sl::ILidarDriver::getDeviceInfo ( sl_lidar_response_device_info_t &  info,
sl_u32  timeout = DEFAULT_TIMEOUT 
)
pure virtual

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

Implemented in sl::SlamtecLidarDriver, and sl::SL_LidarDriver.

◆ getDeviceMacAddr()

virtual sl_result sl::ILidarDriver::getDeviceMacAddr ( sl_u8 *  macAddrArray,
sl_u32  timeoutInMs = DEFAULT_TIMEOUT 
)
pure virtual

Get LPX series lidar's MAC address

Parameters
macAddrArrayThe device MAC information returned from the LPX series lidar Notice: the macAddrArray must point to a valid buffer with at least 6 bytes length Otherwise, buffer overwrite will occur

Implemented in sl::SlamtecLidarDriver, and sl::SL_LidarDriver.

◆ getFrequency()

virtual sl_result sl::ILidarDriver::getFrequency ( const LidarScanMode scanMode,
const sl_lidar_response_measurement_node_hq_t nodes,
size_t  count,
float &  frequency 
)
pure virtual

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

Implemented in sl::SlamtecLidarDriver, and sl::SL_LidarDriver.

◆ getHealth()

virtual sl_result sl::ILidarDriver::getHealth ( sl_lidar_response_device_health_t &  health,
sl_u32  timeout = DEFAULT_TIMEOUT 
)
pure virtual

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

Implemented in sl::SlamtecLidarDriver, and sl::SL_LidarDriver.

◆ getLidarIpConf()

virtual sl_result sl::ILidarDriver::getLidarIpConf ( sl_lidar_ip_conf_t &  conf,
sl_u32  timeout = DEFAULT_TIMEOUT 
)
pure virtual

Get LPX and S2E 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

Implemented in sl::SlamtecLidarDriver, and sl::SL_LidarDriver.

◆ getLIDARMajorType()

virtual LIDARMajorType sl::ILidarDriver::getLIDARMajorType ( const sl_lidar_response_device_info_t *  devInfo = nullptr)
pure virtual

Get the Major Type (Series Info) of the LIDAR

Parameters
devInfoThe device info used to deduct the result If NULL is specified, a driver cached version of the connected LIDAR will be used

Implemented in sl::SlamtecLidarDriver.

◆ getLIDARTechnologyType()

virtual LIDARTechnologyType sl::ILidarDriver::getLIDARTechnologyType ( const sl_lidar_response_device_info_t *  devInfo = nullptr)
pure virtual

Get the technology of the LIDAR's measurement system

Parameters
devInfoThe device info used to deduct the result If NULL is specified, a driver cached version of the connected LIDAR will be used

Implemented in sl::SlamtecLidarDriver.

◆ getModelNameDescriptionString()

virtual sl_result sl::ILidarDriver::getModelNameDescriptionString ( std::string &  out_description,
bool  fetchAliasName = true,
const sl_lidar_response_device_info_t *  devInfo = nullptr,
sl_u32  timeout = DEFAULT_TIMEOUT 
)
pure virtual

Get the Model Name of the LIDAR The result will be somthing like: "A1M8" or "S1M1" or "A3M1-R1"

Parameters
out_descriptionThe output string that contains the generated model name
fetchAliasNameIf set to true, a communication will be taken to ask if there is any Alias name availabe
devInfoThe device info used to deduct the result If NULL is specified, a driver cached version of the connected LIDAR will be used
timeoutThe timeout value used by potential data communication

Implemented in sl::SlamtecLidarDriver.

◆ getMotorInfo()

virtual sl_result sl::ILidarDriver::getMotorInfo ( LidarMotorInfo motorInfo,
sl_u32  timeoutInMs = DEFAULT_TIMEOUT 
)
pure virtual

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

Parameters
motorInfoThe motor information returned from the RPLIDAR

Implemented in sl::SlamtecLidarDriver.

◆ getScanDataWithIntervalHq()

virtual sl_result sl::ILidarDriver::getScanDataWithIntervalHq ( sl_lidar_response_measurement_node_hq_t nodebuffer,
size_t &  count 
)
pure virtual

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.

Implemented in sl::SlamtecLidarDriver, and sl::SL_LidarDriver.

◆ getTypicalScanMode()

virtual sl_result sl::ILidarDriver::getTypicalScanMode ( sl_u16 &  outMode,
sl_u32  timeoutInMs = DEFAULT_TIMEOUT 
)
pure virtual

Get typical scan mode of lidar.

Implemented in sl::SlamtecLidarDriver, and sl::SL_LidarDriver.

◆ grabScanDataHq()

virtual sl_result sl::ILidarDriver::grabScanDataHq ( sl_lidar_response_measurement_node_hq_t nodebuffer,
size_t &  count,
sl_u32  timeout = DEFAULT_TIMEOUT 
)
pure virtual

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.

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

Implemented in sl::SlamtecLidarDriver, and sl::SL_LidarDriver.

◆ grabScanDataHqWithTimeStamp()

virtual sl_result sl::ILidarDriver::grabScanDataHqWithTimeStamp ( sl_lidar_response_measurement_node_hq_t nodebuffer,
size_t &  count,
sl_u64 &  timestamp_uS,
sl_u32  timeout = DEFAULT_TIMEOUT 
)
pure virtual

Wait and grab a complete 0-360 degree scan data previously received with timestamp support.

The returned timestamp belongs to the first data point of the scan data (begining of the scan). Its value is represented based on the current machine's time domain with the unit of microseconds (uS).

If the currently connected LIDAR supports hardware timestamp mechanism, this timestamp will use the actual data emitted by the LIDAR device and remap it to the current machine's time domain.

For other models that do not support hardware timestamps, this data will be deducted through estimation, and there may be a slight deviation from the actual situation.

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.
timestamp_uSThe reference used to store the timestamp value.
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.

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

Implemented in sl::SlamtecLidarDriver.

◆ isConnected()

virtual bool sl::ILidarDriver::isConnected ( )
pure virtual

Check if the connection is established

Implemented in sl::SlamtecLidarDriver, and sl::SL_LidarDriver.

◆ negotiateSerialBaudRate()

virtual sl_result sl::ILidarDriver::negotiateSerialBaudRate ( sl_u32  requiredBaudRate,
sl_u32 *  baudRateDetected = NULL 
)
pure virtual

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

Implemented in sl::SL_LidarDriver, and sl::SlamtecLidarDriver.

◆ reset()

virtual sl_result sl::ILidarDriver::reset ( sl_u32  timeoutInMs = DEFAULT_TIMEOUT)
pure virtual

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)

Implemented in sl::SlamtecLidarDriver, and sl::SL_LidarDriver.

◆ setLidarIpConf()

virtual sl_result sl::ILidarDriver::setLidarIpConf ( const sl_lidar_ip_conf_t &  conf,
sl_u32  timeout = DEFAULT_TIMEOUT 
)
pure virtual

Set LPX and S2E 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

Implemented in sl::SlamtecLidarDriver, and sl::SL_LidarDriver.

◆ setMotorSpeed()

virtual sl_result sl::ILidarDriver::setMotorSpeed ( sl_u16  speed = DEFAULT_MOTOR_SPEED)
pure virtual

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.

Implemented in sl::SlamtecLidarDriver, and sl::SL_LidarDriver.

◆ startScan()

virtual sl_result sl::ILidarDriver::startScan ( bool  force,
bool  useTypicalScan,
sl_u32  options = 0,
LidarScanMode outUsedScanMode = nullptr 
)
pure virtual

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

Implemented in sl::SlamtecLidarDriver, and sl::SL_LidarDriver.

◆ startScanExpress()

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

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

Implemented in sl::SlamtecLidarDriver, and sl::SL_LidarDriver.

◆ stop()

virtual sl_result sl::ILidarDriver::stop ( sl_u32  timeout = DEFAULT_TIMEOUT)
pure virtual

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

Implemented in sl::SlamtecLidarDriver, and sl::SL_LidarDriver.


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


rplidar_ros
Author(s):
autogenerated on Fri Aug 2 2024 08:42:14