Wiki

New in navigation ROS Diamondback, navigation_experimental ROS CTurtle

  Show EOL distros: 

navigation_experimental: assisted_teleop | dwa_local_planner | goal_passer | isolated_point_filter | move_slow_and_clear | pose_base_controller | pose_follower | sbpl_lattice_planner | sbpl_recovery | twist_recovery

Package Summary

This package provides an implementation of the Dynamic Window Approach to local robot navigation on a plane. Given a global plan to follow and a costmap, the local planner produces velocity commands to send to a mobile base. This package supports any robot who's footprint can be represented as a convex polygon or cicrle, and exposes its configuration as ROS parameters that can be set in a launch file. The parameters for this planner are also dynamically reconfigurable. This package's ROS wrapper adheres to the BaseLocalPlanner interface specified in the nav_core package.

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

Package Summary

This package provides an implementation of the Dynamic Window Approach to local robot navigation on a plane. Given a global plan to follow and a costmap, the local planner produces velocity commands to send to a mobile base. This package supports any robot who's footprint can be represented as a convex polygon or cicrle, and exposes its configuration as ROS parameters that can be set in a launch file. The parameters for this planner are also dynamically reconfigurable. This package's ROS wrapper adheres to the BaseLocalPlanner interface specified in the nav_core package.

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

Package Summary

This package provides an implementation of the Dynamic Window Approach to local robot navigation on a plane. Given a global plan to follow and a costmap, the local planner produces velocity commands to send to a mobile base. This package supports any robot who's footprint can be represented as a convex polygon or cicrle, and exposes its configuration as ROS parameters that can be set in a launch file. The parameters for this planner are also dynamically reconfigurable. This package's ROS wrapper adheres to the BaseLocalPlanner interface specified in the nav_core package.

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

Package Summary

This package provides an implementation of the Dynamic Window Approach to local robot navigation on a plane. Given a global plan to follow and a costmap, the local planner produces velocity commands to send to a mobile base. This package supports any robot who's footprint can be represented as a convex polygon or cicrle, and exposes its configuration as ROS parameters that can be set in a launch file. The parameters for this planner are also dynamically reconfigurable. This package's ROS wrapper adheres to the BaseLocalPlanner interface specified in the nav_core package.

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

This package provides an implementation of the Dynamic Window Approach to local robot navigation on a plane. Given a global plan to follow and a costmap, the local planner produces velocity commands to send to a mobile base. This package supports any robot who's footprint can be represented as a convex polygon or cicrle, and exposes its configuration as ROS parameters that can be set in a launch file. The parameters for this planner are also dynamically reconfigurable. This package's ROS wrapper adheres to the BaseLocalPlanner interface specified in the nav_core package.

  • Maintainer status: maintained
  • Maintainer: David V. Lu!! <davidvlu AT gmail DOT com>, Michael Ferguson <mferguson AT fetchrobotics DOT com>
  • Author: Eitan Marder-Eppstein, contradict@gmail.com
  • License: BSD
  • Source: git https://github.com/ros-planning/navigation.git (branch: hydro-devel)
pr2_navigation: dwa_local_planner | laser_tilt_controller_filter | pr2_move_base | pr2_navigation_config | pr2_navigation_global | pr2_navigation_local | pr2_navigation_perception | pr2_navigation_self_filter | pr2_navigation_slam | pr2_navigation_teleop | semantic_point_annotator

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

This package provides an implementation of the Dynamic Window Approach to local robot navigation on a plane. Given a global plan to follow and a costmap, the local planner produces velocity commands to send to a mobile base. This package supports any robot who's footprint can be represented as a convex polygon or cicrle, and exposes its configuration as ROS parameters that can be set in a launch file. The parameters for this planner are also dynamically reconfigurable. This package's ROS wrapper adheres to the BaseLocalPlanner interface specified in the nav_core package.

  • 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: Eitan Marder-Eppstein, contradict@gmail.com
  • 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

This package provides an implementation of the Dynamic Window Approach to local robot navigation on a plane. Given a global plan to follow and a costmap, the local planner produces velocity commands to send to a mobile base. This package supports any robot who's footprint can be represented as a convex polygon or cicrle, and exposes its configuration as ROS parameters that can be set in a launch file. The parameters for this planner are also dynamically reconfigurable. This package's ROS wrapper adheres to the BaseLocalPlanner interface specified in the nav_core package.

  • Maintainer status: maintained
  • Maintainer: David V. Lu!! <davidvlu AT gmail DOT com>, Michael Ferguson <mferguson AT fetchrobotics DOT com>
  • Author: Eitan Marder-Eppstein, contradict@gmail.com
  • 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

pr2_navigation: dwa_local_planner | laser_tilt_controller_filter | pr2_move_base | pr2_navigation_config | pr2_navigation_global | pr2_navigation_local | pr2_navigation_perception | pr2_navigation_self_filter | pr2_navigation_slam | pr2_navigation_teleop | semantic_point_annotator

Package Summary

This package provides an implementation of the Dynamic Window Approach to local robot navigation on a plane. Given a global plan to follow and a costmap, the local planner produces velocity commands to send to a mobile base. This package supports any robot who's footprint can be represented as a convex polygon or cicrle, and exposes its configuration as ROS parameters that can be set in a launch file. The parameters for this planner are also dynamically reconfigurable. This package's ROS wrapper adheres to the BaseLocalPlanner interface specified in the nav_core package.

  • 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: Eitan Marder-Eppstein, contradict@gmail.com
  • 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

This package provides an implementation of the Dynamic Window Approach to local robot navigation on a plane. Given a global plan to follow and a costmap, the local planner produces velocity commands to send to a mobile base. This package supports any robot who's footprint can be represented as a convex polygon or cicrle, and exposes its configuration as ROS parameters that can be set in a launch file. The parameters for this planner are also dynamically reconfigurable. This package's ROS wrapper adheres to the BaseLocalPlanner interface specified in the nav_core package.

  • 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: Eitan Marder-Eppstein, contradict@gmail.com
  • 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

pr2_navigation: dwa_local_planner | laser_tilt_controller_filter | pr2_move_base | pr2_navigation_config | pr2_navigation_global | pr2_navigation_local | pr2_navigation_perception | pr2_navigation_self_filter | pr2_navigation_slam | pr2_navigation_teleop | semantic_point_annotator

Package Summary

This package provides an implementation of the Dynamic Window Approach to local robot navigation on a plane. Given a global plan to follow and a costmap, the local planner produces velocity commands to send to a mobile base. This package supports any robot who's footprint can be represented as a convex polygon or cicrle, and exposes its configuration as ROS parameters that can be set in a launch file. The parameters for this planner are also dynamically reconfigurable. This package's ROS wrapper adheres to the BaseLocalPlanner interface specified in the nav_core package.

  • 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: Eitan Marder-Eppstein, contradict@gmail.com
  • 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

pr2_navigation: dwa_local_planner | laser_tilt_controller_filter | pr2_move_base | pr2_navigation_config | pr2_navigation_global | pr2_navigation_local | pr2_navigation_perception | pr2_navigation_self_filter | pr2_navigation_slam | pr2_navigation_teleop | semantic_point_annotator

Package Summary

This package provides an implementation of the Dynamic Window Approach to local robot navigation on a plane. Given a global plan to follow and a costmap, the local planner produces velocity commands to send to a mobile base. This package supports any robot who's footprint can be represented as a convex polygon or cicrle, and exposes its configuration as ROS parameters that can be set in a launch file. The parameters for this planner are also dynamically reconfigurable. This package's ROS wrapper adheres to the BaseLocalPlanner interface specified in the nav_core package.

  • 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: Eitan Marder-Eppstein, contradict@gmail.com
  • License: BSD
  • Source: git https://github.com/ros-planning/navigation.git (branch: noetic-devel)

Overview

The dwa_local_planner package provides a controller that drives a mobile base in the plane. This controller serves to connect the path planner to the robot. Using a map, the planner creates a kinematic trajectory for the robot to get from a start to a goal location. Along the way, the planner creates, at least locally around the robot, a value function, represented as a grid map. This value function encodes the costs of traversing through the grid cells. The controller's job is to use this value function to determine dx,dy,dtheta velocities to send to the robot.

local_plan.png

The basic idea of the Dynamic Window Approach (DWA) algorithm is as follows:

  1. Discretely sample in the robot's control space (dx,dy,dtheta)
  2. For each sampled velocity, perform forward simulation from the robot's current state to predict what would happen if the sampled velocity were applied for some (short) period of time.
  3. Evaluate (score) each trajectory resulting from the forward simulation, using a metric that incorporates characteristics such as: proximity to obstacles, proximity to the goal, proximity to the global path, and speed. Discard illegal trajectories (those that collide with obstacles).
  4. Pick the highest-scoring trajectory and send the associated velocity to the mobile base.
  5. Rinse and repeat.

Useful references:

DWAPlannerROS

The dwa_local_planner::DWAPlannerROS object is a wrapper for a dwa_local_planner::DWAPlanner object that exposes its functionality as a C++ ROS Wrapper. It operates within a ROS namespace (assumed to be name from here on) specified on initialization. It adheres to the nav_core::BaseLocalPlanner interface found in the nav_core package.

Example creation of a dwa_local_planner::DWAPlannerROS object:

   1 #include <tf/transform_listener.h>
   2 #include <costmap_2d/costmap_2d_ros.h>
   3 #include <dwa_local_planner/dwa_planner_ros.h>
   4 
   5 ...
   6 
   7 tf::TransformListener tf(ros::Duration(10));
   8 costmap_2d::Costmap2DROS costmap("my_costmap", tf);
   9 
  10 dwa_local_planner::DWAPlannerROS dp;
  11 dp.initialize("my_dwa_planner", &tf, &costmap);

API Stability

Published Topics

~<name>/global_plan (nav_msgs/Path) ~<name>/local_plan (nav_msgs/Path)

Subscribed Topics

odom (nav_msgs/Odometry)

Parameters

There are a large number of ROS Parameters that can be set to customize the behavior of the dwa_local_planner::DWAPlannerROS wrapper. These parameters are grouped into several categories: robot configuration, goal tolerance, forward simulation, trajectory scoring, oscillation prevention, and global plan. Most of these parameters can also be changed using dynamic_reconfigure to facilitate tuning the local planner in a running system.

Robot Configuration Parameters

~<name>/acc_lim_x (double, default: 2.5)

~<name>/acc_lim_y (double, default: 2.5) ~<name>/acc_lim_th (double, default: 3.2) ~<name>/max_vel_trans (double, default: 0.55) ~<name>/min_vel_trans (double, default: 0.1) ~<name>/max_vel_x (double, default: 0.55) ~<name>/min_vel_x (double, default: 0.0) ~<name>/max_vel_y (double, default: 0.1) ~<name>/min_vel_y (double, default: -0.1) ~<name>/max_rot_vel (double, default: 1.0) ~<name>/min_rot_vel (double, default: 0.4)

Goal Tolerance Parameters

~<name>/yaw_goal_tolerance (double, default: 0.05)

~<name>/xy_goal_tolerance (double, default: 0.10) ~<name>/latch_xy_goal_tolerance (bool, default: false)

Forward Simulation Parameters

~<name>/sim_time (double, default: 1.7)

~<name>/sim_granularity (double, default: 0.025) ~<name>/vx_samples (integer, default: 3) ~<name>/vy_samples (integer, default: 10) ~<name>/vth_samples (integer, default: 20) ~<name>/controller_frequency (double, default: 20.0)

Trajectory Scoring Parameters

The cost function used to score each trajectory is in the following form:

cost =
  path_distance_bias * (distance to path from the endpoint of the trajectory in meters)
  + goal_distance_bias * (distance to local goal from the endpoint of the trajectory in meters)
  + occdist_scale * (maximum obstacle cost along the trajectory in obstacle cost (0-254))

~<name>/path_distance_bias (double, default: 32.0)

~<name>/goal_distance_bias (double, default: 24.0) ~<name>/occdist_scale (double, default: 0.01) ~<name>/forward_point_distance (double, default: 0.325) ~<name>/stop_time_buffer (double, default: 0.2) ~<name>/scaling_speed (double, default: 0.25) ~<name>/max_scaling_factor (double, default: 0.2) ~<name>/publish_cost_grid (bool, default: false)

Oscillation Prevention Parameters

~<name>/oscillation_reset_dist (double, default: 0.05)

Global Plan Parameters

~<name>/prune_plan (bool, default: true)

C++ API

For C++ level API documentation on the base_local_planner::TrajectoryPlannerROS class, please see the following page: DWAPlannerROS C++ API

DWAPlanner

The dwa_local_planner::DWAPlanner provides implementations of the DWA and Trajectory Rollout algorithms described earlier. In order to use the dwa_local_planner::DWAPlanner with ROS, please use the DWAPlannerROS wrapper. It is not recommended to use the dwa_local_planner::DWAPlanner on its own.

API Stability

C++ API

For C++ level API documentation on the dwa_local_planner::DWAPlanner class, please see the following page: DWAPlanner C++ API

Wiki: dwa_local_planner (last edited 2020-10-28 13:26:08 by JashMota)