Note: This tutorial assumes that you have completed the previous tutorials: Set up and test Optimization, Incorporate customized Obstacles, Incorporate dynamic obstacles, Costmap conversion.
(!) Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags.

Track and include dynamic obstacles via costmap_converter

Description: In this tutorial you will learn how to utilize the costmap converter to easily track dynamic obstacles based on costmap updates.

Keywords: Trajectory Optimization Local Planner Navigation Dynamic Obstacles Tracking Costmap-Conversion

Tutorial Level: INTERMEDIATE

Next Tutorial: Frequently Asked Questions

Introduction

Before you proceed, make sure that you are familiar with the costmap_converter package in general and how it is utilized in the teb_local_planner (refer to the tutorial Costmap Conversion).

The costmap_converter package provides a plugin called costmap_converter::CostmapToDynamicObstacles which tries to detect dynamic obstacles based on the temporal evolution of the local costmap. The plugin also has an underlying parameter static_converter_plugin which can be set to one of the conventional (static obstacle) costmap_converter plugins, e.g. costmap_converter::CostmapToPolygonsDBSMCCH.

You also need to make sure to enable dynamic obstacle planning in the teb_local_planner as described here.

Testing the obstacle tracker

Install the teb_local_planner_tutorials package or clone the repository from the github repository to your catkin workspace.

Now open a terminal and invoke

roslaunch teb_local_planner_tutorials dyn_obst_costmap_conversion.launch

You should now see the tracking example and results similiar to: Dynamic obstacle tracking via costmap_converter

You can check the corresponding launch and config files in the source code repository for further details.

Note, the parameters might not be perfect (also for the underlying Kalman filter). We have not spent much time on tuning parameters in the costmap_converter package. So if you have improvements, we would be happy if you can open an issue or merge request at the costmap_converter or teb_local_planner_tutorials issue board.

Corridor example

The following example demonstrates how the robot navigates through a corridor with moving obstacles.

Close the previous program and run the following command:

roslaunch teb_local_planner_tutorials dyn_obst_corridor_scenario.launch

The complete navigation setup for a differential drive is loaded. Specify a navigation goal in rviz by providing a 2D Nav Goal at the other end of the corridor.

You should see something like: Corridor navigation with dynamic obstacles

Again, you can investigate the corresponding launch and config files in the source code repository for further details.

Remarks

The planner currently assumes that obstacles are moving mainly with constant velocity. This assumption is meaningful in many applications. However, in a true random-walk scenario, the planner performance can be worse in comparison to a planning configuration in which those obstacles are treated as static ones (teb_local_planner parameter include_dynamic_obstacles=false).

Wiki: teb_local_planner/Tutorials/Track and include dynamic obstacles via costmap_converter (last edited 2018-06-15 17:19:53 by ChristophRoesmann)