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

extrapolation error of local cost map in navigation

asked 2012-08-04 05:49:14 -0600

psykokwak gravatar image

updated 2012-08-04 05:52:24 -0600

Hi all, I'm following the navigation tutorial with my differential wheeled robot. I build my map with hector slam and now i'm trying to explore it with the navigation stack but I have the following error when I try to send the robot at some Goal :

[ERROR] [1344094708.876267784]: Extrapolation Error: Unable to lookup transform, cache is empty, when looking up transform from frame [/odom] to frame [/map]
[ERROR] [1344094708.876364007]: Global Frame: /odom Plan Frame size 98: /map
[ WARN] [1344094708.876424927]: Could not transform the global plan to the frame of the controller

If I replace the "global_frame" parameter from "/odom" to whatever (like "/map") in the "local_costmap_params.yaml" configuration file, the error disapears but it does not work...

My tf tree seems good : image description

And a tf_echo seems good :

psykokwak@robot:~/ros/workspace$ rosrun tf tf_echo /map /odom
At time 1344095433.661
- Translation: [-0.008, 0.011, 0.000]
- Rotation: in Quaternion [0.000, 0.000, 0.000, 1.000]
            in RPY [0.000, -0.000, 0.001]
At time 1344095434.660
- Translation: [-0.007, 0.009, 0.000]
- Rotation: in Quaternion [0.000, 0.000, 0.000, 1.000]
            in RPY [0.000, -0.000, 0.000]
At time 1344095435.659
- Translation: [-0.007, 0.009, 0.000]
- Rotation: in Quaternion [0.000, 0.000, 0.000, 1.000]
            in RPY [0.000, -0.000, 0.000]
At time 1344095435.926
- Translation: [-0.005, 0.008, 0.000]
- Rotation: in Quaternion [0.000, 0.000, 0.000, 1.000]
            in RPY [0.000, -0.000, 0.001]



So, I have no idea about the origin of my problem :(

edit retag flag offensive close merge delete

Comments

No one knows ? :(

psykokwak gravatar image psykokwak  ( 2012-08-06 08:55:04 -0600 )edit

I have the same problem, but only when I launch the robot_pose_ekf stack... Whitout that stack everything works perfectly. But I don't know how to solve it :( Did you found what was wrong?

g.aterido gravatar image g.aterido  ( 2012-10-23 21:45:28 -0600 )edit

sorry...... I am now encountering such problem..... do you figure it out!!????

Gazer gravatar image Gazer  ( 2013-06-13 07:49:38 -0600 )edit

I have same problem, any help?

Reza gravatar image Reza  ( 2013-07-11 01:29:48 -0600 )edit

I have the same problem and cannot resolve it. Any help would be very much appreciated. My thread on this problem can be found here: http://answers.ros.org/question/63360/extrapolation-error-using-hector_mapping-move_base/

Huibuh gravatar image Huibuh  ( 2013-08-12 20:43:59 -0600 )edit

Have same problem too!

AbuIbra gravatar image AbuIbra  ( 2013-11-01 16:30:28 -0600 )edit

Ditto, except I'm using gmapping instead of hector_slam

BlitherPants gravatar image BlitherPants  ( 2014-01-14 10:15:06 -0600 )edit

2 Answers

Sort by ยป oldest newest most voted
5

answered 2014-01-23 19:59:23 -0600

Huibuh gravatar image

Hello All,

I know what the origin of the problem is, and how to (at least temporarily) fix it.

The Problem

When using AMCL to provide the map->odom tf-transform to move_base, everything works fine. This is because AMCL 'future dates' the provided transform (see last sentence here: http://wiki.ros.org/amcl#Transforms).

However, when using hector_slam for localization instead of AMCL, the provided map->odom tf-transform is not future dated. This leads to move_base throwing the mentioned error:

Extrapolation Error: Unable to lookup transform, cache is empty, when looking up transform from frame [/odom] to frame [/map]

How to temporarily fix it

Check out https://github.com/tu-darmstadt-ros-pkg/hector_slam.git (catkin branch) into your own ROS workspace and modify Line 347 in file HectorMappingRos.cpp (direct link https://github.com/tu-darmstadt-ros-pkg/hector_slam/blob/catkin/hector_mapping/src/HectorMappingRos.cpp) as follows:

# Replace the original line 347 in HectorMappingRos.cpp
tfB_->sendTransform( tf::StampedTransform (map_to_odom_, scan.header.stamp, p_map_frame_, p_odom_frame_));

# ...with these two lines
ros::Duration future_date_duration(0.3F);
tfB_->sendTransform( tf::StampedTransform (map_to_odom_, scan.header.stamp  + future_date_duration, p_map_frame_, p_odom_frame_));

This future dates the tf-transform published by hector_mapping by 0.3s. Then compile the package and re-run your experiment. In my case, this got rid of the error messages.

But this has some disadvantages:

  • The delay of 0.3s can be noted in the navigation/localization performance of hector_mapping in conjunction with move_base. You can also see the updates in rviz lag behind.
  • Patched hector_mapping is no permanent solution.

@BlitherPants I suppose it is the same reason why gmapping throws the same errors when used together with move_base.

Suggested permanent fix

I can see two options:

  1. move_base has to be changed so it also accepts non-future dated map->odom transforms OR
  2. hector_slam and gmapping have to be modified to provide future dated map->odom transforms

I suggest we get the follwing people involved in this discussion:

'@David Lu' (AMCL + move_base maintainer)

'@Stefan Kohlbrecher' (hector_slam author)

'@Johannes Meyer' (hector_slam maintainer)

'@Brian Gerkey' (gmapping author)

edit flag offensive delete link more

Comments

Wow, thanks for the detailed answer! I'll have to see if I can poke around in the source code of gmapping and get back to you...

BlitherPants gravatar image BlitherPants  ( 2014-01-24 02:06:55 -0600 )edit

This iooks like a bug in move_base to me. Future-dating a transform that is based on timestamped laser (and odometry) data is wrong (even if the error will be small for practical applications so that it won't break things). Sounds like there's simply a waitForTransform missing.

Stefan Kohlbrecher gravatar image Stefan Kohlbrecher  ( 2014-01-27 05:14:54 -0600 )edit

It looks like the error is happening in TrajectoryPlannerROS (called by move_base, called by gmapping), in the function "transformGlobalPlan" in goal_functions.cpp. Inside this function is a lookupTransform but no waitForTransform. Wonder if that's the problem? My tf skills are still being built...

BlitherPants gravatar image BlitherPants  ( 2014-01-27 07:06:18 -0600 )edit
1

answered 2014-07-07 14:30:31 -0600

Manolis Chiou gravatar image

Very good solution! Saved me a lot of research as I need to use hector slam with move_base. However, I think there is no need for the duration to be so high. In my case it works with 0.09-0.1 secs. Looking on how gmapping works with move_base I saw the following lines:

ros::Time tf_expiration = ros::Time::now() + ros::Duration(tf_delay_);
 tfB_->sendTransform( tf::StampedTransform (map_to_odom_, tf_expiration, map_frame_, odom_frame_));

with tf_delay to be:

 if(!private_nh_.getParam("tf_delay", tf_delay_))
    tf_delay_ = transform_publish_period;

In the case of hector_slam I think the tranform period is the published /scan period and it depends on the laser. In my case with the hokuyo urg-04lx is 0.1 sec (10hz).

Works fine so far with move_base. The only thing i have noticed is more cpu load by hector_slam.

edit flag offensive delete link more

Question Tools

7 followers

Stats

Asked: 2012-08-04 05:49:14 -0600

Seen: 4,689 times

Last updated: Jul 07 '14