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

#include <rplidar_driver.h>

Inheritance diagram for rp::standalone::rplidar::RPlidarDriver:
Inheritance graph
[legend]

Public Types

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

Public Member Functions

virtual u_result ascendScanData (rplidar_response_measurement_node_hq_t *nodebuffer, size_t count)=0
 
virtual u_result checkIfTofLidar (bool &isTofLidar, _u32 timeout=DEFAULT_TIMEOUT)=0
 
virtual u_result checkMotorCtrlSupport (bool &support, _u32 timeout=DEFAULT_TIMEOUT)=0
 
virtual u_result clearNetSerialRxCache ()=0
 
virtual u_result connect (const char *, _u32, _u32 flag=0)=0
 
 DEPRECATED (virtual u_result getSampleDuration_uS(rplidar_response_sample_rate_t &rateInfo, _u32 timeout=DEFAULT_TIMEOUT))=0
 
 DEPRECATED (virtual u_result getFrequency(bool inExpressMode, size_t count, float &frequency, bool &is4kmode))=0
 
 DEPRECATED (virtual u_result checkExpressScanSupported(bool &support, _u32 timeout=DEFAULT_TIMEOUT))=0
 
 DEPRECATED (virtual u_result grabScanData(rplidar_response_measurement_node_t *nodebuffer, size_t &count, _u32 timeout=DEFAULT_TIMEOUT))=0
 
 DEPRECATED (virtual u_result ascendScanData(rplidar_response_measurement_node_t *nodebuffer, size_t count))=0
 
 DEPRECATED (virtual u_result getScanDataWithInterval(rplidar_response_measurement_node_t *nodebuffer, size_t &count))=0
 
virtual void disconnect ()=0
 Disconnect with the RPLIDAR and close the serial port. More...
 
virtual u_result getAllSupportedScanModes (std::vector< RplidarScanMode > &outModes, _u32 timeoutInMs=DEFAULT_TIMEOUT)=0
 Get all scan modes that supported by lidar. More...
 
virtual u_result getDeviceInfo (rplidar_response_device_info_t &info, _u32 timeout=DEFAULT_TIMEOUT)=0
 
virtual u_result getFrequency (const RplidarScanMode &scanMode, size_t count, float &frequency)=0
 
virtual u_result getHealth (rplidar_response_device_health_t &health, _u32 timeout=DEFAULT_TIMEOUT)=0
 
virtual u_result getScanDataWithIntervalHq (rplidar_response_measurement_node_hq_t *nodebuffer, size_t &count)=0
 
virtual u_result getTypicalScanMode (_u16 &outMode, _u32 timeoutInMs=DEFAULT_TIMEOUT)=0
 Get typical scan mode of lidar. More...
 
virtual u_result grabScanDataHq (rplidar_response_measurement_node_hq_t *nodebuffer, size_t &count, _u32 timeout=DEFAULT_TIMEOUT)=0
 
virtual bool isConnected ()=0
 Returns TRUE when the connection has been established. More...
 
virtual u_result reset (_u32 timeout=DEFAULT_TIMEOUT)=0
 
virtual u_result setLidarSpinSpeed (_u16 rpm, _u32 timeout=DEFAULT_TIMEOUT)=0
 
virtual u_result setMotorPWM (_u16 pwm)=0
 
virtual u_result startMotor ()=0
 Start RPLIDAR's motor when using accessory board. More...
 
virtual u_result startScan (bool force, bool useTypicalScan, _u32 options=0, RplidarScanMode *outUsedScanMode=NULL)=0
 
virtual u_result startScanExpress (bool force, _u16 scanMode, _u32 options=0, RplidarScanMode *outUsedScanMode=NULL, _u32 timeout=DEFAULT_TIMEOUT)=0
 
virtual u_result startScanNormal (bool force, _u32 timeout=DEFAULT_TIMEOUT)=0
 
virtual u_result stop (_u32 timeout=DEFAULT_TIMEOUT)=0
 
virtual u_result stopMotor ()=0
 Stop RPLIDAR's motor when using accessory board. More...
 
virtual ~RPlidarDriver ()
 

Static Public Member Functions

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

Public Attributes

ChannelDevice_chanDev
 

Protected Member Functions

 RPlidarDriver ()
 

Detailed Description

Definition at line 83 of file rplidar_driver.h.

Member Enumeration Documentation

anonymous enum
Enumerator
DEFAULT_TIMEOUT 

Definition at line 85 of file rplidar_driver.h.

anonymous enum
Enumerator
MAX_SCAN_NODES 

Definition at line 89 of file rplidar_driver.h.

anonymous enum
Enumerator
LEGACY_SAMPLE_DURATION 

Definition at line 93 of file rplidar_driver.h.

Constructor & Destructor Documentation

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

Definition at line 329 of file rplidar_driver.h.

rp::standalone::rplidar::RPlidarDriver::RPlidarDriver ( )
inlineprotected

Definition at line 331 of file rplidar_driver.h.

Member Function Documentation

virtual u_result rp::standalone::rplidar::RPlidarDriver::ascendScanData ( rplidar_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 RESULT_OPERATION_FAIL when all the scan data is invalid.

Implemented in rp::standalone::rplidar::RPlidarDriverImplCommon.

virtual u_result rp::standalone::rplidar::RPlidarDriver::checkIfTofLidar ( bool &  isTofLidar,
_u32  timeout = DEFAULT_TIMEOUT 
)
pure virtual

Check if the device is Tof lidar. Note: this API is effective if and only if getDeviceInfo has been called.

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

Implemented in rp::standalone::rplidar::RPlidarDriverImplCommon.

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

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.

Implemented in rp::standalone::rplidar::RPlidarDriverImplCommon.

virtual u_result rp::standalone::rplidar::RPlidarDriver::clearNetSerialRxCache ( )
pure virtual
virtual u_result rp::standalone::rplidar::RPlidarDriver::connect ( const char *  ,
_u32  ,
_u32  flag = 0 
)
pure virtual

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

Implemented in rp::standalone::rplidar::RPlidarDriverSerial, and rp::standalone::rplidar::RPlidarDriverTCP.

RPlidarDriver * rp::standalone::rplidar::RPlidarDriver::CreateDriver ( _u32  drivertype = DRIVER_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 85 of file rplidar_driver.cpp.

rp::standalone::rplidar::RPlidarDriver::DEPRECATED ( virtual u_result   getSampleDuration_uSrplidar_response_sample_rate_t &rateInfo, _u32 timeout=DEFAULT_TIMEOUT)
pure virtual

Get the sample duration information of the RPLIDAR. DEPRECATED, please use RplidarScanMode::us_per_sample

Parameters
rateInfoThe sample duration information returned from the RPLIDAR
timeoutThe operation timeout value (in millisecond) for the serial port communication
rp::standalone::rplidar::RPlidarDriver::DEPRECATED ( virtual u_result   getFrequencybool inExpressMode, size_t count, float &frequency, bool &is4kmode)
pure virtual

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

Parameters
inExpressModeIndicate whether the RPLIDAR is in express mode
countThe number of sample nodes inside the given buffer
frequencyThe scanning frequency (in HZ) calcuated by the interface.
is4kmodeReturn whether the RPLIDAR is working on 4k sample rate mode.
rp::standalone::rplidar::RPlidarDriver::DEPRECATED ( virtual u_result   checkExpressScanSupportedbool &support, _u32 timeout=DEFAULT_TIMEOUT)
pure virtual

Check whether the device support express mode. DEPRECATED, please use getAllSupportedScanModes

Parameters
supportReturn the result.
timeoutThe operation timeout value (in millisecond) for the serial port communication.
rp::standalone::rplidar::RPlidarDriver::DEPRECATED ( virtual u_result   grabScanDatarplidar_response_measurement_node_t *nodebuffer, size_t &count, _u32 timeout=DEFAULT_TIMEOUT)
pure virtual

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

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

rp::standalone::rplidar::RPlidarDriver::DEPRECATED ( virtual u_result   ascendScanDatarplidar_response_measurement_node_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 RESULT_OPERATION_FAIL when all the scan data is invalid.
rp::standalone::rplidar::RPlidarDriver::DEPRECATED ( virtual u_result   getScanDataWithIntervalrplidar_response_measurement_node_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 RESULT_OPERATION_TIMEOUT to indicate that not even a single node can be retrieved since last call.

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

Disconnect with the RPLIDAR and close the serial port.

Implemented in rp::standalone::rplidar::RPlidarDriverSerial, and rp::standalone::rplidar::RPlidarDriverTCP.

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 98 of file rplidar_driver.cpp.

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

Get all scan modes that supported by lidar.

Implemented in rp::standalone::rplidar::RPlidarDriverImplCommon.

virtual u_result rp::standalone::rplidar::RPlidarDriver::getDeviceInfo ( rplidar_response_device_info_t &  info,
_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 rp::standalone::rplidar::RPlidarDriverImplCommon.

virtual u_result rp::standalone::rplidar::RPlidarDriver::getFrequency ( const RplidarScanMode scanMode,
size_t  count,
float &  frequency 
)
pure virtual

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

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

Implemented in rp::standalone::rplidar::RPlidarDriverImplCommon.

virtual u_result rp::standalone::rplidar::RPlidarDriver::getHealth ( rplidar_response_device_health_t &  health,
_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 rp::standalone::rplidar::RPlidarDriverImplCommon.

virtual u_result rp::standalone::rplidar::RPlidarDriver::getScanDataWithIntervalHq ( rplidar_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. This buffer must be initialized by the caller.
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_TIMEOUT to indicate that not even a single node can be retrieved since last call. The interface will return RESULT_REMAINING_DATA to indicate that the given buffer is full, but that there remains data to be read.

Implemented in rp::standalone::rplidar::RPlidarDriverImplCommon.

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

Get typical scan mode of lidar.

Implemented in rp::standalone::rplidar::RPlidarDriverImplCommon.

virtual u_result rp::standalone::rplidar::RPlidarDriver::grabScanDataHq ( rplidar_response_measurement_node_hq_t nodebuffer,
size_t &  count,
_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 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.

Implemented in rp::standalone::rplidar::RPlidarDriverImplCommon.

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

Returns TRUE when the connection has been established.

Implemented in rp::standalone::rplidar::RPlidarDriverImplCommon.

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

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

Implemented in rp::standalone::rplidar::RPlidarDriverImplCommon.

virtual u_result rp::standalone::rplidar::RPlidarDriver::setLidarSpinSpeed ( _u16  rpm,
_u32  timeout = DEFAULT_TIMEOUT 
)
pure virtual

Set the RPLIDAR's motor rpm, currently valid for tof lidar only.

Parameters
rpmThe motor rpm value would like to set

Implemented in rp::standalone::rplidar::RPlidarDriverImplCommon.

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

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

Parameters
pwmThe motor pwm value would like to set

Implemented in rp::standalone::rplidar::RPlidarDriverImplCommon.

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

Start RPLIDAR's motor when using accessory board.

Implemented in rp::standalone::rplidar::RPlidarDriverImplCommon.

virtual u_result rp::standalone::rplidar::RPlidarDriver::startScan ( bool  force,
bool  useTypicalScan,
_u32  options = 0,
RplidarScanMode outUsedScanMode = NULL 
)
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 rp::standalone::rplidar::RPlidarDriverImplCommon.

virtual u_result rp::standalone::rplidar::RPlidarDriver::startScanExpress ( bool  force,
_u16  scanMode,
_u32  options = 0,
RplidarScanMode outUsedScanMode = NULL,
_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 rp::standalone::rplidar::RPlidarDriverImplCommon.

virtual u_result rp::standalone::rplidar::RPlidarDriver::startScanNormal ( bool  force,
_u32  timeout = DEFAULT_TIMEOUT 
)
pure virtual

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.

Parameters
forceForce the core system to output scan data regardless whether the scanning motor is rotating or not.
timeoutThe operation timeout value (in millisecond) for the serial port communication.

Implemented in rp::standalone::rplidar::RPlidarDriverImplCommon.

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

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

Implemented in rp::standalone::rplidar::RPlidarDriverImplCommon.

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

Stop RPLIDAR's motor when using accessory board.

Implemented in rp::standalone::rplidar::RPlidarDriverImplCommon.

Member Data Documentation

ChannelDevice* rp::standalone::rplidar::RPlidarDriver::_chanDev

Definition at line 334 of file rplidar_driver.h.


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


rplidar_ros
Author(s):
autogenerated on Wed Jan 1 2020 04:01:40