Skip to content

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.

FunctionalityC++ SupportAPI Function
Configure LiDAR IPSetLivoxLidarIp
Set LiDAR Work ModeSetLivoxLidarWorkMode
Get Point Cloud DataSetLivoxLidarPointCloudCallBack
Get IMU DataSetLivoxLidarImuDataCallback

Introduction

API Documentation

SetLivoxLidarIp

cpp

/**
 * Set LiDAR IP info.
 * @param handle       Device handle.
 * @param ip_config    Pointer to LiDAR IP config.
 * @param cb           Callback for result.
 * @param client_data  User data.
 * @return             kStatusSuccess on success.
 */
livox_status SetLivoxLidarIp(uint32_t handle, LivoxLidarIpInfo* ip_config,
                             LivoxLidarAsyncControlCallback cb, void* client_data);

SetLivoxLidarWorkMode

cpp

/**
 * Set LiDAR work mode.
 * @param handle       Device handle.
 * @param work_mode    Desired LiDAR work mode.
 * @param cb           Callback for result.
 * @param client_data  User data.
 * @return             kStatusSuccess on success.
 */
livox_status SetLivoxLidarWorkMode(uint32_t handle, LivoxLidarWorkMode work_mode,
                                   LivoxLidarAsyncControlCallback cb, void* client_data);

SetLivoxLidarPointCloudCallBack

cpp

/**
 * Register callback to receive point cloud data.
 * @param cb           Point cloud callback function.
 * @param client_data  User data.
 */
void SetLivoxLidarPointCloudCallBack(LivoxLidarPointCloudCallBack cb, void* client_data);

SetLivoxLidarImuDataCallback

cpp

/**
 * Register callback to receive IMU data.
 * @param cb           IMU data callback function.
 * @param client_data  User data.
 */
void SetLivoxLidarImuDataCallback(LivoxLidarImuDataCallback cb, void* client_data);

Usage Example

cpp

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;
  }
}

WARNING

⚠ 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 NameMessage TypeRole
/livox/lidarsensor_msgs/msg/PointCloud2Subscriber
Message Structure
bash
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

  • header: Contains stamp (timestamp) and frame_id (coordinate frame).
  • height: Number of point rows (usually 1 for unorganized clouds).
  • width: Number of points per row or total number of points.
  • fields[]: Structure of each point (e.g., x, y, z, intensity).
  • is_bigendian: Endianness of the data (typically false for little-endian).
  • point_step: Number of bytes per point.
  • row_step: Number of bytes per row.
  • data[]: Raw binary array storing point cloud data.
  • is_dense: True if the cloud has no invalid (NaN) points.
Callback Example
cpp
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)

bash
ros2 topic echo /nav/livox/lidar_192_168_144_101
bash
ros2 topic echo /nav/livox/lidar_192_168_144_102

For GS Robot (RoboSense)

bash
ros2 topic echo /nav/rslidar_points

Precautions

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