Enea,

On Thu, Apr 22, 2010 at 2:10 AM, Enea Scioni <enea.scioni@student.unife.it> wrote:

Hi all ROS users and developers!
I'm running the navigation stack on my mobile platform, when I receive some
ROS Warning from move_base node (or better, from costmap_2d_ros).
Infact, my warnings are:
1)[ WARN] 1271924926.290219000: Costmap2DROS transform timeout. Current
time: 1271924926.2901, global_pose stamp: 1271924925.4903, tolerance:
0.3000;

If this warning prints only at startup, its probably not a huge deal as the system is settling. However, if you're seeing it print continuously it means that the transform from the map->base_link frame is over 0.3 seconds out-of-date (0.8 seconds in the example above) and the navigation stack is warning you that it is unable to get the robot's pose in the global frame. There are two ways to solve this, one much better than the other:

1) Good Solution: Track down the latency in your transform tree and find out why the transform from map->base_link can be so old. A tool that will help with this is tf_monitor.

2) Bad Solution: You can up the tolerance parameter for the costmap, allowing it to use older transforms. This isn't actually solving the problem and means that your robot may navigate unsafely because collision checks will occur in the wrong places if the robot is moving.
 
published  by costmap_2d_ros.cpp, around line 763, after a fail check up
about global_pose timeout;
2)[ WARN] 1271924927.223672000: The scan observation buffer has not been
updated for 1.07 seconds, and it should be updated every 0.20 seconds,
published each second, where the last update time is always the same, so
every warning increase the "delay" time (it means that the scan observation
buffer is not updated everytime I suppose..); this warning is published by
observation_buffer.cpp around line 155;

This implies that laser scans are not coming into the navigation stack correctly. Verify your topic names, rates, connections between nodes, and transforms from the laser frame to the odometric frame.
 
3)(consequence) I receive the warning published by move_base.cpp, line 476:
Sensor date is out of date, we're not going to allow commanding of the base
for safety.

The subscribed topic is: [ INFO] 1271926474.239322000: Subscribed to Topics
(costmap_2d_ros): scan,
where scan is my topic name about sensor_msgs::LaserScan data. (I use an
sick522, I published scan data using sicktoolbox_wrapper node).

Besides, I'm able to visualize all sensor data and tf stream using rviz as
well, so I've some trouble to recognize the cause of my problem.

Can you try visualizing all your sensor data in the odometric and map frames to see if your transforms are set up correctly? If things work in the base_link frame but not the global frames, there's something wrong. Do you receive any warning from message notifiers?
 

I'm using also:
-amcl node;
-map server node;
-driver for my platform ( cmd_vel and publish pose messages
(nav_msgs::Odometry).
-Another node that publish tf data.

Anybody could tell me where I can check for resolve this problem?

Thank you!

Enea Scioni

Hopefully, this gives you a few things to check. Let us know how it goes.

Hope all is well,

Eitan


--
View this message in context: http://ros-users.122217.n3.nabble.com/costmap-2d-observation-buffer-warnings-tp742425p742425.html
Sent from the ROS-Users mailing list archive at Nabble.com.

------------------------------------------------------------------------------
_______________________________________________
ros-users mailing list
ros-users@lists.sourceforge.net
https://lists.sourceforge.net/lists/listinfo/ros-users
_______________________________________________
ros-users mailing list
ros-users@code.ros.org
https://code.ros.org/mailman/listinfo/ros-users