This is a tutorial to create SLAM map with LIO-SAM without dynamic objects using these:
- https://github.com/TixiaoShan/LIO-SAM/tree/ros2
- https://github.com/autowarefoundation/autoware.universe/tree/main/perception/lidar_centerpoint
- https://github.com/davutcanakbas/dynamic_object_removal
To run LIO-SAM without dynamic objects, there is need for ROS2 bag file and ROS2 bag file should contain these topics:
- For lidar based object detection:
sensor_msgs/msg/PointCloud2
- For 3D object removal:
sensor_msgs/msg/PointCloud2
,autoware_auto_perception_msgs::msg::DetectedObjects(this will come form lidar based object detection)
- For LIO-SAM:
sensor_msgs/msg/PointCloud2
,sensor_msgs/msg/Imu
,nav_msgs/msg/Odometry(optional)
1. Install lidar_centerpoint
ROS2 package from Autoware.
Clone Autoware main repo.
git clone https://github.com/autowarefoundation/autoware.git
cd autoware
By using the provided Ansible script from Autoware, you can install dependencies such as Cuda, TensorRT, and so on. Also this script downloads model files which will use from lidar_centerpoint
(You can check downloaded model files from ~/autoware_data/lidar_centerpoint/
).
./setup-dev-env.sh
Construct workspaces using vcstool and install ROS2 dependencies.
mkdir src
vcs import src < autoware.repos
source /opt/ros/humble/setup.bash
rosdep install -y --from-paths src --ignore-src --rosdistro $ROS_DISTRO
Build lidar_centerpoint
package and its dependencies.
colcon build --symlink-install --cmake-args -DCMAKE_BUILD_TYPE=RelWithDebInfo -DCMAKE_EXPORT_COMPILE_COMMANDS=1 --packages-select lidar_centerpoint autoware_auto_geometry_msgs autoware_auto_mapping_msgs autoware_lint_common tensorrt_common tier4_debug_msgs autoware_auto_perception_msgs autoware_auto_planning_msgs autoware_cmake autoware_auto_vehicle_msgs tier4_autoware_utils interpolation object_recognition_utils
2. Clone and build object removal repository. (When you work with LIO-SAM, you must change PCL point type. Check this issue)
mkdir dynamic_object_removal_ws/src
cd dynamic_object_removal_ws/src
git clone https://github.com/davutcanakbas/dynamic_object_removal
cd ..
colcon build
3. Clone and build LIO-SAM.
mkdir lio_sam_ws/src
cd lio_sam_ws/src
git clone git@github.com:TixiaoShan/LIO-SAM.git
cd lio_sam
git checkout ros2
cd ../..
colcon build
4. Configure the parameters of these packages.
Open autoware/src/universe/autoware.universe/perception/lidar_centerpoint/launch/lidar_centerpoint.launch.xml and change following parameters:
<arg name="input/pointcloud" default="/sensing/lidar/top/pointcloud_raw"/> # it should be your lidar topic
<param name="densification_world_frame_id" value="map"/> # it should be your lidar frame
Open dynamic_object_removal/launch/dynamic_object_removal.launch.xml and set following parameters.
<arg name="input/pointcloud" default="/kitti/point_cloud" description="input point cloud topic"/> # it should be your lidar topic
<arg name="input/objects" default="/objects" description="input objects topic"/> # it come from lidar_centerpoint
Open lio_sam/config/params.yaml and set following parameters.
pointCloudTopic: "/points" # required: your lidar topic
imuTopic: "/imu/data" # required: your imu topic
gpsTopic: "odometry/gpsz" # optional: your odometry topic
useImuHeadingInitialization: true # set true if you use odometry
useGpsElevation: true # set true if you use odometry
# select your lidar sensor from supported types. If your lidar not sport, select velodyne and change other lidar parameters with using your lidar features.
sensor: velodyne
N_SCAN: 32
Horizon_SCAN: 1800
# set your lidar-imu calibration
extrinsicRot: [1.0, 0.0, 0.0,
0.0, 1.0, 0.0,
0.0, 0.0, 1.0 ]
extrinsicRPY: [ 1.0, 0.0, 0.0,
0.0, 1.0, 0.0,
0.0, 0.0, 1.0 ]
5. Run
Open a new terminal for each block and run following commands.
cd dynamic_object_removal_ws
source install/setup.bash
ros2 launch dynamic_object_removal dynamic_object_removal.launch.xml
cd autoware
source install/setup.bash
ros2 launch lidar_centerpoint lidar_centerpoint.launch.xml
cd lio_sam_ws
source install/setup.bash
ros2 launch lio_sam run.launch.py
6. Save map
When mapping process is finished, run following command and save slam map to specified path.
cd lio_sam_ws
source install/setup.bash
ros2 service call /lio_sam/save_map lio_sam/srv/SaveMap "{resolution: 0.2, destination: /Downloads/service_LOAM}"
You can find example results from this drive link.
- It can see that this proposal can clear almost dynamic objects in point cloud data but in some point cloud data, especcialy if there is a objects in long distance, lidar_centerpoint cannot find them.
- In this proposal, users must build all Autoware packages to use lidar_centerpoint and it looks a little bit waste of time. It may be considere to use lidar_centerpoint separately from Autoware for this task.
Thank you for good information.
I confirmed that the dynamic object deletion part is working properly.
How were your mapping speeds when using lio-sam?
In my case, it was very slow as it seemed to update almost every 3 seconds.