introlab / rtabmap

RTAB-Map library and standalone application
https://introlab.github.io/rtabmap
Other
2.85k stars 787 forks source link

Building rtabmap with ORB_SLAM3 crashes rtabmap when a Loop Closure is detected #1056

Closed GVMCOTESA closed 1 year ago

GVMCOTESA commented 1 year ago

I am trying to build RTAB-Map with ORB-SLAM3 support. The problem is that when a LC is detected, it crashes:

[rtabmap/rtabmap-7] process has died [pid 15906, exit code -11, cmd /ros_ws/devel/lib/rtabmap_slam/rtabmap -d move_base:=/move_base scan:=/scan odom:=/odom rgbd_image:=rgbd_image grid_map:=/map __name:=rtabmap __log:=/home/germanvega/.ros/log/9948e098-0aa0-11ee-a4ae-0242ac1b0002/rtabmap-rtabmap-7.log].
log file: /home/germanvega/.ros/log/9948e098-0aa0-11ee-a4ae-0242ac1b0002/rtabmap-rtabmap-7*.log

I have isolated the problem to when I build with this flag: -DWITH_ORB_SLAM=ON

I have the following launch node:

<node name="rtabmap" pkg="rtabmap_slam" type="rtabmap" output="screen" args="$(arg rtabmap_args)">
      <param name="database_path"       type="string" value="$(arg database_path)"/>
      <param name="frame_id"            type="string" value="base_link"/>
      <param name="subscribe_rgb"   type="bool" value="false"/>
      <param name="subscribe_depth" type="bool" value="false"/>
      <param name="subscribe_rgbd" type="bool" value="true"/>
      <param name="subscribe_scan"      type="bool"   value="true"/>
      <param name="approx_sync"         type="bool"   value="true"/>

      <!-- use actionlib to send goals to move_base -->
      <param name="use_action_for_goal" type="bool" value="true"/>
      <remap from="move_base"            to="/move_base"/>

      <!-- inputs -->
      <remap from="scan"            to="/scan"/>
      <remap from="odom"            to="/odom"/>
      <remap from="rgbd_image"       to="rgbd_image"/>

      <!-- output -->
      <remap from="grid_map" to="/map"/>

      <!-- 3D->2D (PnP) -->
      <param name="RGBD/OptimizeMaxError"             type="double"   value="4.000"  />
      <param name="RGBD/OptimizeFromGraphEnd"         type="string"   value="false"/>
      <param name="RGBD/LoopClosureReextractFeatures" type="string"   value="true"/>
      <param name="Grid/MaxGroundHeight"              type="double"   value="0.18"/>

      <param name="Vis/MinInliers"                    type="string"   value="10"/>
      <param name="Vis/InlierDistance"                type="string"   value="0.1"/>
      <param name="Viz/EstimationType"                type="int"      value="1"/>
      <param name="Vis/MaxFeatures"                   type="int"      value="1000"/>

      <!-- Force 2d mode -->
      <param name="Reg/Force3DoF"                                     value="true" />
      <param name="Optimizer/Slam2D"                                  value="true" />

      <!-- RGBD Settings -->
      <param name="RBGD/Enabled"          type="string"   value="true"/>
      <param name="Grid/Sensor"           type="string"   value="0"/>
      <param name="subscribe_stereo"      type="bool"     value="false"/>
      <param name="subscribe_depth"       type="bool"     value="true"/>
      <param name="subscribe_scan_cloud"  type="bool"     value="false"/>
      <param name="stereo_approx_sync"    type="bool"     value="true"/>

      <param name="frame_id"              type="string"   value="base_link"/>

      <param name="queue_size"            type="int"      value="30"/>

      <!-- ORB-SLAM3 5 -->
      <param name="Odom/Strategy" type="int" value="0"/>
      <param name="OdomORBSLAM/VocPath" type="string" value="/orb_slam/ORB_SLAM3_NOETIC/Vocabulary/ORBvoc.txt"/>
    </node>

ORB_SLAM is deactivated and still it crashes.

I have seen some warnings in the log:

[...]
[ INFO] [1686740296.858683728]: Setting RTAB-Map parameter "g2o/RobustKernelDelta"="8"
[ INFO] [1686740296.858988821]: Setting RTAB-Map parameter "g2o/Solver"="3"
[ WARN] [1686740296.949849953]: Rtabmap: Parameter name changed: "Optimizer/Slam2D" -> "Reg/Force3DoF". The new parameter is already used with value "true", ignoring the old one with value "true".
[ INFO] [1686740296.999183656]: RTAB-Map detection rate = 1.000000 Hz
[...]
 INFO] [1686740297.091969384]: rtabmap: Database version = "0.21.1".
[ INFO] [1686740297.092061045]: rtabmap: SLAM mode (Mem/IncrementalMemory=true)
[ WARN] [1686740297.111964837]: rtabmap: Parameters subscribe_depth and subscribe_rgbd cannot be true at the same time. Parameter subscribe_depth is set to false.
[ INFO] [1686740297.114539755]: /rtabmap/rtabmap: subscribe_depth = false
[ INFO] [1686740297.114595612]: /rtabmap/rtabmap: subscribe_rgb = false
[...]
[ INFO] [1686740297.289734604]: rtabmap 0.21.1 started...
[INFO] [1686740297.328318, 1252.750000]: wait_for_service(/gazebo/spawn_urdf_model): finally were able to contact [rosrpc://5f4c55589052:40605]
[INFO] [1686740297.331876, 1252.750000]: Calling service /gazebo/spawn_urdf_model
[ WARN] [1686740297.392913614, 1252.820000000]: Timed out waiting for transform from base_link to map to become available before running costmap, tf error: canTransform: target_frame map does not exist.. canTransform returned after 1252.82 timeout was 0.1.
../src/intel/isl/isl.c:2105: FINISHME: ../src/intel/isl/isl.c:isl_surf_supports_ccs: CCS for 3D textures is disabled, but a workaround is available.
libpng warning: iCCP: known incorrect sRGB profile
libpng warning: iCCP: known incorrect sRGB profile
libpng warning: iCCP: known incorrect sRGB profile
[...]
[ INFO] [1686740299.214247624, 1253.390000000]: Requesting the map...
[ INFO] [1686740299.414872685, 1253.590000000]: Resizing static layer to 140 X 136 at 0.050000 m/pix
[ INFO] [1686740299.514066437, 1253.690000000]: Received a 140 X 136 map at 0.050000 m/pix
[ INFO] [1686740299.514160982, 1253.690000000]: Subscribing to updates
[ WARN] [1686740299.555466979, 1253.730000000]: local_costmap: Pre-Hydro parameter "static_map" unused since "plugins" is provided
[ INFO] [1686740299.556550166, 1253.730000000]: local_costmap: Using plugin "obstacle_layer"
[ INFO] [1686740299.558870446, 1253.730000000]:     Subscribed to Topics: laser_scan_sensor
[ INFO] [1686740299.643684287, 1253.810000000]: Created local_planner base_local_planner/TrajectoryPlannerROS
[...]
[ INFO] [1686740348.178711104, 1302.310000000]: rtabmap (48): Rate=1.00s, Limit=0.000s, Conversion=0.0018s, RTAB-Map=0.0451s, Maps update=0.0020s pub=0.0008s (local map=43, WM=43)
[ INFO] [1686740349.272326911, 1303.400000000]: rtabmap (49): Rate=1.00s, Limit=0.000s, Conversion=0.0022s, RTAB-Map=0.0408s, Maps update=0.0011s pub=0.0002s (local map=43, WM=43)
[rtabmap/rtabmap-7] process has died [pid 15906, exit code -11, cmd /ros_ws/devel/lib/rtabmap_slam/rtabmap -d move_base:=/move_base scan:=/scan odom:=/odom rgbd_image:=rgbd_image grid_map:=/map __name:=rtabmap __log:=/home/germanvega/.ros/log/9948e098-0aa0-11ee-a4ae-0242ac1b0002/rtabmap-rtabmap-7.log].
log file: /home/germanvega/.ros/log/9948e098-0aa0-11ee-a4ae-0242ac1b0002/rtabmap-rtabmap-7*.log
[ WARN] [1686740350.661189772, 1304.790000000]: Costmap2DROS transform timeout. Current time: 1304.7900, global_pose stamp: 1304.4800, tolerance: 0.2500
[ WARN] [1686740350.860628721, 1304.990000000]: Transform timeout for global_costmap. Current time: 1304.9900, pose stamp: 1304.4800, tolerance: 0.5000
[ WARN] [1686740350.860769002, 1304.990000000]: Unable to get starting pose of robot, unable to create global plan
[ WARN] [1686740350.860824946, 1304.990000000]: Unable to get starting pose of robot, unable to create global plan
[ WARN] [1686740350.860833715, 1304.990000000]: Unable to get starting pose of robot, unable to create global plan
<This warning repeats thousands of times in less than a second>
[ERROR] [1686739963.445686975, 1652.690000000]: Extrapolation Error looking up robot pose: Lookup would require extrapolation 346.150000000s into the past.  Requested time 1296.530000000 but the earliest data is at time 1642.680000000, when looking up transform from frame [base_link] to frame [map]

Versions

matlabbe commented 1 year ago

I suspect an issue with -march=native or multiple opencv versions on the computer. See step A from https://github.com/introlab/rtabmap_ros/issues/28#issue-99654759 to get more logs (backtrace) when it crashes.

GVMCOTESA commented 1 year ago

It was -march=native, I am working with the focal docker image, and I created the following command to remove that flag from all CMakeLists.txt in the ORB_SLAM3_NOETIC repo:

sed -i 's/-march=native//g' CMakeLists.txt Thirdparty/DBoW2/CMakeLists.txt Thirdparty/g2o/CMakeLists.txt

Thank you!