introlab / rtabmap_ros

RTAB-Map's ROS package.
http://wiki.ros.org/rtabmap_ros
BSD 3-Clause "New" or "Revised" License
999 stars 558 forks source link

Problem with 3D lidar SLAM #768

Open manserrod opened 2 years ago

manserrod commented 2 years ago

Hello guys,

I'm trying to set up my Summit-XL robot for SLAM (using a 3D Lidar and RGBD Camera) in ros-Kinetic. I found out about this package and I thought it was perfect for what I had in mind. The thing is I keep having some issues while mapping the environment in the simulation:

But, after a few loops, this warning keeps poping up: image

And eventually, either the process ends abruptly or the odom_frame and the map_frame get misaligned. As I understand, this issue occurs because the environment isn't "cluttered" enough. I've investigated and tried to tune up the parameters, but the issue persists.

The process also shows this warning at the beginning sometimes: image

When it happens, it usually ends in termination shortly after.

For reference, here is my .launch file:

<launch>
<group ns="rtabmap">

 <node pkg="nodelet" type="nodelet" name="rgbd_sync" args="standalone rtabmap_ros/rgbd_sync" output="screen">
   <remap from="rgb/image"       to="/robot/front_rgbd_camera/rgb/image_raw"/>
   <remap from="depth/image"     to="/robot/front_rgbd_camera/depth/image_raw"/>
   <remap from="rgb/camera_info" to="/robot/front_rgbd_camera/rgb/camera_info"/>
   <remap from="rgbd_image"      to="combo"/> <!-- output -->
   <param name="approx_sync"     value="false"/> 
 </node>

 <node pkg="rtabmap_ros" type="rtabmap" name="rtabmap" output="screen" args="--delete_db_on_start">
   <param name="subscribe_rgbd"       type="bool" value="true"/>
   <param name="frame_id"             type="string" value="robot_base_footprint"/>
<!-- <param name="odom_frame_id"        type="string" value="robot_odom"/> -->
   <param name="subscribe_depth"      type="bool" value="false"/>
   <param name="subscribe_rgb"        type="bool" value="false"/>
   <param name="subscribe_scan_cloud" type="bool" value="true"/>
   <param name="approx_sync"          type="bool" value="true"/>
   <param name="odom_guess_frame_id"        type="string" value="robot_odom"/>

   <remap from="odom"       to="/robot/robotnik_base_control/odom"/>
   <remap from="gps/fix"    to="/robot/gps/fix"/>
   <remap from="gps/fix"    to="/robot/gps/fix"/>
   <remap from="imu"        to="/robot/imu/data_raw"/>
   <remap from="scan_cloud" to="/robot/front_3d_laser/points"/>
   <remap from="rgbd_image" to="combo"/>

  <!-- RTAB-Map's parameters -->
   <param name="Rtabmap/DetectionRate"          type="string" value="1"/>

   <param name="RGBD/NeighborLinkRefining"      type="string" value="false"/>
   <param name="RGBD/ProximityMaxGraphDepth"    type="string" value="0"/>
   <param name="RGBD/ProximityPathMaxNeighbors" type="string" value="1"/>
   <param name="RGBD/AngularUpdate"             type="string" value="0.01"/>
   <param name="RGBD/OptimizeMaxError"          type="string" value="0"/> 

   <param name="Optimizer/Strategy"         type="string" value="2"/> <!-- g2o=1, GTSAM=2 -->
   <param name="Optimizer/Robust"               type="string" value="true"/>

   <param name="Mem/NotLinkedNodesKept"         type="string" value="false"/>
   <param name="Mem/STMSize"                    type="string" value="30"/>
   <param name="Mem/LaserScanVoxelSize"         type="string" value="0"/>

   <param name="Reg/Strategy"                   type="string" value="1"/>
   <param name="Reg/Force3DoF"                  type="string" value="true"/>

   <param name="Grid/CellSize"                  type="string" value="0.05"/>
   <param name="Grid/RangeMax"                  type="string" value="5"/>
   <param name="Grid/ClusterRadius"             type="string" value="1"/>
   <param name="Grid/GroundIsObstacle"          type="string" value="false"/>
   <param name="Grid/RayTracing"                type="string" value="false"/>
   <param name="Grid/3D"                        type="string" value="true"/>
   <param name="Grid/MaxObstacleHeight"         type="string" value="1.5"/>

   <param name="Icp/MaxTranslation"             type="string" value="0.30"/>
   <param name="Icp/MaxRotation"                type="string" value="0.80"/>
   <param name="Icp/VoxelSize"                  type="string" value="0"/>
   <param name="Icp/Iterations"                 type="string" value="10"/>

   <param name="OdomF2M/ScanSubtractRadius"     type="string" value="0.2"/>
   <param name="OdomF2M/ScanMaxSize"            type="string" value="10000"/>
 </node>

</group>
</launch>

Sorry if some of these questions seem a bit basic, I'm still fairly new to ROS and I've struggled a bit with it. In any case, thank you!

matlabbe commented 2 years ago

If your odomery topic has wrong covariance, use odom_frame_id instead to use TF for odometry. You can also tune odom_tf_angular_variance (default 0.001) and odom_tf_angular_variance (default 0.001) parameters.

For the 0 0 0 0 warning, I think it is a test warning message that was wrongly committed (are you using latest master or kinetic binaries?). To see where it coming from, you can use rqt_console. Kinetic binaries are not updated anymore. I think that warning msg has been removed.

For the GTSAM error, how did you install GTSAM? May be related to some tbb compilation issue. However, as you shown with your very large covariance, GTSAM will likely fail with such large covariance. Fix the covariance as explained above, or you can also use g2o instead by setting Optimizer/Strategy to 1.