Show EOL distros: 

navigation: amcl | base_local_planner | carrot_planner | clear_costmap_recovery | costmap_2d | dwa_local_planner | fake_localization | global_planner | map_server | move_base | move_base_msgs | move_slow_and_clear | nav_core | navfn | robot_pose_ekf | rotate_recovery | voxel_grid

Package Summary

A path planner library and node.

  • Maintainer status: maintained
  • Maintainer: David V. Lu!! <davidvlu AT gmail DOT com>, Michael Ferguson <mferguson AT fetchrobotics DOT com>
  • Author: David Lu!!
  • License: BSD
  • Source: git https://github.com/ros-planning/navigation.git (branch: hydro-devel)
navigation: amcl | base_local_planner | carrot_planner | clear_costmap_recovery | costmap_2d | dwa_local_planner | fake_localization | global_planner | map_server | move_base | move_base_msgs | move_slow_and_clear | nav_core | navfn | robot_pose_ekf | rotate_recovery | voxel_grid

Package Summary

A path planner library and node.

  • Maintainer status: maintained
  • Maintainer: David V. Lu!! <davidvlu AT gmail DOT com>, Michael Ferguson <mfergs7 AT gmail DOT com>, Aaron Hoy <ahoy AT fetchrobotics DOT com>
  • Author: David Lu!!
  • License: BSD
  • Source: git https://github.com/ros-planning/navigation.git (branch: indigo-devel)
navigation: amcl | base_local_planner | carrot_planner | clear_costmap_recovery | costmap_2d | dwa_local_planner | fake_localization | global_planner | map_server | move_base | move_base_msgs | move_slow_and_clear | nav_core | navfn | robot_pose_ekf | rotate_recovery | voxel_grid

Package Summary

A path planner library and node.

  • Maintainer status: maintained
  • Maintainer: David V. Lu!! <davidvlu AT gmail DOT com>, Michael Ferguson <mferguson AT fetchrobotics DOT com>
  • Author: David Lu!!
  • License: BSD
  • Source: git https://github.com/ros-planning/navigation.git (branch: jade-devel)
navigation: amcl | base_local_planner | carrot_planner | clear_costmap_recovery | costmap_2d | dwa_local_planner | fake_localization | global_planner | map_server | move_base | move_base_msgs | move_slow_and_clear | nav_core | navfn | robot_pose_ekf | rotate_recovery | voxel_grid

Package Summary

A path planner library and node.

  • Maintainer status: maintained
  • Maintainer: David V. Lu!! <davidvlu AT gmail DOT com>, Michael Ferguson <mfergs7 AT gmail DOT com>, Aaron Hoy <ahoy AT fetchrobotics DOT com>
  • Author: David Lu!!
  • License: BSD
  • Source: git https://github.com/ros-planning/navigation.git (branch: kinetic-devel)
navigation: amcl | base_local_planner | carrot_planner | clear_costmap_recovery | costmap_2d | dwa_local_planner | fake_localization | global_planner | map_server | move_base | move_base_msgs | move_slow_and_clear | nav_core | navfn | robot_pose_ekf | rotate_recovery | voxel_grid

Package Summary

A path planner library and node.

  • Maintainer status: maintained
  • Maintainer: David V. Lu!! <davidvlu AT gmail DOT com>, Michael Ferguson <mfergs7 AT gmail DOT com>, Aaron Hoy <ahoy AT fetchrobotics DOT com>
  • Author: David Lu!!
  • License: BSD
  • Source: git https://github.com/ros-planning/navigation.git (branch: lunar)
navigation: amcl | base_local_planner | carrot_planner | clear_costmap_recovery | costmap_2d | dwa_local_planner | fake_localization | global_planner | map_server | move_base | move_base_msgs | move_slow_and_clear | nav_core | navfn | rotate_recovery | voxel_grid

Package Summary

A path planner library and node.

  • Maintainer status: maintained
  • Maintainer: David V. Lu!! <davidvlu AT gmail DOT com>, Michael Ferguson <mfergs7 AT gmail DOT com>, Aaron Hoy <ahoy AT fetchrobotics DOT com>
  • Author: David Lu!!
  • License: BSD
  • Source: git https://github.com/ros-planning/navigation.git (branch: melodic-devel)
navigation: amcl | base_local_planner | carrot_planner | clear_costmap_recovery | costmap_2d | dwa_local_planner | fake_localization | global_planner | map_server | move_base | move_base_msgs | move_slow_and_clear | nav_core | navfn | rotate_recovery | voxel_grid

Package Summary

A path planner library and node.

  • Maintainer status: maintained
  • Maintainer: David V. Lu!! <davidvlu AT gmail DOT com>, Michael Ferguson <mfergs7 AT gmail DOT com>, Aaron Hoy <ahoy AT fetchrobotics DOT com>
  • Author: David Lu!!
  • License: BSD
  • Source: git https://github.com/ros-planning/navigation.git (branch: noetic-devel)

Overview

This package provides an implementation of a fast, interpolated global planner for navigation. This class adheres to the nav_core::BaseGlobalPlanner interface specified in the nav_core package. It was built as a more flexible replacement to navfn, which in turn is based on NF1.

Examples of Different Parameterizations

Standard Behavior

All parameters default. GlobalPlanner.png

Grid Path

use_grid_path=True GridPath.png Path follows the grid boundaries.

Simple Potential Calculation

use_quadratic=False Nonquad.png Slightly different calculation for the potential. Note that the original potential calculation from navfn is a quadratic approximation. Of what, the maintainer of this package has no idea.

A* Path

use_dijkstra=False AStar.png Note that a lot less of the potential has been calculated (indicated by the colored areas). This is indeed faster than using Dijkstra's, but has the effect of not necessarily producing the same paths. Another thing to note is that in this implementation of A*, the potentials are computed using 4-connected grid squares, while the path found by tracing the potential gradient from the goal back to the start uses the same grid in an 8-connected fashion. Thus, the actual path found may not be fully optimal in an 8-connected sense. (Also, no visited-state set is tracked while computing potentials, as in a more typical A* implementation, because such is unnecessary for 4-connected grids). To see the differences between the behavior of Dijkstra's and the behavior of A*, consider the following example.

Dijkstra's

Dijkstra.png

A*

AStar2.png

Old Navfn Behavior

old_navfn_behavior=True For reproducing paths just like NavFn did. OldNavFn.png

Note:

  • The start of the path does not match the actual start location.
  • The very end of the path moves along grid lines.
  • All of the coordinates are slightly shifted by half a grid cell

Orientation filter

As a post-processing step, an orientation can be added to the points on the path. With use of the ~orientation_mode parameter (dynamic reconfigure), the following orientation modes can be set:

  • None=0 (No orientations added except goal orientation)

  • Forward=1 (Positive x axis points along path, except for the goal orientation)

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

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

  • Backward=4 (Negative x axis points along the path, except for the goal orientation)

  • Leftward=5 (Positive y axis points along the path, except for the goal orientation)

  • Rightward=6 (Negative y axis points along the path, except for the goal orientation)

The orientation of point i is calculated using the positions of i - orientation_window_size and `i + orientation_window_size`. The window size can be altered to smoothen the orientation calculation.

ROS API

Published Topics

~<name>/plan (nav_msgs/Path)
  • The last plan computed, published every time the planner computes a new path, and used primarily for visualization purposes.

Parameters

~<name>/allow_unknown (bool, default: true)
  • Specifies whether or not to allow the planner to create plans that traverse unknown space. NOTE: if you are using a layered costmap_2d costmap with a voxel or obstacle layer, you must also set the track_unknown_space param for that layer to be true, or it will convert all your unknown space to free space (which planner will then happily go right through).
~<name>/default_tolerance (double, default: 0.0)
  • A tolerance on the goal point for the planner. The planner will attempt to create a plan that is as close to the specified goal as possible but no further than default_tolerance away.
~<name>/visualize_potential (bool, default: false)
  • Specifies whether or not to visualize the potential area computed via a PointCloud2.
~<name>/use_dijkstra (bool, default: true)
  • If true, use dijkstra's algorithm. Otherwise, A*.
~<name>/use_quadratic (bool, default: true)
  • If true, use the quadratic approximation of the potential. Otherwise, use a simpler calculation.
~<name>/use_grid_path (bool, default: false)
  • If true, create a path that follows the grid boundaries. Otherwise, use a gradient descent method.
~<name>/old_navfn_behavior (bool, default: false)
  • If for some reason, you want global_planner to exactly mirror the behavior of navfn, set this to true (and use the defaults for the other boolean parameters)
~<name>/lethal_cost (int, default: 253)
  • Lethal Cost (dynamic reconfigure)
~<name>/neutral_cost (int, default: 50)
  • Neutral Cost (dynamic reconfigure)
~<name>/cost_factor (double, default: 3.)
  • Factor to multiply each cost from costmap by (dynamic reconfigure)
~<name>/publish_potential (bool, default: True)
  • Publish Potential Costmap (dynamic reconfigure)
~<name>/orientation_mode (int, default: 0)
  • How to set the orientation of each point (None=0, Forward=1, Interpolate=2, ForwardThenInterpolate=3, Backward=4, Leftward=5, Rightward=6) (dynamic reconfigure)
~<name>/orientation_window_size (int, default: 1)
  • What window to use to determine the orientation based on the position derivative specified by the orientation mode (dynamic reconfigure)
~<name>/outline_map (bool, default: true)
  • Outlines the global costmap with lethal obstacles. For the usage of a non static (rolling window) global costmap this needs to be set to false

Wiki: global_planner (last edited 2021-02-12 13:30:14 by TristanSchwörer)