(!) 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.

Frequently Asked Questions

Description: This page tries to answer and explain frequently asked questions regarding the teb_local_planner.

Tutorial Level: INTERMEDIATE

Question: Why does my robot navigate too close to walls and/or cuts corners?

Short Answer: Define/Increase the inflation radius in your costmap configuration.

Long Answer: At first glance, parameter min_obstacle_dist could be increased, but this could lead to an undesired navigation behavior in small hallways or doors (see Gaps in the trajectory). The local planner "follows" a moving virtual goal on the global plan. Therefore locations of intermediate global plan position of the global plan significantly influence the spatial behavior of the local plan. By defining an inflation radius the global planner prefers plans with minimum cost and hence plans with a higher separation from walls. Note, the teb_local_planner itself does not take the inflation radius into account. The resulting motion is time-optimal w.r.t. the virtual goal. If you wish to stick much more to following the global path, refer to Global path following. If your robot hits walls, you should really increase min_obstacle_dist or setup an appropriate footprint (refer to this tutorial).

Global path following

Question: Why doesn't my robot follow the global plan properly?

Short Answer: The default planning criterion is time-optimality, but you can easily customize it.

Long Answer: By default, following the global plan is achieved by targeting a moving virtual goal taken from intermediate global plan positions within the scope of the local costmap (in particular a subset of the global plan with length max_global_plan_lookahead_dist, but never beyond the boundary of the local costmap). The local plan between the current robot position and the virtual goal is subject to optimization, e.g. to minimization of the transition time. If the robot should prefer to follow the global plan instead of reaching the (virtual) goal in minimum time, a first strategy could be to significantly reduce max_global_plan_lookahead_dist. But this approach is NOT recommended, since it reduces the prediction/planning horizon and weakens the capabilities of avoiding obstacles (the virtual goal is fixed in current versions and thus not subject to optimization). Instead, in order to account for global path following, the teb_local_planner is able to inject attractors (via-points) along the global plan (distance between attractors: global_plan_viapoint_sep, attraction strength: weight_viapoint). Refer to the tutorial Following the Global Plan (Via-Points) for more details.

Gaps in the trajectory

Question: What is the cause of the following behavior?

Obstacle distance chosen too high

Short Answer: Parameter min_obstacle_dist is chosen too high.

Long Answer: Just an exmaple: if the parameter min_obstacle_dist is set to a distance of 1m, the robot tries to keep a distance of at least 1m to each side of the door. But if the width of the door is just 1m, the optimizer will still plan through the center of the door (local minimum: both forces resulting from obstacle avoidance are negating each other in the center). But in order to satisfy the minimum distance to each pose the optimizer moves the planned poses along the trajectory (therefore the gap!). This case is not detected by the planner currently. However if there would be any collision, the feasiblity check would probably detect that. If you really have to keep large distances to obstacles you cannot drive through that door. Then you must also configure your global planner (robot footprint, inflation etc.) properly to avoid global planning through it. Otherwise reduce the minimum distance until the trajectory does not contain any large gap.

If you are using a robot footprint model other than the point model also check that the expansion ist correct and not too large (the footprint is published via markers).

Following global plan backwards

Question: Why does the robot switches directions in case the goal pose is behind the robot and the orientation of the start and goal pose are similar?

Short Answer: In case the goal is inside the local costmap it should work out of the box. Otherwise, it is up to the global planner how intermediate orientations are chosen.

Long Answer: The teb_local_planner chooses poses from the global plan as intermediate goals until the actual goal (last pose of the global plan) is reached. However, since not all global planners are specifying a valid orientation but the position only (e.g., navfn), the teb_local_planner overwrites global plan orientations by default (parameter global_plan_overwrite_orientation). It implements a forward oriented motion, such that the orientation of a pose always points to the consecutive pose. This forward mode is sufficient for many applications. However, in some cases, you might want to have a different behavior. Please refer to the following figure, in which the robot should just back up along the corridor. The goal orientation is chosen similar to the start orientation:

Intermediate global plan orientations in default mode

You might agree, that changing the direction is not appropriate in this case. However, you can set global_plan_overwrite_orientation=false to consider orientations from the global plan. The more recent global_planner which replaced navfn provides multiple strategies for choosing the orientation. At the time of writing, the following strategies are implemented:

  • None (No orientations added except goal orientation)

  • Forward (Orientations point to the next point on the path)

  • Interpolate (Orientations are a linear blend of start and goal pose)

  • ForwardThenInterpolate (Forward orientation until last straightaway, then a linear blend until the goal pose).

The following figure shows how the teb_local_planner behaves in the previous scenario in case the Interpolate mode is selected:

Intermediate global plan orientations in interpolate mode

The Interpolate mode behaves perfect here. However, let's assume the corridor includes curves, in that case Interpolate is not what we want, since it just evaluates the start and the goal orientations. Backward would be appropriate (Forward + pi), however, this is not yet implemented in the global_planner package (at least until this pull request is merged). In practical applications we probably sometimes need Forward and sometimes Backward mode, so you need to come up with a smarter strategy, e.g. a corridor detection (note, just the global planner can do this with the global map). Currently, you need to write your own global planner for this, or you might extend the global planner package.

Notice, teb_local_planner parameter allow_init_with_backwards_motion needs to be set to true such that the trajectories between the start and the current intermediate goal (e.g., obtained from sampling distinctive topologies) are also initialized with backward orientations (only in case the goal is behind the start with similar orientation). This also allows the robot to back up correctly within the local cost map even if all but the last intermediate orientations are forward oriented.

Computation time

Question: Computing the local plan takes too long on my robot. Can I speed up the planning?

Short Answer: The planning is subject to optimization which is computationally demanding. However, the computation time is influenced by many parameters and a satifying navigation behavior can often be achieved with dedicated self-tuned parameter sets.

Long Answer: The following list provides a brief overview and implications of parameters that influence the computation time significantly.

Local costmap_2d configuration (a rolling window is highly recommended!):

width/height

Size of the local costmap: implies maximum trajectory length and how many occupied cells are taken into account (major impact on computation time, but if too small: short prediction/planning horizon reduces the degrees of freedom, e.g. for obstacle avoidance).

resolution

Resolution of the local costmap: a fine resolution (small values) implies many obstacles subject to optimization (major impact on computation time).

Obstacle/Costmap parameters of the teb_local_planner:

costmap_obstacles_behind_robot_dist

Since the local costmap is centered at the current robot position, not all obstacles behind the robot must be taken into account. To allow safe turning behaviors, this value should be non-zero. A higher value includes more obstacles for optimization.

obstacle_poses_affected

Number of nearest neighbors on the trajectory taken into account (increases the number of distance calculations for each obstacle). For small obstacles and point obstacles, this value can be small (<10). Increase the value again if the trajectory is not smooth enough close to obstacles.

footprint_model

The robot footprint model influces the runtime, since the complexity of distance calculation is increased (avoid a polygon footprint if possible). Refer to this tutorial. The footprint can be visualized by activating the teb markers in rviz.

The costmap-obstacle preprocessing can also be moved into another thread by registering/activating a costmap_converter plugin. Those plugins aim to transform the costmap cells (many point obstacles) to geometric primitives (points, lines, polygons). Also redundant cells or cells of the interior of an obstacle can be filtered. But up to now, available conversion plugins are still experimental and there are many more efficient ways to pre-process the costmap. Refer to this tutorial. If someone is interested to contribute, further plugins can be easily integrated using pluginlib.

Trajectory representation:

dt_ref

Determines the desired resolution of the trajectory: small values lead to a fine resolution and thus a better approximation of the kinodynamic model, but many points must be optimized (major impact on optimization time). Too high values (> 0.6s) can lead to trajectories that are not feasible anymore due to the poor approximation of the kinodynamic model (especially in case of car-like robots).

max_global_plan_lookahead_dist

Limits the distance to the virtual goal (along the global plan) and thus the number of poses subject to optimization (temporal distance between poses approx dt_ref seconds). But the length is also bounded by the local costmap size

Optimization parameters:

no_inner_iterations

Number of solver calls in each "outer-iteration". Highly influences the computation time but also the quality of the solution.

no_outer_iterations

Number of outer iterations for each sampling interval that specifies how often the trajectory is resized to account for dt_ref and how often associations between obstacles and planned poses are renewed. Also the solver is called each iteration. The value significantly influences the computation time as well as convergence properties.

weight_acc_lim_*

You can ignore acceleration limits by setting the weight to 0.0. By doing so the complexity of the optimization and hence the computation time can be reduced.

Parallel planning of alternative trajectories:

enable_homotopy_class_planning

If you only have timing problems in case multiple alternatives are computed, set the alternative planning to false or first restrict the number of alternatives using max_number_classes.

max_number_classes

Restrict the number of alternative trajectories that are subject to optimization. Often 2 alternatives are sufficient (avoid obstacle on the left or right side).

There are further parameters regarding the sampling of the roadmap_graph (roadmap_graph_*) that might be adjusted if the computation time is still too long with homotopy class planning enabled and max. 2 alternatives.

Wiki: teb_local_planner/Tutorials/Frequently Asked Questions (last edited 2018-06-20 17:56:30 by ChristophRoesmann)