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

Could not transform the global plan to the frame of the controller

asked 2018-10-01 02:19:18 -0600

updated 2020-01-07 18:22:13 -0600

jayess gravatar image

Hello,

I am using the husky mobile base with ros kinetic. I am using hector_mapping for getting the map and using move_base for sending simple 2D navigation goal. I additionally tried using the map_server to save the map and use the map with amcl and move_base. I am assuming this is mostly coming from move_base. However In either case whenever I pass a 2D navigation goal. I start receiving:

[ INFO] [1538375948.914403476]: Got new plan
[ERROR] [1538375948.914494414]: Extrapolation Error: Lookup would require extrapolation into the future.  Requested time 1538375948.918941058 but the latest data is at time 1538375948.914756447, when looking up transform from frame [odom] to frame [map]

[ERROR] [1538375948.914534395]: Global Frame: odom Plan Frame size 50: map

[ WARN] [1538375948.914546917]: Could not transform the global plan to the frame of the controller
[ERROR] [1538375948.914558586]: Could not get local plan

I came across couple of posts: like this one . I synced the clock. Here is tf_monitor output:

base_link to odom:

RESULTS: for base_link to odom
Chain is: base_link -> odom
Net delay     avg = -0.0313133: max = 0.0478765

odom to map RESULTS: for odom to map Chain is: odom -> map Net delay avg = -0.0281289: max = 0.000102856

Frames:

All Broadcasters:
Node: unknown_publisher 85.9467 Hz, Average Delay: -0.00285203 Max Delay: 0.339757
Node: unknown_publisher(static) 1e+08 Hz, Average Delay: 0 Max Delay: 0

base_link to map

RESULTS: for base_link to map
Chain is: base_link -> odom -> map
Net delay     avg = -0.0273669: max = 0
Frames:
Frame: base_link published by unknown_publisher Average Delay: 0.00281878 Max Delay: 0.0196072

Also attached is the tf tree for move_base and amcl.tf_tree rqt_graph

costmap_common.yaml

footprint: [[-0.5, -0.33], [-0.5, 0.33], [0.5, 0.33], [0.5, -0.33]]
footprint_padding: 0.01

robot_base_frame: base_link
update_frequency: 4.0
publish_frequency: 3.0
transform_tolerance: 0.5

resolution: 0.05

obstacle_range: 1.5
raytrace_range: 6.0

#layer definitions
static:
    map_topic: /map
    subscribe_to_updates: true

obstacles_laser:
    observation_sources: laser
    laser: {data_type: LaserScan, clearing: true, marking: true, topic: /r2000_node/scan, inf_is_valid: true}

inflation:
    inflation_radius: 1.0
cribe_to_updates: true

obstacles_laser:
    observation_sources: laser
    laser: {data_type: LaserScan, clearing: true, marking: true, topic: /r2000_node/scan, inf_is_valid: true}

inflation:
    inflation_radius: 1.0

I have not changed much in the other config files that are under husky_navigation.

Any suggestion is greatly appreciated

edit retag flag offensive close merge delete

Comments

I don't think that this is the reason for your error but obstacle_layer is misspelt as obstacles_laser in costmap_common.yaml. And the section is repeated twice.

Subodh Malgonde gravatar image Subodh Malgonde  ( 2018-10-30 04:28:51 -0600 )edit

Also, were you able to figure this one out? I have been struggling with this for the past 3 days.

Subodh Malgonde gravatar image Subodh Malgonde  ( 2018-10-30 04:28:56 -0600 )edit

5 Answers

Sort by ยป oldest newest most voted
8

answered 2018-11-01 00:56:55 -0600

Subodh Malgonde gravatar image

updated 2018-11-04 06:03:52 -0600

I was also getting the "Extrapolation into the future" errors when using move_base with amcl. I switched to a faster localization package, MIT's Particle Filter, and it fixed these errors for me.

EDIT: I just realized that the faster localization package did not fix these errors for me. I made one more change along with using another localization package. I set the global_frame of local_costmap_params.yaml to map, earlier it was set to odom. This fixed these errors. No matter what localization package I use, if I set global_frame to odom then I get these errors.

edit flag offensive delete link more

Comments

@Subodh Malgonde I also had this issue and changed to map and it worked. But is this correct?

stevemartin gravatar image stevemartin  ( 2019-01-22 05:00:35 -0600 )edit

I also changed the global_frame from odom to map and I don't have localization issues anymore.

itaouil gravatar image itaouil  ( 2020-04-05 11:03:44 -0600 )edit

Worked for me too! Thanks!! :)

JunTuck gravatar image JunTuck  ( 2020-10-27 09:33:09 -0600 )edit

Thanks man, it worked! Searched for a solution way to long before giving it a try...

Tristan9497 gravatar image Tristan9497  ( 2020-11-26 07:28:58 -0600 )edit
4

answered 2020-10-26 09:28:43 -0600

I think the most proper way to solve this problem is

increase param transform_tolerance in amcl.

Without change source code, and no need to set the global frame to map in local_costmap which may result in oscillation during navigation.

This problem bothered me from time to time in the last three months.

edit flag offensive delete link more

Comments

Which is a good value? how do you define it ?

Johart24 gravatar image Johart24  ( 2022-03-31 14:19:50 -0600 )edit

Simply increasing the transform tolerance to there is no warning should be fine, as long as the robot won't collide with obstacles.

tianb03 gravatar image tianb03  ( 2022-04-06 05:34:08 -0600 )edit

do I also increase the tolerance in the costmap.yaml?

mgrallos gravatar image mgrallos  ( 2023-01-25 20:47:58 -0600 )edit

If there is no warning then no need to increase.

tianb03 gravatar image tianb03  ( 2023-02-06 06:42:26 -0600 )edit

you can increase the tolerance in the amcl.launch

violasrq gravatar image violasrq  ( 2023-06-27 01:40:07 -0600 )edit
3

answered 2020-01-06 03:02:46 -0600

Rufus gravatar image

Changing odom to map in local_costmap_params.yaml does not tackle the root of the problem.

The error is likely caused by the frequency / timing mismatch in publishing for your tf /map -> /odom and the rest of the tree. Take a look at this answer.

In my case, I solved this by making my /map -> /odom transform valid by adding a bit of buffer time to the transform.header.stamp (i.e. making the transform slightly from the future) like so:

    map_to_odom_msg.header.stamp = now + ros::Duration(1.0);

It sure seems hacky, but it worked for me... It'd be great if someone could correct me if there's a more proper way of synchronizing tfs.

For reference, the error message stems from this line of code. I suspect that line is missing a waitForTransform but I'm no expert in the ROS source code..

edit flag offensive delete link more

Comments

It's pretty crazy that the local planner can't work without a localization system that post-dates the transforms. Even amcl has a similar parameter (transform_tolerance)

adsasine gravatar image adsasine  ( 2021-04-08 13:51:57 -0600 )edit
2

answered 2021-11-03 05:10:03 -0600

Maksim Sokolov gravatar image

Rufus was almost correct. In some cases if you using low freq. laser sensors like 10-12Hz (Sick S300), AMCL will publish transform with same freq. If you using global planner quite frequently 1-2Hz, randomly you will face with this problem.

If all this is correct for you, then local base planner has a bug for you. But the line causing this is not (108 as Rufus mentioned), but this line (base_local_planner/src/goal_functions.cpp): 113 tf.transform(global_pose, robot_pose, plan_pose.header.frame_id);

For me is difficult to understand why they did not put timeout for this line, unlike 108 (which is fine). There is no logic in this. Why they did this unblocking/instant.

So to solve this issue need to add timeout to line 113, it will look like that: tf.transform(global_pose, robot_pose, plan_pose.header.frame_id, ros::Duration(0.1));

Timeout duration will depend on your particular case, but usually 0.1 is more than you need.

edit flag offensive delete link more

Comments

This worked perfectly

hunterlineage1 gravatar image hunterlineage1  ( 2023-05-10 11:39:53 -0600 )edit
0

answered 2020-07-06 01:04:36 -0600

james P M gravatar image

This is mainly due to the update frequency in the global and local cost maps.

Try to increase the frequency in configuration .yamal file

update_frequency: 4.0 try with 10 ..

it may solve your problem

edit flag offensive delete link more

Question Tools

5 followers

Stats

Asked: 2018-10-01 02:19:18 -0600

Seen: 7,261 times

Last updated: Nov 03 '21