Public Types | Public Member Functions | Static Public Member Functions | Protected Member Functions | Private Attributes | List of all members
rp::standalone::rplidar::RPlidarDriver Class Reference

#include <rplidar_driver.h>

Public Types

enum  { DEFAULT_TIMEOUT = 2000 }
 
enum  { MAX_SCAN_NODES = 8192 }
 
enum  { LEGACY_SAMPLE_DURATION = 476 }
 

Public Member Functions

u_result ascendScanData (rplidar_response_measurement_node_hq_t *nodebuffer, size_t count)
 
u_result checkMotorCtrlSupport (bool &support, _u32 timeout=DEFAULT_TIMEOUT)
 
u_result clearNetSerialRxCache ()
 
u_result connect (const char *path, _u32 portOrBaud, _u32 flag=0)
 
void disconnect ()
 Disconnect with the RPLIDAR and close the serial port. More...
 
u_result getAllSupportedScanModes (std::vector< RplidarScanMode > &outModes, _u32 timeoutInMs=DEFAULT_TIMEOUT)
 Get all scan modes that supported by lidar. More...
 
u_result getDeviceInfo (rplidar_response_device_info_t &info, _u32 timeout=DEFAULT_TIMEOUT)
 
u_result getDeviceMacAddr (_u8 *macAddrArray, _u32 timeoutInMs=DEFAULT_TIMEOUT)
 
u_result getHealth (rplidar_response_device_health_t &health, _u32 timeout=DEFAULT_TIMEOUT)
 
u_result getLidarIpConf (rplidar_ip_conf_t &conf, _u32 timeout=DEFAULT_TIMEOUT)
 
u_result getScanDataWithInterval (rplidar_response_measurement_node_t *nodebuffer, size_t &count)
 
u_result getScanDataWithIntervalHq (rplidar_response_measurement_node_hq_t *nodebuffer, size_t &count)
 
u_result getTypicalScanMode (_u16 &outMode, _u32 timeoutInMs=DEFAULT_TIMEOUT)
 Get typical scan mode of lidar. More...
 
u_result grabScanDataHq (rplidar_response_measurement_node_hq_t *nodebuffer, size_t &count, _u32 timeout=DEFAULT_TIMEOUT)
 
bool isConnected ()
 Returns TRUE when the connection has been established. More...
 
u_result reset (_u32 timeout=DEFAULT_TIMEOUT)
 
 RPlidarDriver (sl_u32 channelType)
 
u_result setLidarIpConf (const rplidar_ip_conf_t &conf, _u32 timeout=DEFAULT_TIMEOUT)
 
u_result setMotorPWM (_u16 pwm)
 
u_result startMotor ()
 Start RPLIDAR's motor when using accessory board. More...
 
u_result startScan (bool force, bool useTypicalScan, _u32 options=0, RplidarScanMode *outUsedScanMode=NULL)
 
u_result startScanExpress (bool force, _u16 scanMode, _u32 options=0, RplidarScanMode *outUsedScanMode=NULL, _u32 timeout=DEFAULT_TIMEOUT)
 
u_result stop (_u32 timeout=DEFAULT_TIMEOUT)
 
u_result stopMotor ()
 Stop RPLIDAR's motor when using accessory board. More...
 
virtual ~RPlidarDriver ()
 

Static Public Member Functions

static RPlidarDriverCreateDriver (_u32 drivertype=CHANNEL_TYPE_SERIALPORT)
 
static void DisposeDriver (RPlidarDriver *drv)
 

Protected Member Functions

 RPlidarDriver ()
 

Private Attributes

IChannel_channel
 
sl_u32 _channelType
 
ILidarDriver_lidarDrv
 

Detailed Description

Definition at line 53 of file rplidar_driver.h.

Member Enumeration Documentation

◆ anonymous enum

anonymous enum
Enumerator
DEFAULT_TIMEOUT 

Definition at line 55 of file rplidar_driver.h.

◆ anonymous enum

anonymous enum
Enumerator
MAX_SCAN_NODES 

Definition at line 59 of file rplidar_driver.h.

◆ anonymous enum

anonymous enum
Enumerator
LEGACY_SAMPLE_DURATION 

Definition at line 63 of file rplidar_driver.h.

Constructor & Destructor Documentation

◆ RPlidarDriver() [1/2]

rp::standalone::rplidar::RPlidarDriver::RPlidarDriver ( sl_u32  channelType)

Definition at line 49 of file rplidar_driver.cpp.

◆ ~RPlidarDriver()

rp::standalone::rplidar::RPlidarDriver::~RPlidarDriver ( )
virtual

Definition at line 54 of file rplidar_driver.cpp.

◆ RPlidarDriver() [2/2]

rp::standalone::rplidar::RPlidarDriver::RPlidarDriver ( )
protected

Definition at line 47 of file rplidar_driver.cpp.

Member Function Documentation

◆ ascendScanData()

u_result rp::standalone::rplidar::RPlidarDriver::ascendScanData ( rplidar_response_measurement_node_hq_t nodebuffer,
size_t  count 
)

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 RESULT_OPERATION_FAIL when all the scan data is invalid.

Definition at line 175 of file rplidar_driver.cpp.

◆ checkMotorCtrlSupport()

u_result rp::standalone::rplidar::RPlidarDriver::checkMotorCtrlSupport ( bool &  support,
_u32  timeout = DEFAULT_TIMEOUT 
)

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

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

Definition at line 141 of file rplidar_driver.cpp.

◆ clearNetSerialRxCache()

u_result rp::standalone::rplidar::RPlidarDriver::clearNetSerialRxCache ( )
inline

Definition at line 106 of file rplidar_driver.h.

◆ connect()

u_result rp::standalone::rplidar::RPlidarDriver::connect ( const char *  path,
_u32  portOrBaud,
_u32  flag = 0 
)

Open the specified serial port and connect to a target RPLIDAR device

Parameters
port_paththe device path of the serial port e.g. on Windows, it may be com3 or \.\com10 on Unix-Like OS, it may be /dev/ttyS1, /dev/ttyUSB2, etc
baudratethe baudrate used For most RPLIDAR models, the baudrate should be set to 115200
flagother flags Reserved for future use, always set to Zero

Definition at line 67 of file rplidar_driver.cpp.

◆ CreateDriver()

RPlidarDriver * rp::standalone::rplidar::RPlidarDriver::CreateDriver ( _u32  drivertype = CHANNEL_TYPE_SERIALPORT)
static

Create an RPLIDAR Driver Instance This interface should be invoked first before any other operations

Parameters
drivertypethe connection type used by the driver.

Definition at line 56 of file rplidar_driver.cpp.

◆ disconnect()

void rp::standalone::rplidar::RPlidarDriver::disconnect ( )

Disconnect with the RPLIDAR and close the serial port.

Definition at line 91 of file rplidar_driver.cpp.

◆ DisposeDriver()

void rp::standalone::rplidar::RPlidarDriver::DisposeDriver ( RPlidarDriver drv)
static

Dispose the RPLIDAR Driver Instance specified by the drv parameter Applications should invoke this interface when the driver instance is no longer used in order to free memory

Definition at line 62 of file rplidar_driver.cpp.

◆ getAllSupportedScanModes()

u_result rp::standalone::rplidar::RPlidarDriver::getAllSupportedScanModes ( std::vector< RplidarScanMode > &  outModes,
_u32  timeoutInMs = DEFAULT_TIMEOUT 
)

Get all scan modes that supported by lidar.

Definition at line 106 of file rplidar_driver.cpp.

◆ getDeviceInfo()

u_result rp::standalone::rplidar::RPlidarDriver::getDeviceInfo ( rplidar_response_device_info_t info,
_u32  timeout = DEFAULT_TIMEOUT 
)

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

Definition at line 131 of file rplidar_driver.cpp.

◆ getDeviceMacAddr()

u_result rp::standalone::rplidar::RPlidarDriver::getDeviceMacAddr ( _u8 macAddrArray,
_u32  timeoutInMs = DEFAULT_TIMEOUT 
)

Get LPX and S2E series lidar's MAC address

Parameters
macAddrArrayThe device MAC information returned from the LPX series lidar

Definition at line 160 of file rplidar_driver.cpp.

◆ getHealth()

u_result rp::standalone::rplidar::RPlidarDriver::getHealth ( rplidar_response_device_health_t health,
_u32  timeout = DEFAULT_TIMEOUT 
)

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

Definition at line 126 of file rplidar_driver.cpp.

◆ getLidarIpConf()

u_result rp::standalone::rplidar::RPlidarDriver::getLidarIpConf ( rplidar_ip_conf_t conf,
_u32  timeout = DEFAULT_TIMEOUT 
)

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

Definition at line 155 of file rplidar_driver.cpp.

◆ getScanDataWithInterval()

u_result rp::standalone::rplidar::RPlidarDriver::getScanDataWithInterval ( rplidar_response_measurement_node_t nodebuffer,
size_t &  count 
)

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 RESULT_OPERATION_TIMEOUT to indicate that not even a single node can be retrieved since last call.

Definition at line 180 of file rplidar_driver.cpp.

◆ getScanDataWithIntervalHq()

u_result rp::standalone::rplidar::RPlidarDriver::getScanDataWithIntervalHq ( rplidar_response_measurement_node_hq_t nodebuffer,
size_t &  count 
)

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 RESULT_OPERATION_TIMEOUT to indicate that not even a single node can be retrieved since last call.

Definition at line 185 of file rplidar_driver.cpp.

◆ getTypicalScanMode()

u_result rp::standalone::rplidar::RPlidarDriver::getTypicalScanMode ( _u16 outMode,
_u32  timeoutInMs = DEFAULT_TIMEOUT 
)

Get typical scan mode of lidar.

Definition at line 111 of file rplidar_driver.cpp.

◆ grabScanDataHq()

u_result rp::standalone::rplidar::RPlidarDriver::grabScanDataHq ( rplidar_response_measurement_node_hq_t nodebuffer,
size_t &  count,
_u32  timeout = DEFAULT_TIMEOUT 
)

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 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.

Definition at line 170 of file rplidar_driver.cpp.

◆ isConnected()

bool rp::standalone::rplidar::RPlidarDriver::isConnected ( )

Returns TRUE when the connection has been established.

Definition at line 96 of file rplidar_driver.cpp.

◆ reset()

u_result rp::standalone::rplidar::RPlidarDriver::reset ( _u32  timeout = DEFAULT_TIMEOUT)

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.

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

Definition at line 101 of file rplidar_driver.cpp.

◆ setLidarIpConf()

u_result rp::standalone::rplidar::RPlidarDriver::setLidarIpConf ( const rplidar_ip_conf_t conf,
_u32  timeout = DEFAULT_TIMEOUT 
)

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

Definition at line 150 of file rplidar_driver.cpp.

◆ setMotorPWM()

u_result rp::standalone::rplidar::RPlidarDriver::setMotorPWM ( _u16  pwm)

Set the RPLIDAR's motor pwm when using accessory board, currently valid for A2 only.

Parameters
pwmThe motor pwm value would like to set

Definition at line 136 of file rplidar_driver.cpp.

◆ startMotor()

u_result rp::standalone::rplidar::RPlidarDriver::startMotor ( )

Start RPLIDAR's motor when using accessory board.

Definition at line 190 of file rplidar_driver.cpp.

◆ startScan()

u_result rp::standalone::rplidar::RPlidarDriver::startScan ( bool  force,
bool  useTypicalScan,
_u32  options = 0,
RplidarScanMode outUsedScanMode = NULL 
)

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

Definition at line 116 of file rplidar_driver.cpp.

◆ startScanExpress()

u_result rp::standalone::rplidar::RPlidarDriver::startScanExpress ( bool  force,
_u16  scanMode,
_u32  options = 0,
RplidarScanMode outUsedScanMode = NULL,
_u32  timeout = DEFAULT_TIMEOUT 
)

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

Definition at line 121 of file rplidar_driver.cpp.

◆ stop()

u_result rp::standalone::rplidar::RPlidarDriver::stop ( _u32  timeout = DEFAULT_TIMEOUT)

Ask the RPLIDAR 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

Definition at line 165 of file rplidar_driver.cpp.

◆ stopMotor()

u_result rp::standalone::rplidar::RPlidarDriver::stopMotor ( )

Stop RPLIDAR's motor when using accessory board.

Definition at line 194 of file rplidar_driver.cpp.

Member Data Documentation

◆ _channel

IChannel* rp::standalone::rplidar::RPlidarDriver::_channel
private

Definition at line 239 of file rplidar_driver.h.

◆ _channelType

sl_u32 rp::standalone::rplidar::RPlidarDriver::_channelType
private

Definition at line 238 of file rplidar_driver.h.

◆ _lidarDrv

ILidarDriver* rp::standalone::rplidar::RPlidarDriver::_lidarDrv
private

Definition at line 240 of file rplidar_driver.h.


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


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