warnings: disabling bundle adjustment, IMU won't be added to graph.

classic Classic list List threaded Threaded
2 messages Options
Reply | Threaded
Open this post in threaded view
|

warnings: disabling bundle adjustment, IMU won't be added to graph.

yonim
This post was updated on .
Hi sir,

While running the following launch file:

<launch>
  
  <arg name="output"                  default="screen"/>        <!-- Control node output (screen or log) -->
  
  <arg name="subscribe_scan"          default="true"/>
  <arg name="scan_topic"              default="/scan"/>
  
  <arg name="odom_topic"               default="odom"/>          <!-- Odometry topic name -->
  <arg name="publish_tf_odom"          default="true"/>
  <arg name="imu_topic"                default="/imu/data"/> 
  <arg name="rviz_cfg"                default="$(find rtabmap_ros)/launch/config/rgbd.rviz" />
  
  <group ns="rtabmap">

    <!-- Use RGBD synchronization -->
    <!-- Here is a general example using a standalone nodelet, 
         but it is recommended to attach this nodelet to nodelet 
         manager of the camera to avoid topic serialization -->
    <node pkg="nodelet" type="nodelet" name="rgbd_sync" args="standalone rtabmap_ros/rgbd_sync" output="screen">
      <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="rgbd_image"      to="rgbd_image"/> <!-- output -->

      <!-- Should be true for not synchronized camera topics 
           (e.g., false for kinectv2, zed, realsense, true for xtion, kinect360)-->
      <param name="approx_sync"       value="false"/> 
    </node>

     <!-- ICP Odometry -->
    <node  pkg="rtabmap_ros" type="icp_odometry" name="icp_odometry" output="$(arg output)" args="$(arg rtabmap_args) " >
      <remap from="scan"                   to="$(arg scan_topic)"/>
      <remap from="odom"                   to="$(arg odom_topic)"/>
      <remap from="imu"                    to="$(arg imu_topic)"/>
      
      <param name="frame_id"                    type="string" value="base_link"/>
      <param name="odom_frame_id"               type="string" value="odom"/>
      <param name="publish_tf"                  type="bool"   value="true"/>
     
      <param name="wait_imu_to_init"            type="bool"   value="true"/>         
    </node>
    
    <node name="rtabmap" pkg="rtabmap_ros" type="rtabmap" output="screen" args="--delete_db_on_start">
          <param name="frame_id" type="string" value="base_link"/>

          <param name="subscribe_depth" type="bool" value="false"/>
          <param name="subscribe_rgbd" type="bool" value="true"/>
          <param name="subscribe_scan" type="bool" value="true"/>

          <remap from="odom" to="odom"/>
          <remap from="scan" to="/scan"/>
          <remap from="rgbd_image" to="rgbd_image"/>

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

         <!-- <param name="map_frame_id"         type="string" value="map"/>
          <param name="odom_frame_id"        type="string" value="odom"/>  -->

          <!-- RTAB-Map's parameters -->
          <param name="RGBD/NeighborLinkRefining" type="string" value="true"/>
          <param name="RGBD/ProximityBySpace"     type="string" value="true"/>
          <param name="RGBD/AngularUpdate"        type="string" value="0.01"/>
          <param name="RGBD/LinearUpdate"         type="string" value="0.01"/>
          <param name="RGBD/OptimizeFromGraphEnd" type="string" value="false"/>
          <param name="Grid/FromDepth"            type="string" value="false"/> <!-- occupancy grid from lidar -->
          <param name="Reg/Force3DoF"             type="string" value="true"/>
          <param name="Reg/Strategy"              type="string" value="1"/> <!-- 1=ICP -->
          
          <!-- ICP parameters -->
          <param name="Icp/VoxelSize"                 type="string" value="0.05"/>
          <param name="Icp/MaxCorrespondenceDistance" type="string" value="0.1"/>
    </node>
  </group>

  <!-- Visualization RVIZ -->
  <node  pkg="rviz" type="rviz" name="rviz" args="-d $(arg rviz_cfg)"/>
  <node  pkg="nodelet" type="nodelet" name="points_xyzrgb" args="standalone rtabmap_ros/point_cloud_xyzrgb" output="$(arg output)">
 
    <param name="decimation"  type="double" value="4"/>
    <param name="voxel_size"  type="double" value="0.0"/>
    <param name="approx_sync" type="bool"   value="$(arg approx_sync)"/>
  </node>

</launch>

The following warnings are received:
[ WARN] (2021-03-14 05:28:52.059) OdometryF2M.cpp:164::OdometryF2M() OdomF2M/BundleAdjustment=1 cannot be used with registration not done only with images (Reg/Strategy=1), disabling bundle adjustment.
[ WARN] [1615692533.418470914]: We are receiving imu data (buffer=5), but cannot interpolate imu transform at time 1615692533.058735. IMU won't be added to graph.

Does it mean that no bundle adjustment is done ?
Is the loop closure relying on images? lidar? both?
Why is the IMU not added to graph?


Thank you a lot for your support!!
Reply | Threaded
Open this post in threaded view
|

Re: warnings: disabling bundle adjustment, IMU won't be added to graph.

matlabbe
Administrator
Hi,

The bundle warning is coming from the icp_odometry node, which is using scan, so visual stuff are disabled.

For rtabmap node, images are using for loop closure detections, and lidar for proximity detections.

The IMU warning seems coming from rtabmap node, but you didn't explicitly remap the imu topic, not sure to which imu topic it is connected. What is the frequency of the imu topic (rostopic hz)?

cheers,
Mathieu