[ROS2][feat] Always use multilidar
Goal
This MR has the same purpose as MR !272 (merged)
- Trigger the SLAM process only when all LiDARs are received.
- For now, one LiDAR sensor was considered as master and the others were added when available.
- Most of the times, when various Lidars are used, it is to solve some missing degree of liberty in the independent LiDAR fields of view. So, if we allow the SLAM to process one only LiDAR frame (because it is all that it has at some point), it can fail and never recover.
- Now, the SLAM outputs a pose each time it has gathered all frames (it will be based on the sensor with the lowest frequency)
- A time parameter allows to drop frames if some have never been received
Changes
- Add parameters MultiLidarsNum to indicate the number of LiDAR sensors used
- Refact
ScanCallback
function to gather all frames from different LiDAR sensors - Remove
SecondaryScanCallback
function
Results
This is tested on a robosense multilidar data.
With the new changes in feat/ROS2, please see the following commands:
- Change parameters in
slam_config_indoor.yaml
lidars_nb: 2
input:
- "lidar_points_1"
- "lidar_points_2"
- In
slam_velodyne.py
, add tf of two lidars:
# left lidar link
tf_left_node = Node(package="tf2_ros", executable="static_transform_publisher", name="tf_left_to_base",
arguments=["--x", "-0.655", "--y", "0.455", "--z", "0.364",
"--roll", "0", "--pitch", "0", "--yaw", "2.356",
"--frame-id", "base_link", "--child-frame-id", "bpearl_back_left_frame"],
)
# right lidar link
tf_right_node = Node(package="tf2_ros", executable="static_transform_publisher", name="tf_right_to_base",
arguments=["--x", "0.655", "--y", "-0.455", "--z", "0.364",
"--roll", "0", "--pitch", "0", "--yaw", "-0.785",
"--frame-id", "base_link", "--child-frame-id", "bpearl_front_right_frame"],
)
comment this line:
# ld.add_action(velodyne_conversion_node)
add:
ld.add_action(tf_left_node)
ld.add_action(tf_right_node)
run in two terminals robosense_conversion_node:
ros2 run lidar_conversions robosense_conversion_node --ros-args --remap /lidar_points:=/lidar_points_1 --ros-args --remap /rslidar_points:=/lidars/bpearl_back_left
ros2 run lidar_conversions robosense_conversion_node --ros-args --remap /lidar_points:=/lidar_points_2 --ros-args --remap /rslidar_points:=/lidars/bpearl_front_right
launch slam
ros2 launch lidar_slam slam_velodyne.py outdoor:=false
play rosbag
ros2 bag play path/to/rosbag --clock -d 1 --topics /lidars/bpearl_back_left /lidars/bpearl_front_right
TODO
-
Clean -
Reenable removed features from previously master callback -
Make it NLidars compatible (only two for now) -
Update MR !272 (merged) when this MR is done
Edited by Tong Fu