0
$\begingroup$

Rosanswers logo

Hello,

After migration from Foxy to Galactic I got the following issue:

[planner_server-18] [INFO] [1643728496.934987109] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Lookup would require extrapolation into the past.  Requested time 0.200000 but the earliest data is at time 1643728495.556496, when looking up transform from frame [base_link] to frame [map]

The timestamp 0.2000 corresponds to the param transform_timeoutof the slam_toolbox(if I change this param, I get its value displayed in the message instead of the 0.2000) and is not updated, as if the TF was not updated.

This message get printed again and again, preventing my others nodes to works correctly. Sometime the issue disappears spontaneously after several seconds (but then get other messages).

The TF tree looks like this, the TF seems never updated: image description

This is exactly the same issue as described by this user but on Reddit.

The TF map<->odom is published by the slam_toolbox in localization mode.

The Tf is regularly published in /tf topic and looks like this:

transforms:
- header:
    stamp:
      sec: 0
      nanosec: 200000000
    frame_id: map
  child_frame_id: odom
  transform:
    translation:
      x: 0.0
      y: 0.0
      z: 0.0
    rotation:
      x: 0.0
      y: 0.0
      z: 0.0
      w: 1.0

What could be the root cause and how to solve this ?


Originally posted by PatoInso on ROS Answers with karma: 109 on 2022-02-01

Post score: 0


Original comments

Comment by PatoInso on 2022-02-02:
ok, this issue and my other one are somehow linked. Under Galactic, the slam_toolbox sets the timestamp of the TF map-odom with the timestamp of the last laserscan + transform_timeout offset (https://github.com/SteveMacenski/slam_toolbox/blob/f449abf039dd15cd0be719ceeb039533b487329c/src/slam_toolbox_common.cpp#L234). Under Foxy, it was timestamped with now() + transform_timeout offset (https://github.com/SteveMacenski/slam_toolbox/blob/e2f0a71c5475b4e7d32085a18aa89c36f014e28b/src/slam_toolbox_common.cpp#L233).

I replaced in Galactic the laser timestamp by now(), and my two issues got resolved... definitively some time issue

Comment by PatoInso on 2022-02-02:
Also, slam_toolbox misses a lot of laserscan msg. A RCLCPP_INFO in the laser callback shows that sometimes, it is not called for several seconds (up to 10sec), while the scans are published at a solid 20Hz in /scan topic

$\endgroup$

1 Answer 1

0
$\begingroup$

Rosanswers logo

Ok, not so sure of the mechanism behind this, but it was related to timestamps issues caused by delays in my laserscan pipeline:

  • A first delay introduced by a Message Filter that cached some laserscan message to sync them in my scan merger. So when a new scan was received, the previous scan was typically outputed (so 1 sample of delay)
  • The struct of my laser_odometry package was so that the the TF odom <-> base_link was computed and timestamped with the latest laserscan, but was only published 100ms later (a structure with a process() then a spin_some() that processed obsolete data)

Solving this two issues and reducing the delay, so that the timestamp of the TF remains close of now(), solved it for me.


Originally posted by PatoInso with karma: 109 on 2022-02-08

This answer was ACCEPTED on the original site

Post score: 0

$\endgroup$

Your Answer

By clicking “Post Your Answer”, you agree to our terms of service and acknowledge you have read our privacy policy.

Not the answer you're looking for? Browse other questions tagged or ask your own question.