Namespaces | Classes | Enumerations | Functions | Variables
sl Namespace Reference

Namespaces

 crc32
 
 internal
 

Classes

class  IChannel
 
class  ILidarDriver
 
class  ISerialPortChannel
 
struct  LidarMotorInfo
 
struct  LidarScanMode
 
class  RawSampleNodeHolder
 
struct  Result
 
class  ScanDataHolder
 
class  SerialPortChannel
 
class  SL_LidarDriver
 
class  SlamtecLidarDriver
 
struct  SlamtecLidarTimingDesc
 
class  TcpChannel
 
class  UdpChannel
 

Enumerations

enum  ChannelType { CHANNEL_TYPE_SERIALPORT = 0x0, CHANNEL_TYPE_TCP = 0x1, CHANNEL_TYPE_UDP = 0x2 }
 
enum  LIDARInterfaceType {
  LIDAR_INTERFACE_UART = 0, LIDAR_INTERFACE_ETHERNET = 1, LIDAR_INTERFACE_USB = 2, LIDAR_INTERFACE_CANBUS = 5,
  LIDAR_INTERFACE_UNKNOWN = 0xFFFF
}
 
enum  LIDARMajorType {
  LIDAR_MAJOR_TYPE_UNKNOWN = 0, LIDAR_MAJOR_TYPE_A_SERIES = 1, LIDAR_MAJOR_TYPE_S_SERIES = 2, LIDAR_MAJOR_TYPE_T_SERIES = 3,
  LIDAR_MAJOR_TYPE_M_SERIES = 4, LIDAR_MAJOR_TYPE_C_SERIES = 6
}
 
enum  LIDARTechnologyType {
  LIDAR_TECHNOLOGY_UNKNOWN = 0, LIDAR_TECHNOLOGY_TRIANGULATION = 1, LIDAR_TECHNOLOGY_DTOF = 2, LIDAR_TECHNOLOGY_ETOF = 3,
  LIDAR_TECHNOLOGY_FMCW = 4
}
 
enum  MotorCtrlSupport { MotorCtrlSupportNone = 0, MotorCtrlSupportPwm = 1, MotorCtrlSupportRpm = 2 }
 

Functions

template<class TNode >
static bool angleLessThan (const TNode &a, const TNode &b)
 
template<class TNode >
static sl_result ascendScanData_ (TNode *nodebuffer, size_t count)
 
static void convert (const sl_lidar_response_measurement_node_hq_t &from, sl_lidar_response_measurement_node_t &to)
 
static void convert (const sl_lidar_response_measurement_node_t &from, sl_lidar_response_measurement_node_hq_t &to)
 
Result< ILidarDriver * > createLidarDriver ()
 
Result< IChannel * > createSerialPortChannel (const std::string &device, int baudrate)
 
Result< IChannel * > createTcpChannel (const std::string &ip, int port)
 
Result< IChannel * > createUdpChannel (const std::string &ip, int port)
 
static float getAngle (const sl_lidar_response_measurement_node_hq_t &node)
 
static float getAngle (const sl_lidar_response_measurement_node_t &node)
 
static sl_u32 getDistanceQ2 (const sl_lidar_response_measurement_node_hq_t &node)
 
static sl_u16 getDistanceQ2 (const sl_lidar_response_measurement_node_t &node)
 
static void printDeprecationWarn (const char *fn, const char *replacement)
 
static void setAngle (sl_lidar_response_measurement_node_hq_t &node, float v)
 
static void setAngle (sl_lidar_response_measurement_node_t &node, float v)
 

Variables

struct sl::LidarScanMode __attribute__
 

Enumeration Type Documentation

◆ ChannelType

Enumerator
CHANNEL_TYPE_SERIALPORT 
CHANNEL_TYPE_TCP 
CHANNEL_TYPE_UDP 

Definition at line 283 of file sl_lidar_driver.h.

◆ LIDARInterfaceType

Enumerator
LIDAR_INTERFACE_UART 
LIDAR_INTERFACE_ETHERNET 
LIDAR_INTERFACE_USB 
LIDAR_INTERFACE_CANBUS 
LIDAR_INTERFACE_UNKNOWN 

Definition at line 146 of file sl_lidar_driver.h.

◆ LIDARMajorType

Enumerator
LIDAR_MAJOR_TYPE_UNKNOWN 
LIDAR_MAJOR_TYPE_A_SERIES 
LIDAR_MAJOR_TYPE_S_SERIES 
LIDAR_MAJOR_TYPE_T_SERIES 
LIDAR_MAJOR_TYPE_M_SERIES 
LIDAR_MAJOR_TYPE_C_SERIES 

Definition at line 137 of file sl_lidar_driver.h.

◆ LIDARTechnologyType

Enumerator
LIDAR_TECHNOLOGY_UNKNOWN 
LIDAR_TECHNOLOGY_TRIANGULATION 
LIDAR_TECHNOLOGY_DTOF 
LIDAR_TECHNOLOGY_ETOF 
LIDAR_TECHNOLOGY_FMCW 

Definition at line 129 of file sl_lidar_driver.h.

◆ MotorCtrlSupport

Enumerator
MotorCtrlSupportNone 
MotorCtrlSupportPwm 
MotorCtrlSupportRpm 

Definition at line 276 of file sl_lidar_driver.h.

Function Documentation

◆ angleLessThan()

template<class TNode >
static bool sl::angleLessThan ( const TNode &  a,
const TNode &  b 
)
static

Definition at line 123 of file sl_lidar_driver.cpp.

◆ ascendScanData_()

template<class TNode >
static sl_result sl::ascendScanData_ ( TNode *  nodebuffer,
size_t  count 
)
static

Definition at line 129 of file sl_lidar_driver.cpp.

◆ convert() [1/2]

static void sl::convert ( const sl_lidar_response_measurement_node_hq_t from,
sl_lidar_response_measurement_node_t &  to 
)
static

Definition at line 83 of file sl_lidar_driver.cpp.

◆ convert() [2/2]

static void sl::convert ( const sl_lidar_response_measurement_node_t &  from,
sl_lidar_response_measurement_node_hq_t to 
)
static

Definition at line 75 of file sl_lidar_driver.cpp.

◆ createLidarDriver()

Result< ILidarDriver * > sl::createLidarDriver ( )

Create a LIDAR driver instance

Example Result<ISerialChannel*> channel = createSerialPortChannel("/dev/ttyUSB0", 115200); assert((bool)channel); assert(*channel);

auto lidar = createLidarDriver(); assert((bool)lidar); assert(*lidar);

auto res = (*lidar)->connect(*channel); assert(SL_IS_OK(res));

sl_lidar_response_device_info_t deviceInfo; res = (*lidar)->getDeviceInfo(deviceInfo); assert(SL_IS_OK(res));

printf("Model: %d, Firmware Version: %d.%d, Hardware Version: %d\n", deviceInfo.model, deviceInfo.firmware_version >> 8, deviceInfo.firmware_version & 0xffu, deviceInfo.hardware_version);

delete *lidar; delete *channel;

Definition at line 1698 of file sl_lidar_driver.cpp.

◆ createSerialPortChannel()

Result< IChannel * > sl::createSerialPortChannel ( const std::string &  device,
int  baudrate 
)

Create a serial channel

Parameters
deviceSerial port device e.g. on Windows, it may be com3 or \.\com10 on Unix-Like OS, it may be /dev/ttyS1, /dev/ttyUSB2, etc
baudrateBaudrate Please refer to the datasheet for the baudrate (maybe 115200 or 256000)

Definition at line 141 of file sl_serial_channel.cpp.

◆ createTcpChannel()

Result< IChannel * > sl::createTcpChannel ( const std::string &  ip,
int  port 
)

Create a TCP channel

Parameters
ipIP address of the device
portTCP port

Definition at line 120 of file sl_tcp_channel.cpp.

◆ createUdpChannel()

Result< IChannel * > sl::createUdpChannel ( const std::string &  ip,
int  port 
)

Create a UDP channel

Parameters
ipIP address of the device
portUDP port

Definition at line 125 of file sl_udp_channel.cpp.

◆ getAngle() [1/2]

static float sl::getAngle ( const sl_lidar_response_measurement_node_hq_t node)
inlinestatic

Definition at line 102 of file sl_lidar_driver.cpp.

◆ getAngle() [2/2]

static float sl::getAngle ( const sl_lidar_response_measurement_node_t &  node)
inlinestatic

Definition at line 91 of file sl_lidar_driver.cpp.

◆ getDistanceQ2() [1/2]

static sl_u32 sl::getDistanceQ2 ( const sl_lidar_response_measurement_node_hq_t node)
inlinestatic

Definition at line 117 of file sl_lidar_driver.cpp.

◆ getDistanceQ2() [2/2]

static sl_u16 sl::getDistanceQ2 ( const sl_lidar_response_measurement_node_t &  node)
inlinestatic

Definition at line 112 of file sl_lidar_driver.cpp.

◆ printDeprecationWarn()

static void sl::printDeprecationWarn ( const char *  fn,
const char *  replacement 
)
static

Definition at line 70 of file sl_lidar_driver.cpp.

◆ setAngle() [1/2]

static void sl::setAngle ( sl_lidar_response_measurement_node_hq_t node,
float  v 
)
inlinestatic

Definition at line 107 of file sl_lidar_driver.cpp.

◆ setAngle() [2/2]

static void sl::setAngle ( sl_lidar_response_measurement_node_t &  node,
float  v 
)
inlinestatic

Definition at line 96 of file sl_lidar_driver.cpp.

Variable Documentation

◆ __attribute__

struct sl::LidarScanMode sl::__attribute__


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