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.

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.

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.

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.

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.

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.

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.

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

  • The C++ API is stable
  • The ROS API is stable

Published Topics

~<name>/global_plan (nav_msgs/Path)
  • The portion of the global plan that the local planner is currently attempting to follow. Used primarily for visualization purposes.
~<name>/local_plan (nav_msgs/Path)
  • The local plan or trajectory that scored the highest on the last cycle. Used primarily for visualization purposes.

Subscribed Topics

odom (nav_msgs/Odometry)
  • Odometry information that gives the local planner the current speed of the robot. The velocity information in this message is assumed to be in the same coordinate frame as the robot_base_frame of the costmap contained within the TrajectoryPlannerROS object. See the costmap_2d package for information about the robot_base_frame parameter.

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)

  • The x acceleration limit of the robot in meters/sec^2
~<name>/acc_lim_y (double, default: 2.5)
  • The y acceleration limit of the robot in meters/sec^2
~<name>/acc_lim_th (double, default: 3.2)
  • The rotational acceleration limit of the robot in radians/sec^2
~<name>/max_vel_trans (double, default: 0.55)
  • The absolute value of the maximum translational velocity for the robot in m/s
~<name>/min_vel_trans (double, default: 0.1)
  • The absolute value of the minimum translational velocity for the robot in m/s
~<name>/max_vel_x (double, default: 0.55)
  • The maximum x velocity for the robot in m/s.
~<name>/min_vel_x (double, default: 0.0)
  • The minimum x velocity for the robot in m/s, negative for backwards motion.
~<name>/max_vel_y (double, default: 0.1)
  • The maximum y velocity for the robot in m/s
~<name>/min_vel_y (double, default: -0.1)
  • The minimum y velocity for the robot in m/s
~<name>/max_rot_vel (double, default: 1.0)
  • The absolute value of the maximum rotational velocity for the robot in rad/s
~<name>/min_rot_vel (double, default: 0.4)
  • The absolute value of the minimum rotational velocity for the robot in rad/s

Goal Tolerance Parameters

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

  • The tolerance in radians for the controller in yaw/rotation when achieving its goal
~<name>/xy_goal_tolerance (double, default: 0.10)
  • The tolerance in meters for the controller in the x & y distance when achieving a goal
~<name>/latch_xy_goal_tolerance (bool, default: false)
  • If goal tolerance is latched, if the robot ever reaches the goal xy location it will simply rotate in place, even if it ends up outside the goal tolerance while it is doing so.

Forward Simulation Parameters

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

  • The amount of time to forward-simulate trajectories in seconds
~<name>/sim_granularity (double, default: 0.025)
  • The step size, in meters, to take between points on a given trajectory
~<name>/vx_samples (integer, default: 3)
  • The number of samples to use when exploring the x velocity space
~<name>/vy_samples (integer, default: 10)
  • The number of samples to use when exploring the y velocity space
~<name>/vth_samples (integer, default: 20)
  • The number of samples to use when exploring the theta velocity space
~<name>/controller_frequency (double, default: 20.0)
  • The frequency at which this controller will be called in Hz. Uses searchParam to read the parameter from parent namespaces if not set in the namespace of the controller. For use with move_base, this means that you only need to set its "controller_frequency" parameter and can safely leave this one unset.

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)

  • The weighting for how much the controller should stay close to the path it was given
~<name>/goal_distance_bias (double, default: 24.0)
  • The weighting for how much the controller should attempt to reach its local goal, also controls speed
~<name>/occdist_scale (double, default: 0.01)
  • The weighting for how much the controller should attempt to avoid obstacles
~<name>/forward_point_distance (double, default: 0.325)
  • The distance from the center point of the robot to place an additional scoring point, in meters
~<name>/stop_time_buffer (double, default: 0.2)
  • The amount of time that the robot must stop before a collision in order for a trajectory to be considered valid in seconds
~<name>/scaling_speed (double, default: 0.25)
  • The absolute value of the velocity at which to start scaling the robot's footprint, in m/s
~<name>/max_scaling_factor (double, default: 0.2)
  • The maximum factor to scale the robot's footprint by
~<name>/publish_cost_grid (bool, default: false)
  • Whether or not to publish the cost grid that the planner will use when planning. When true, a sensor_msgs/PointCloud2 will be available on the ~<name>/cost_cloud topic. Each point cloud represents the cost grid and has a field for each individual scoring function component as well as the overall cost for each cell, taking the scoring parameters into account.

Oscillation Prevention Parameters

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

  • How far the robot must travel in meters before oscillation flags are reset

Global Plan Parameters

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

  • Defines whether or not to eat up the plan as the robot moves along the path. If set to true, points will fall off the end of the plan once the robot moves 1 meter past them.

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

  • The C++ API is stable. However, it is recommended that you use the DWAPlannerROS wrapper instead of using the dwa_local_planner::TrajectoryPlanner on its own.

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)