LiDAR Service Interface
LiDAR Data Acquisition Interface
C++ Interface
Livox LiDAR (e.g., MID-360)
Overview
The LiDAR device supports access via the Livox SDK2 C++ API, which enables configuration of LiDAR IP and operating modes, retrieval of point cloud data, and access to built-in IMU data.
The SDK includes source code and precompiled dynamic/static libraries for integration.
| Functionality | C++ Support | API Function |
|---|---|---|
| Configure LiDAR IP | ✔ | SetLivoxLidarIp |
| Set LiDAR Work Mode | ✔ | SetLivoxLidarWorkMode |
| Get Point Cloud Data | ✔ | SetLivoxLidarPointCloudCallBack |
| Get IMU Data | ✔ | SetLivoxLidarImuDataCallback |
livox_status SetLivoxLidarIp(uint32_t handle, LivoxLidarIpInfo* ip_config, LivoxLidarAsyncControlCallback cb, void* client_data)
Description
Set LiDAR IP info.
Parameters
| Parameter Name | Type | Required/Default | Description |
|---|---|---|---|
handle | uint32_t | Required | Device handle. |
ip_config | LivoxLidarIpInfo* | Required | Pointer to LiDAR IP config. |
cb | LivoxLidarAsyncControlCallback | Required | Callback for result. |
client_data | void* | Optional | User data. |
Return Value
| Type | Description |
|---|---|
livox_status | kStatusSuccess on success. |
livox_status SetLivoxLidarWorkMode(uint32_t handle, LivoxLidarWorkMode work_mode, LivoxLidarAsyncControlCallback cb, void* client_data)
Description
Set LiDAR work mode.
Parameters
| Parameter Name | Type | Required/Default | Description |
|---|---|---|---|
handle | uint32_t | Required | Device handle. |
work_mode | LivoxLidarWorkMode | Required | Desired LiDAR work mode. |
cb | LivoxLidarAsyncControlCallback | Required | Callback for result. |
client_data | void* | Optional | User data. |
Return Value
| Type | Description |
|---|---|
livox_status | kStatusSuccess on success. |
void SetLivoxLidarPointCloudCallBack(LivoxLidarPointCloudCallBack cb, void* client_data)
Description
Register callback to receive point cloud data.
Parameters
| Parameter Name | Type | Required/Default | Description |
|---|---|---|---|
cb | LivoxLidarPointCloudCallBack | Required | Point cloud callback function. |
client_data | void* | Optional | User data. |
Return Value
| Type | Description |
|---|---|
void | No return value. |
void SetLivoxLidarImuDataCallback(LivoxLidarImuDataCallback cb, void* client_data)
Description
Register callback to receive IMU data.
Parameters
| Parameter Name | Type | Required/Default | Description |
|---|---|---|---|
cb | LivoxLidarImuDataCallback | Required | IMU data callback function. |
client_data | void* | Optional | User data. |
Return Value
| Type | Description |
|---|---|
void | No return value. |
Usage Example
SetLivoxLidarPointCloudCallBack(PointCloudCallback, nullptr);
void PointCloudCallback(uint32_t handle, const uint8_t dev_type,
LivoxLidarEthernetPacket* data, void* client_data) {
if (data == nullptr) return;
printf("point cloud handle: %u, data_num: %d, data_type: %d, length: %d, frame_counter: %d\n",
handle, data->dot_num, data->data_type, data->length, data->frame_cnt);
if (data->data_type == kLivoxLidarCartesianCoordinateHighData) {
auto* p_point_data = (LivoxLidarCartesianHighRawPoint*)data->data;
for (uint32_t i = 0; i < data->dot_num; i++) {
// Process p_point_data[i].x, y, z
}
} else if (data->data_type == kLivoxLidarCartesianCoordinateLowData) {
auto* p_point_data = (LivoxLidarCartesianLowRawPoint*)data->data;
} else if (data->data_type == kLivoxLidarSphericalCoordinateData) {
auto* p_point_data = (LivoxLidarSpherPoint*)data->data;
}
}⚠Note
Each callback does not represent a complete LiDAR frame. You must aggregate at least 100 callbacks to form a full scan.
ROS 2 Interface
Overview
The LiDAR ROS 2 interface provides access to point cloud data via the /livox/lidar topic, using the sensor_msgs/msg/PointCloud2 message type. This includes raw 3D point data captured by the solid-state LiDAR.
Topic Information
| Topic Name | Message Type | Role |
|---|---|---|
/livox/lidar | sensor_msgs/msg/PointCloud2 | Subscriber |
Message Structure
std_msgs/Header header # Message header containing timestamp and coordinate frame information
uint32 height # Height of the point cloud (usually 1 for unorganized clouds)
uint32 width # Width of the point cloud (number of points)
sensor_msgs/PointField[] fields # Definition of each point's fields (e.g., x, y, z, intensity, etc.)
bool is_bigendian # Byte order of the data (usually false for little-endian)
uint32 point_step # Number of bytes per point
uint32 row_step # Number of bytes per row
uint8[] data # Actual point cloud data in binary format
bool is_dense # Indicates whether the point cloud is dense (i.e., contains no invalid points)Field Descriptions
| Field Name | Type | Description |
|---|---|---|
header | std_msgs/Header | Contains stamp (timestamp) and frame_id (coordinate frame). |
height | uint32 | Height of the point cloud (usually 1 for unorganized clouds). |
width | uint32 | Width of the point cloud (number of points per row or total number of points). |
fields | sensor_msgs/PointField[] | Definition of each point's fields (e.g., x, y, z, intensity, etc.). |
is_bigendian | bool | Byte order of the data (usually false for little-endian). |
point_step | uint32 | Number of bytes per point. |
row_step | uint32 | Number of bytes per row. |
data | uint8[] | Actual point cloud data in binary format. |
is_dense | bool | Indicates whether the point cloud is dense (i.e., contains no invalid points). |
Callback Example
void lidarCallback(sensor_msgs::msg::PointCloud2::SharedPtr lidar_msg) {
pcl::PointCloud<pcl::PointXYZI>::Ptr pc_pcl(new pcl::PointCloud<pcl::PointXYZI>());
pcl::fromROSMsg<pcl::PointXYZI>(*lidar_msg, *pc_pcl);
for (const auto& pc : pc_pcl->points) {
/* <Customed processing procedure > */
}
}Testing Method
Subscribe to LIDAR Message Data:
For IS Robot (Livox)
ros2 topic echo /nav/livox/lidar_192_168_144_101ros2 topic echo /nav/livox/lidar_192_168_144_102For GS Robot (Robosense)
ros2 topic echo /nav/rslidar_pointsPrecautions
- Ensure the LiDAR driver node is correctly launched and actively publishing the corresponding topic before subscribing.
- Confirm the correct IP configuration and frame ID alignment if using multiple LiDAR units.