Posted by
Gi_T on
URL: http://official-rtab-map-forum.206.s1.nabble.com/Lidar-based-3d-SLAM-in-sparse-feature-environment-tp10174p10338.html
As always thanks for all the help Mathieu.
I spend the last few weeks checking out how to do sensor calibration and have seen some improvments for the depth overlay but the depth spread of the Realsense is still quite large.
I used
cam_lidar_calibrationfor the extrinsics between lidar and camera. Results seem decent when comparing to CAD.
For Lidar to IMU configuration I used
lidar_imu_calib to get the rotation and measured the translation as I could not get any plausible results for the translation through calibration.
Current open questions:- For using /mavros/vision_pose/pose it's recommended to have at least 30 Hz but the ICP odometry adjusts to the frequency of the Lidar (Velodyne VLP-16 in my case which by default only has 10 Hz). To get around this I currently publish the map->base_link with higher frequency. Do you think it makes sense to increase the Velodyne RPM to get up to 20 Hz but lower the angular resolution?
- Is there some way to increase Z accuracy as we currently experience quite a large offset (can be seen for the bag provided below)
- What other settings should I have a look at the improve localization and overall map quality?
Current config:
<?xml version="1.0"?>
<launch>
<arg name="rtabmap_viz" default="true" />
<arg name="use_imu" default="true" />
<arg name="imu_topic" default="/mavros/imu/data" />
<arg name="scan_20_hz" default="false" /> <!-- If we launch the velodyne with "rpm:=1200"
argument -->
<arg name="deskewing" default="true" />
<arg name="slerp" default="false" /> <!-- If true, a slerp between the first and last time will
be used to deskew each point, which is faster than using tf for every point but less accurate -->
<arg name="organize_cloud" default="$(arg deskewing)" /> <!-- Should be organized if deskewing is
enabled -->
<arg name="scan_topic" default="/velodyne_points" />
<arg name="frame_id" default="base_link" />
<arg name="queue_size" default="10" /> <!-- Set to 100 for kitti dataset to make sure all scans
are processed -->
<arg name="queue_size_odom" default="1" /> <!-- Set to 100 for kitti dataset to make sure all
scans are processed -->
<arg name="loop_ratio" default="0.2" />
<arg name="resolution" default="0.1" /> <!-- set 0.05-0.3 for indoor, set 0.3-0.5 for outdoor
(0.4 for kitti) -->
<arg name="iterations" default="10" />
<!-- Grid parameters -->
<arg name="ground_is_obstacle" default="true" />
<arg name="grid_max_range" default="5" />
<!-- For F2M Odometry -->
<arg name="ground_normals_up" default="false" /> <!-- set to true when velodyne is always
horizontal to ground (ground robot, car, kitti) -->
<arg name="local_map_size" default="15000" />
<arg name="key_frame_thr" default="0.4" />
<!-- For FLOAM Odometry -->
<arg name="floam" default="false" /> <!-- RTAB-Map should be built with FLOAM
http://official-rtab-map-forum.206.s1.nabble.com/icp-odometry-with-LOAM-crash-tp8261p8563.html -->
<arg name="floam_sensor" default="0" /> <!-- 0=16 rings (VLP16), 1=32 rings, 2=64 rings (kitti
dataset) -->
<!-- IMU orientation estimation and publish tf -->
<node if="$(arg use_imu)" pkg="nodelet" type="nodelet" name="imu_to_tf"
args="standalone rtabmap_util/imu_to_tf">
<remap from="imu/data" to="$(arg imu_topic)" />
<param name="fixed_frame_id" value="$(arg frame_id)_stabilized" />
<param name="base_frame_id" value="$(arg frame_id)" />
</node>
<!-- Lidar Deskewing -->
<node if="$(arg deskewing)" pkg="nodelet" type="nodelet" name="lidar_deskewing" args="standalone rtabmap_util/lidar_deskewing" output="screen">
<param name="wait_for_transform" value="0.05"/>
<param name="fixed_frame_id" value="$(arg frame_id)_stabilized"/>
<param name="slerp" value="$(arg slerp)"/>
<remap from="input_cloud" to="$(arg scan_topic)"/>
</node>
<arg if="$(arg deskewing)" name="scan_topic_deskewed" default="$(arg scan_topic)/deskewed"/>
<arg unless="$(arg deskewing)" name="scan_topic_deskewed" default="$(arg scan_topic)"/>
<!-- Localization-only mode -->
<arg name="localization" default="false"/>
<arg if="$(arg localization)" name="rtabmap_args" default=""/>
<arg unless="$(arg localization)" name="rtabmap_args" default="--delete_db_on_start"/>
<group ns="rtabmap">
<node pkg="rtabmap_odom" type="icp_odometry" name="icp_odometry" output="screen" args="$(arg rtabmap_args)">
<remap from="scan_cloud" to="$(arg scan_topic_deskewed)" />
<param name="frame_id" type="string" value="$(arg frame_id)" />
<param name="odom_frame_id" type="string" value="odom" />
<param name="queue_size" type="int" value="$(arg queue_size_odom)" />
<param name="wait_for_transform_duration" type="double" value="0.2" />
<param if="$(arg scan_20_hz)" name="expected_update_rate" type="double" value="25" />
<param unless="$(arg scan_20_hz)" name="expected_update_rate" type="double" value="15" />
<remap if="$(arg use_imu)" from="imu" to="$(arg imu_topic)" />
<param if="$(arg use_imu)" name="guess_frame_id" type="string"
value="$(arg frame_id)_stabilized" />
<param if="$(arg use_imu)" name="wait_imu_to_init" type="bool" value="true" />
<!-- ICP parameters -->
<param name="Icp/PointToPlane" type="string" value="true" />
<param name="Icp/Iterations" type="string" value="$(arg iterations)" />
<param if="$(arg floam)" name="Icp/VoxelSize" type="string" value="0" />
<param unless="$(arg floam)" name="Icp/VoxelSize" type="string"
value="$(arg resolution)" />
<param name="Icp/DownsamplingStep" type="string" value="1" /> <!-- cannot be increased
with ring-like lidar -->
<param name="Icp/Epsilon" type="string" value="0.001" />
<param if="$(arg floam)" name="Icp/PointToPlaneK" type="string" value="0" />
<param unless="$(arg floam)" name="Icp/PointToPlaneK" type="string" value="20" />
<param name="Icp/PointToPlaneRadius" type="string" value="0" />
<param name="Icp/MaxTranslation" type="string" value="2" />
<param name="Icp/MaxCorrespondenceDistance" type="string" value="$(eval resolution*10)" />
<param name="Icp/PM" type="string" value="true" />
<param name="Icp/PMOutlierRatio" type="string" value="0.7" />
<param name="Icp/CorrespondenceRatio" type="string" value="0.01" />
<param if="$(arg ground_normals_up)" name="Icp/PointToPlaneGroundNormalsUp"
type="string" value="0.8" />
<!-- localization mode -->
<param name="Mem/InitWMWithAllNodes" type="string" value="$(arg localization)"/>
<param if="$(arg localization)" name="Mem/IncrementalMemory" type="string" value="false"/>
<param unless="$(arg localization)" name="Mem/IncrementalMemory" type="string" value="true"/>
<!-- Odom parameters -->
<param name="Odom/ScanKeyFrameThr" type="string" value="$(arg key_frame_thr)" />
<param if="$(arg floam)" name="Odom/Strategy" type="string" value="11" />
<param unless="$(arg floam)" name="Odom/Strategy" type="string" value="0" />
<param name="OdomF2M/ScanSubtractRadius" type="string" value="$(arg resolution)" />
<param name="OdomF2M/ScanMaxSize" type="string" value="$(arg local_map_size)" />
<param name="OdomLOAM/Sensor" type="string" value="$(arg floam_sensor)" />
<param name="OdomLOAM/Resolution" type="string" value="$(arg resolution)" />
<param if="$(eval not deskewing and scan_20_hz)" name="OdomLOAM/ScanPeriod"
type="string" value="0.05" />
<param if="$(eval not deskewing and not scan_20_hz)" name="OdomLOAM/ScanPeriod"
type="string" value="0.1" />
<param if="$(arg deskewing)" name="OdomLOAM/ScanPeriod" type="string" value="0" />
</node>
<node pkg="rtabmap_slam" type="rtabmap" name="rtabmap" output="screen" args="$(arg rtabmap_args)">
<param name="frame_id" type="string" value="$(arg frame_id)" />
<param name="subscribe_depth" type="bool" value="true"/>
<param name="subscribe_rgb" type="bool" value="true"/>
<param name="subscribe_scan_cloud" type="bool" value="true" />
<param name="approx_sync" type="bool" value="true" />
<param name="wait_for_transform_duration" type="double" value="0.2" />
<remap from="scan_cloud" to="assembled_cloud" />
<remap from="rgb/image" to="/camera/color/image_raw"/>
<remap from="depth/image" to="/camera/aligned_depth_to_color/image_raw"/>
<remap from="rgb/camera_info" to="/camera/color/camera_info"/>
<remap from="depth/camera_info" to="/camera/depth/camera_info"/>
<remap from="imu" to="$(arg imu_topic)" />
<!-- RTAB-Map's parameters -->
<param name="Rtabmap/DetectionRate" type="string" value="1" />
<param name="RGBD/NeighborLinkRefining" type="string" value="false" />
<param name="RGBD/ProximityBySpace" type="string" value="true" />
<param name="RGBD/ProximityMaxGraphDepth" type="string" value="0" />
<param name="RGBD/ProximityPathMaxNeighbors" type="string" value="10" />
<param name="RGBD/AngularUpdate" type="string" value="0.05" />
<param name="RGBD/LinearUpdate" type="string" value="0.05" />
<param name="Mem/NotLinkedNodesKept" type="string" value="false" />
<param name="Mem/STMSize" type="string" value="30" />
<param name="Mem/LaserScanNormalK" type="string" value="20" />
<!-- localization mode -->
<param name="Mem/InitWMWithAllNodes" type="string" value="$(arg localization)"/>
<param if="$(arg localization)" name="Mem/IncrementalMemory" type="string" value="false"/>
<param unless="$(arg localization)" name="Mem/IncrementalMemory" type="string" value="true"/>
<!-- <param name="Mem/LocalizationDataSaved" type="string" value="true"/> --> <!-- Whether map should be updated in localization mode (default=false)-->
<param if="$(arg localization)" name="RGBD/StartAtOrigin" type="string" value="true"/>
<param name="Reg/Strategy" type="string" value="1" />
<param name="Grid/CellSize" type="string" value="$(eval resolution)" />
<param name="Grid/RangeMax" type="string" value="$(arg grid_max_range)" />
<param name="Grid/RayTracing" type="string" value="true" />
<param name="Grid/ClusterRadius" type="string" value="1" />
<param name="Grid/GroundIsObstacle" type="string" value="$(arg ground_is_obstacle)" />
<param name="Optimizer/GravitySigma" type="string" value="0.3" />
<!-- ICP parameters -->
<param name="Icp/VoxelSize" type="string" value="$(arg resolution)" />
<param name="Icp/PointToPlaneK" type="string" value="20" />
<param name="Icp/PointToPlaneRadius" type="string" value="0" />
<param name="Icp/PointToPlane" type="string" value="true" />
<param name="Icp/Iterations" type="string" value="$(arg iterations)" />
<param name="Icp/Epsilon" type="string" value="0.001" />
<param name="Icp/MaxTranslation" type="string" value="3" />
<param name="Icp/MaxCorrespondenceDistance" type="string" value="$(eval resolution*10)" />
<param name="Icp/PM" type="string" value="true" />
<param name="Icp/PMOutlierRatio" type="string" value="0.7" />
<param name="Icp/CorrespondenceRatio" type="string" value="$(arg loop_ratio)" />
</node>
<node if="$(arg rtabmap_viz)" name="rtabmap_viz" pkg="rtabmap_viz" type="rtabmap_viz"
output="screen">
<param name="frame_id" type="string" value="$(arg frame_id)" />
<param name="odom_frame_id" type="string" value="odom" />
<param name="subscribe_odom_info" type="bool" value="true" />
<param name="subscribe_scan_cloud" type="bool" value="true" />
<param name="approx_sync" type="bool" value="false" />
<remap from="scan_cloud" to="odom_filtered_input_scan" />
<remap from="odom_info" to="odom_info" />
</node>
<node pkg="nodelet" type="nodelet" name="point_cloud_assembler" args="standalone rtabmap_util/point_cloud_assembler" output="screen">
<remap from="cloud" to="$(arg scan_topic_deskewed)"/>
<remap from="odom" to="odom"/>
<param if="$(arg scan_20_hz)" name="max_clouds" type="int" value="20" />
<param unless="$(arg scan_20_hz)" name="max_clouds" type="int" value="10" />
<param name="fixed_frame_id" type="string" value="" />
<param name="queue_size" type="int" value="$(arg queue_size)" />
</node>
</group>
</launch>
Rosbag of real test flight (Note /mavros/vision_pose/pose is Optitrack data):
https://drive.google.com/file/d/1VyCl1a7A4dyc669E1452nhGhAXetonFD/view?usp=drive_linkTrajectory difference with current settings (Ground truth measured with Optitrack):


Update:
I switched from the above launch file that has rtabmap_slam/rtabmap and rtabmap_odom/icp_odometry separately to a launch filer using rtabmap.launch similar to the rtabmap_drone_example and managed to achieve a lot better results on the above mentioned bag.
As always thanks for all the help. Cheers,
Gilbert