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

Dynamic obstacles and teb_local_planner

asked 2019-07-16 07:49:09 -0600

schizzz8 gravatar image

Hi all,

When addressing the problem of dynamic obstacles avoidance with my mobile base, I came across this solution. The mentioned tutorial assumes some node is publishing costmap_converter/ObstacleMsgs on a pre-defined topic. In that case, a toy python node is publishing a fake obstacle moving in y direction.

What I'm interested in, is in having a proper way to detect dynamic obstacles and let the teb_local_planner consider them for planning. In the main wiki page, the documentation of the include_dynamic_obstacles parameter states that:

~<name>/include_dynamic_obstacles (bool, default: false)

    If this parameter is set to true, the motion of obstacles with non-zero velocity (provided via user-supplied obstacles on topic ~/obstacles or obtained from the costmap_converter) is predicted and considered during optimization via a constant velocity model. New

Therefore I'd be very interested to know how to obtain dynamic obstacles from the costmap_converter.

Please, can someone show me how to do that?

Thanks.

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
2

answered 2019-07-16 08:23:13 -0600

croesmann gravatar image

updated 2019-07-16 08:47:36 -0600

Hi,

the teb_local_planner considers two different sources for obstacle information:

  • local costmap (costmap_2d)
  • costmap_converter/ObstacleMsgs

The most common option for using the navigation stack with teb_local_planner is to use costmap information. However, the costmap information does not contain any time information and therefore only provides a static view of the environment in each sampling interval. In addition, ObstacleMsgs can be used to provide obstacle information on the associated topic.

Tracking obstacles and predicting their motion (or simplified: their current velocity) usually requires non-trivial algorithms operating with raw sensor data. A proper robotic system therefore includes a separate tracking node that provides the planner with this type of information (e.g., via message api).

However, a simple tracking algorithm has been integrated into the costmap_converter package to identify dynamic obstacles that are based on changes in the costmap and not on raw data. The advantage is that it can be used with minimal configuration and any sensor sources supported by costmap_2d, but with lower accuracy and delay. You can check if the performance is suitable for your setup and application.
See this link for a tutorial on how to use this feature.

Cheers, Christoph

Edit: The current implementation uses a constant-velocity model to predict the obstacles' future movement.

edit flag offensive delete link more

Question Tools

2 followers

Stats

Asked: 2019-07-16 07:49:09 -0600

Seen: 1,169 times

Last updated: Jul 16 '19