Re: Tilted 3D map with floam
Posted by
matlabbe on
URL: http://official-rtab-map-forum.206.s1.nabble.com/Tilted-3D-map-with-floam-tp10380p10406.html
Hi,
Thx for sharing the data. I tried multiple configs to make deskewing working with the provided imu, but it just seems that the TF between imu to lidar is wrong (not sure why though, I saw that on other ousters too), so we cannot really use it for deskewing or aligning the map with gravity. I tried enabling (with the option in my example below) deskewing with the actual motion estimation from icp_odometry, but the resulting point clouds are pretty close to each. Probably because the robot is not moving that fast and the lidar frame rate is high (20 Hz) unlike the usual 10 Hz (see this
video for more intense skewing).
Note that to avoid TF already recorded in the bag, I just ignored them all.
roslaunch test.launch
rosbag play --clock tf:=/not_used tf_static:=/not_used 2024-08-16-15-08-03.bag
The launch file I tested:
<!-- -->
<launch>
<param name="use_sim_time" value="true"/>
<arg name="scan_topic" value="/ouster/points"/>
<arg name="frame_id" value="os_sensor"/>
<arg name="deskewing" value="false"/>
<group ns="rtabmap">
<!-- Start Odometry Node -->
<node pkg="rtabmap_odom" type="icp_odometry" name="icp_odometry" output="screen">
<remap from="scan_cloud" to="$(arg scan_topic)"/>
<param name="frame_id" value="$(arg frame_id)"/>
<param name="odom_frame_id" value="odom"/>
<param name="deskewing" value="$(arg deskewing)"/>
<param name="publish_tf" type="bool" value="true"/>
<rosparam command="load" file="$(find rtabmap_launch)/config/cfg_icp_odom.yaml"/>
</node>
<!-- Start Mapping Node -->
<node pkg="rtabmap_slam" type="rtabmap" name="rtabmap" output="screen" args="--delete_db_on_start">
<param name="frame_id" value="$(arg frame_id)"/>
<param name="map_frame_id" value="map"/>
<param name="subscribe_depth" value="false"/>
<param name="subscribe_rgb" value="false"/>
<param name="subscribe_scan_cloud" value="true"/>
<param name="approx_sync" value="true"/>
<rosparam command="load" file="$(find rtabmap_launch)/config/cfg_rtabmap_mapping.yaml"/>
<remap from="scan_cloud" to="odom_filtered_input_scan"/>
<remap from="odom" to="odom"/>
<remap from="grid_map" to="/map"/>
</node>
<node 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"/>
</node>
</group>
</launch>
odom config:
Icp/PointToPlane: true
Icp/Iterations: 10
Icp/VoxelSize: 0.2
Icp/DownsamplingStep: 1
Icp/Epsilon: 0.001
Icp/PointToPlaneK: 20
Icp/PointToPlaneRadius: 0
Icp/MaxTranslation: 2
Icp/MaxCorrespondenceDistance: 2
Icp/PM: true
Icp/PMOutlierRatio: 0.7
Icp/CorrespondenceRatio: 0.01
Icp/Force4DoF: true
Odom/GuessSmoothingDelay: 0.3
Odom/ScanKeyFrameThr: 0.6
Odom/Strategy: 0
OdomF2M/ScanSubtractRadius: 0.2
OdomF2M/ScanMaxSize: 15000
rtabmap config:
Rtabmap/DetectionRate: 1
RGBD/NeighborLinkRefining: false
RGBD/ProximityBySpace: true
RGBD/ProximityMaxGraphDepth: 0
RGBD/ProximityPathMaxNeighbors: 1
RGBD/LocalRadius: 2
RGBD/AngularUpdate: 0.05
RGBD/LinearUpdate: 0.05
Mem/NotLinkedNodesKept: false
Mem/STMSize: 30
Mem/LaserScanNormalK: 20
Reg/Strategy: 1
Optimizer/GravitySigma: 0.3
Optimizer/Strategy: 1
Grid/3D: true
Grid/CellSize: 0.05
Grid/ClusterRadius: 0.4
Grid/Sensor: 0
Grid/MaxObstacleHeight: 1.8
Grid/MaxGroundHeight: 0.3
Grid/NormalsSegmentation: true
Grid/RayTracing: true
GridGlobal/MinSize: 200
Icp/VoxelSize: 0.2
Icp/PointToPlaneK: 20
Icp/PointToPlaneRadius: 0
Icp/PointToPlane: true
Icp/Iterations: 1
Icp/Epsilon: 0.001
Icp/MaxTranslation: 3
Icp/MaxCorrespondenceDistance: 2
Icp/Strategy: 1
Icp/OutlierRatio: 0.7
Icp/CorrespondenceRatio: 0.2
With and without loop closures

:

Here some side views:





The small slope is caused by the lidar not starting exactly aligned with the gravity, and we don't have valid imu to re-align correctly. To do it automatically, you would need a better imu (maybe less noisy) with TF perfectly aligned with lidar frame. With CloudCompare, we can easily click three points to align the floor with xy plane though.