ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
2

rtabmap obstacle_detection error: lookup would require extrapolation into the future when looking up transform.

asked 2022-02-06 13:18:09 -0600

updated 2022-02-07 13:51:14 -0600

Hi everyone, I have a problem with using rtabmap obstacle_detection nodelet, I get the following error when trying to read the published topic ( in my case called /pointCloud_obstacles):

   [ERROR]  Lookup would require extrapolation -0.120000000s into the future.  Requested time 1027.127000000 but the latest data is at time 1027.007000000, when looking up transform from frame [base_link] to frame [map]

The difference in the two times is always about 0.1 (seconds?) and it's also interesting how it says that it require extrapolation of a negative time into the future, so it seems more the past than the future.

I don't get any error if I do not access the topic (e.g. using rostopic hz or another node).

This is the relevant part of the tf tree: tf tree

This is my launch file, mainly taken from rtabmap outdoor mapping tutorial and from rtabmap outdoor navigation tutorial:

   <param name="use_sim_time" type="bool" value="true"/>

   <!--

   --> 
   <!-- Stereo Odometry -->   
   <node pkg="rtabmap_ros" type="stereo_odometry" name="stereo_odometry" output="screen">
      <remap from="left/image_rect"       to="/zed2/left/image_rect_color"/>
      <remap from="right/image_rect"      to="/zed2/right/image_rect_color"/>
      <remap from="left/camera_info"      to="/zed2/left/camera_info"/>
      <remap from="right/camera_info"     to="/zed2/right/camera_info"/>

      <param name="frame_id" type="string" value="base_footprint"/>
      <param name="queue_size" type="int" value="20"/>
      <param name="odom_frame_id" type="string" value="odom"/>
      <param name="wait_for_transform" type="bool" value="true"/>

      <param name="Odom/Strategy" type="string" value="0"/> <!-- 0=BOW, 1=OpticalFlow -->
      <param name="Odom/EstimationType" type="string" value="1"/> <!-- 3D->2D (PnP) -->
      <param name="Odom/MinInliers" type="string" value="10"/>
      <param name="Odom/RoiRatios" type="string" value="0.03 0.03 0.04 0.04"/>
      <param name="Odom/MaxDepth" type="string" value="10"/>
      <param name="OdomBow/NNDR" type="string" value="0.8"/>
      <param name="Odom/MaxFeatures" type="string" value="1000"/>
      <param name="Odom/FillInfoData" type="string" value="$(arg rtabmapviz)"/>
      <param name="GFTT/MinDistance" type="string" value="10"/>
      <param name="GFTT/QualityLevel" type="string" value="0.00001"/> 
   </node>



   <group ns="rtabmap">   
      <!-- Visual SLAM: args: "delete_db_on_start" and "udebug" -->
      <node name="rtabmap" pkg="rtabmap_ros" type="rtabmap" output="screen" args="--delete_db_on_start">
         <param name="frame_id" type="string" value="zed2_camera_center"/>
         <param name="subscribe_stereo" type="bool" value="true"/>
         <param name="subscribe_depth" type="bool" value="true"/>

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

         <param name="queue_size" type="int" value="30"/>
         <remap from="left/image_rect" to="/zed2/left/image_rect_color"/>
         <remap from="right/image_rect" to="/zed2/right/image_rect_color"/>
         <remap from="left/camera_info" to="/zed2/left/camera_info"/>
         <remap from="right/camera_info" to="/zed2/right/camera_info"/>
         <!-- RTAB-Map's parameters -->
         <param name="Rtabmap/TimeThr" type="string" value="700"/>
         <param name="Rtabmap/DetectionRate" type="string" value="1"/>

         <param name="Kp/MaxFeatures" type="string" value="200"/>
         <param name="Kp/RoiRatios" type="string" value="0.03 0.03 0.04 0.04"/>
         <param ...
(more)
edit retag flag offensive close merge delete

Comments

1

Hi @parmex, please take a look at this previous question #q357836 and please share the things that you have discarded. Please check both answers.

osilva gravatar image osilva  ( 2022-02-07 17:28:53 -0600 )edit

Hi @osilva,thank you for the suggestion! I already looked at that question and I found some hint on what could cause the problem but sadly not how to solve it. Anyway, I marked as accepted the answer below, as it solves my issue :)

AlessioParmeggiani gravatar image AlessioParmeggiani  ( 2022-02-08 04:43:29 -0600 )edit

1 Answer

Sort by ยป oldest newest most voted
1

answered 2022-02-07 20:22:45 -0600

matlabbe gravatar image

It looks like waitForTransform is false by default here. Try adding wait_for_transform parameter to obstacles_detection nodelet:

 <node pkg="nodelet" type="nodelet" name="obstacles_detection"
    args="load rtabmap_ros/obstacles_detection stereo_nodelet">
      <remap from="cloud" to="/pointCloud_downsample"/>
      <remap from="obstacles" to="/pointCloud_obstacles"/>
      <param name="use_sim_time" type="bool" value="true"/>
      <param name="frame_id" type="string" value="base_footprint"/>
      <param name="map_frame_id" type="string" value="map"/>
      <param name="wait_for_transform" type="bool" value="true"/>
      <param name="Grid/MinClusterSize" type="int" value="5"/>
      <param name="Grid/ClusterRadius"       type="double" value="0.1"/>
      <param name="Grid/MaxObstaclesHeight" type="double" value="0.5"/>  
   </node>

The error happens because it is receiving the point cloud before odometry has been completely computed, so it has to wait a little to get TF at that stamp.

edit flag offensive delete link more

Comments

Thank you so much! This solved the problem! :)

AlessioParmeggiani gravatar image AlessioParmeggiani  ( 2022-02-08 04:40:18 -0600 )edit

Question Tools

1 follower

Stats

Asked: 2022-02-06 13:18:09 -0600

Seen: 237 times

Last updated: Feb 07 '22