Skip to content

Commit 0c6f441

Browse files
authored
Merge branch 'main' into ros-queue-length-as-param
2 parents addd294 + b8fe130 commit 0c6f441

35 files changed

+1064
-432
lines changed

.gitmodules

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,3 @@
11
[submodule "src/rs_driver"]
22
path = src/rs_driver
3-
url = https://github.com/RoboSense-LiDAR/rs_driver.git
4-
branch = main
3+
url = ../rs_driver.git

CHANGELOG.md

Lines changed: 17 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,22 @@
11
# CHANGELOG
22

3+
## v1.5.17 2025-02-14
4+
5+
### Added
6+
- Support RSAIRY.
7+
- Support parsing IMU data for RSAIRY and RSE1.
8+
- Support parsing IMU extrinsics parameters frome difop for RSAIRY.
9+
10+
### Changed
11+
- Add feature attribute to point type.
12+
- Updated config file.
13+
- Update help document.
14+
- Update block_time_offset as us for RSE1
15+
16+
### Fixed
17+
- Fix the issue of packets subscription failure under ros2.
18+
19+
320
## v1.5.16 2024-08-27
421
### Added
522
- Load config path frome ros2 param.

CMakeLists.txt

Lines changed: 16 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -3,14 +3,13 @@ cmake_policy(SET CMP0048 NEW)
33
project(rslidar_sdk)
44

55
#=======================================
6-
# Custom Point Type (XYZI, XYZIRT)
6+
# Custom Point Type (XYZI,XYZIRT, XYZIF, XYZIRTF)
77
#=======================================
88
set(POINT_TYPE XYZI)
99

1010
option(ENABLE_TRANSFORM "Enable transform functions" OFF)
1111
if(${ENABLE_TRANSFORM})
1212
add_definitions("-DENABLE_TRANSFORM")
13-
1413
find_package(Eigen3 REQUIRED)
1514
include_directories(${EIGEN3_INCLUDE_DIR})
1615
endif(${ENABLE_TRANSFORM})
@@ -46,6 +45,17 @@ if(${ENABLE_SOURCE_PACKET_LEGACY})
4645
add_definitions("-DENABLE_SOURCE_PACKET_LEGACY")
4746
endif(${ENABLE_SOURCE_PACKET_LEGACY})
4847

48+
option(ENABLE_IMU_DATA_PARSE "Enable imu data parse" OFF)
49+
if(${ENABLE_IMU_DATA_PARSE})
50+
51+
message(=============================================================)
52+
message("-- Enable imu data parse")
53+
message(=============================================================)
54+
55+
add_definitions("-DENABLE_IMU_DATA_PARSE")
56+
57+
endif(${ENABLE_IMU_DATA_PARSE})
58+
4959
#========================
5060
# Project details / setup
5161
#========================
@@ -68,6 +78,10 @@ if(${POINT_TYPE} STREQUAL "XYZI")
6878
add_definitions(-DPOINT_TYPE_XYZI)
6979
elseif(${POINT_TYPE} STREQUAL "XYZIRT")
7080
add_definitions(-DPOINT_TYPE_XYZIRT)
81+
elseif(${POINT_TYPE} STREQUAL "XYZIF")
82+
add_definitions(-DPOINT_TYPE_XYZIF)
83+
elseif(${POINT_TYPE} STREQUAL "XYZIRTF")
84+
add_definitions(-DPOINT_TYPE_XYZIRTF)
7185
endif()
7286

7387
message(=============================================================)

README.md

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -34,6 +34,7 @@ To integrate the Lidar driver into your own projects, please use the rs_driver.
3434
- RS-LiDAR-M3
3535
- RS-LiDAR-E1
3636
- RS-LiDAR-MX
37+
- RS-LiDAR-AIRY
3738

3839
### 1.2 Point Type Supported
3940

README_CN.md

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -33,6 +33,7 @@
3333
- RS-LiDAR-M3
3434
- RS-LiDAR-E1
3535
- RS-LiDAR-MX
36+
- RS-LiDAR-AIRY
3637

3738
### 1.1.2 支持的点类型
3839

config/config.yaml

Lines changed: 34 additions & 17 deletions
Original file line numberDiff line numberDiff line change
@@ -1,27 +1,44 @@
11
common:
2-
msg_source: 1 #0: not use Lidar
3-
#1: packet message comes from online Lidar
4-
#2: packet message comes from ROS or ROS2
5-
#3: packet message comes from Pcap file
6-
send_packet_ros: false #true: Send packets through ROS or ROS2(Used to record packet)
7-
send_point_cloud_ros: true #true: Send point cloud through ROS or ROS2
2+
msg_source: 1 # 0: not use Lidar
3+
# 1: packet message comes from online Lidar
4+
# 2: packet message comes from ROS or ROS2
5+
# 3: packet message comes from Pcap file
6+
send_packet_ros: false # true: Send packets through ROS or ROS2(Used to record packet)
7+
send_point_cloud_ros: true # true: Send point cloud through ROS or ROS2
88
lidar:
99
- driver:
10-
lidar_type: RSM1 #LiDAR type - RS16, RS32, RSBP, RSHELIOS, RSHELIOS_16P, RS128, RS80, RS48, RSP128, RSP80, RSP48,
11-
# RSM1, RSM1_JUMBO, RSM2, RSM3, RSE1, RSMX.
12-
msop_port: 6699 #Msop port of lidar
13-
difop_port: 7788 #Difop port of lidar
14-
start_angle: 0 #Start angle of point cloud
15-
end_angle: 360 #End angle of point cloud
16-
wait_for_difop: true
17-
min_distance: 0.2 #Minimum distance of point cloud
18-
max_distance: 200 #Maximum distance of point cloud
19-
use_lidar_clock: false #True--Use the lidar clock as the message timestamp
20-
#False-- Use the system clock as the timestamp
10+
lidar_type: RSM1 # LiDAR type - RS16, RS32, RSBP, RSAIRY, RSHELIOS, RSHELIOS_16P, RS128, RS80, RS48, RSP128, RSP80, RSP48,
11+
# RSM1, RSM1_JUMBO, RSM2, RSM3, RSE1, RSMX.
12+
13+
msop_port: 6699 # Msop port of lidar
14+
difop_port: 7788 # Difop port of lidar
15+
imu_port: 0 # IMU port of lidar(only for RSAIRY, RSE1), 0 means no imu.
16+
# If you want to use IMU, please first set ENABLE_IMU_DATA_PARSE to ON in CMakeLists.txt
17+
user_layer_bytes: 0 # Bytes of user layer. thers is no user layer if it is 0
18+
tail_layer_bytes: 0 # Bytes of tail layer. thers is no tail layer if it is 0
19+
20+
21+
min_distance: 0.2 # Minimum distance of point cloud
22+
max_distance: 200 # Maximum distance of point cloud
23+
use_lidar_clock: true # true--Use the lidar clock as the message timestamp
24+
# false-- Use the system clock as the timestamp
25+
dense_points: false # true: discard NAN points; false: reserve NAN points
26+
27+
ts_first_point: true # true: time-stamp point cloud with the first point; false: with the last point;
28+
# these parameters are used from mechanical lidar
29+
30+
start_angle: 0 # Start angle of point cloud
31+
end_angle: 360 # End angle of point cloud
32+
33+
# When msg_source is 3, the following parameters will be used
34+
pcap_repeat: true # true: The pcap bag will repeat play
35+
pcap_rate: 1.0 # Rate to read the pcap file
2136
pcap_path: /home/robosense/lidar.pcap #The path of pcap file
37+
2238
ros:
2339
ros_frame_id: rslidar #Frame id of packet message and point cloud message
2440
ros_recv_packet_topic: /rslidar_packets #Topic used to receive lidar packets from ROS
2541
ros_send_packet_topic: /rslidar_packets #Topic used to send lidar packets through ROS
42+
ros_send_imu_data_topic: /rslidar_imu_data #Topic used to send imu data through ROS
2643
ros_send_point_cloud_topic: /rslidar_points #Topic used to send point cloud through ROS
2744
ros_queue_length: 100 #Topic QoS history depth

doc/howto/05_how_to_change_point_type.md

Lines changed: 90 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -10,7 +10,7 @@ In ```CMakeLists.txt``` of the project, change the variable `POINT_TYPE`. Rememb
1010

1111
```cmake
1212
#=======================================
13-
# Custom Point Type (XYZI, XYZIRT)
13+
# Custom Point Type (XYZI,XYZIRT, XYZIF, XYZIRTF)
1414
#=======================================
1515
set(POINT_TYPE XYZI)
1616
```
@@ -34,11 +34,12 @@ struct PointXYZI
3434
rslidar_sdk transforms point cloud of `PointXYZI` to ROS message of `PointCloud2`,and publish it.
3535

3636
```c++
37-
sensor_msgs::PointCloud2 ros_msg;
38-
addPointField(ros_msg, "x", 1, sensor_msgs::PointField::FLOAT32, offset);
39-
addPointField(ros_msg, "y", 1, sensor_msgs::PointField::FLOAT32, offset);
40-
addPointField(ros_msg, "z", 1, sensor_msgs::PointField::FLOAT32, offset);
41-
addPointField(ros_msg, "intensity", 1, sensor_msgs::PointField::FLOAT32, offset);
37+
sensor_msgs::PointCloud2 ros_msg;
38+
int offset = 0;
39+
offset = addPointField(ros_msg, "x", 1, sensor_msgs::PointField::FLOAT32, offset);
40+
offset = addPointField(ros_msg, "y", 1, sensor_msgs::PointField::FLOAT32, offset);
41+
offset = addPointField(ros_msg, "z", 1, sensor_msgs::PointField::FLOAT32, offset);
42+
offset = addPointField(ros_msg, "intensity", 1, sensor_msgs::PointField::FLOAT32, offset);
4243

4344
//
4445
// copy points from point cloud of `PointXYZI` to `PointCloud2`
@@ -70,14 +71,15 @@ struct PointXYZIRT
7071
rslidar_sdk transforms point cloud of `PointXYZIRT` to ROS message of `PointCloud2`,and publish it.
7172

7273
```c++
73-
sensor_msgs::PointCloud2 ros_msg;
74-
addPointField(ros_msg, "x", 1, sensor_msgs::PointField::FLOAT32, offset);
75-
addPointField(ros_msg, "y", 1, sensor_msgs::PointField::FLOAT32, offset);
76-
addPointField(ros_msg, "z", 1, sensor_msgs::PointField::FLOAT32, offset);
77-
addPointField(ros_msg, "intensity", 1, sensor_msgs::PointField::FLOAT32, offset);
78-
#ifdef POINT_TYPE_XYZIRT
79-
sensor_msgs::PointCloud2Iterator<uint16_t> iter_ring_(ros_msg, "ring");
80-
sensor_msgs::PointCloud2Iterator<double> iter_timestamp_(ros_msg, "timestamp");
74+
sensor_msgs::PointCloud2 ros_msg;
75+
int offset = 0;
76+
offset = addPointField(ros_msg, "x", 1, sensor_msgs::PointField::FLOAT32, offset);
77+
offset = addPointField(ros_msg, "y", 1, sensor_msgs::PointField::FLOAT32, offset);
78+
offset = addPointField(ros_msg, "z", 1, sensor_msgs::PointField::FLOAT32, offset);
79+
offset = addPointField(ros_msg, "intensity", 1, sensor_msgs::PointField::FLOAT32, offset);
80+
#if defined(POINT_TYPE_XYZIRT) || defined(POINT_TYPE_XYZIRTF)
81+
offset = addPointField(ros_msg, "ring", 1, sensor_msgs::PointField::UINT16, offset);
82+
offset = addPointField(ros_msg, "timestamp", 1, sensor_msgs::PointField::FLOAT64, offset);
8183
#endif
8284

8385
//
@@ -86,4 +88,78 @@ rslidar_sdk transforms point cloud of `PointXYZIRT` to ROS message of `PointClou
8688
...
8789

8890
```
91+
## 5.4 XYZIF
92+
93+
If `POINT_TYPE` is `XYZIF`, rslidar_sdk uses the RoboSense defined type as below.
94+
95+
```c++
96+
struct PointXYZIF
97+
{
98+
float x;
99+
float y;
100+
float z;
101+
uint8_t intensity;
102+
uint16_t ring;
103+
double timestamp;
104+
};
105+
```
106+
107+
rslidar_sdk transforms point cloud of `PointXYZIF` to ROS message of `PointCloud2`,and publish it.
108+
109+
```c++
110+
sensor_msgs::PointCloud2 ros_msg;
111+
int offset = 0;
112+
offset = addPointField(ros_msg, "x", 1, sensor_msgs::PointField::FLOAT32, offset);
113+
offset = addPointField(ros_msg, "y", 1, sensor_msgs::PointField::FLOAT32, offset);
114+
offset = addPointField(ros_msg, "z", 1, sensor_msgs::PointField::FLOAT32, offset);
115+
offset = addPointField(ros_msg, "intensity", 1, sensor_msgs::PointField::FLOAT32, offset);
116+
#if defined(POINT_TYPE_XYZIF) || defined(POINT_TYPE_XYZIRTF)
117+
offset = addPointField(ros_msg, "feature", 1, sensor_msgs::PointField::UINT8, offset);
118+
#endif
119+
120+
//
121+
// copy points from point cloud of `PointXYZIF` to `PointCloud2`
122+
//
123+
...
124+
125+
```
126+
## 5.5 XYZIRTF
127+
128+
If `POINT_TYPE` is `XYZIRTF`, rslidar_sdk uses the RoboSense defined type as below.
129+
130+
```c++
131+
struct PointXYZIRTF
132+
{
133+
float x;
134+
float y;
135+
float z;
136+
uint8_t intensity;
137+
uint16_t ring;
138+
double timestamp;
139+
};
140+
```
141+
142+
rslidar_sdk transforms point cloud of `PointXYZIRTF` to ROS message of `PointCloud2`,and publish it.
143+
144+
```c++
145+
sensor_msgs::PointCloud2 ros_msg;
146+
int offset = 0;
147+
offset = addPointField(ros_msg, "x", 1, sensor_msgs::PointField::FLOAT32, offset);
148+
offset = addPointField(ros_msg, "y", 1, sensor_msgs::PointField::FLOAT32, offset);
149+
offset = addPointField(ros_msg, "z", 1, sensor_msgs::PointField::FLOAT32, offset);
150+
offset = addPointField(ros_msg, "intensity", 1, sensor_msgs::PointField::FLOAT32, offset);
151+
#if defined(POINT_TYPE_XYZIRT) || defined(POINT_TYPE_XYZIRTF)
152+
offset = addPointField(ros_msg, "ring", 1, sensor_msgs::PointField::UINT16, offset);
153+
offset = addPointField(ros_msg, "timestamp", 1, sensor_msgs::PointField::FLOAT64, offset);
154+
#endif
155+
#if defined(POINT_TYPE_XYZIF) || defined(POINT_TYPE_XYZIRTF)
156+
offset = addPointField(ros_msg, "feature", 1, sensor_msgs::PointField::UINT8, offset);
157+
#endif
158+
159+
//
160+
// copy points from point cloud of `PointXYZIRTF` to `PointCloud2`
161+
//
162+
...
163+
164+
```
89165

0 commit comments

Comments
 (0)