diff --git a/_sources/configuration/packages/configuring-behavior-server.rst.txt b/_sources/configuration/packages/configuring-behavior-server.rst.txt index bea359534..e4bc2658d 100644 --- a/_sources/configuration/packages/configuring-behavior-server.rst.txt +++ b/_sources/configuration/packages/configuring-behavior-server.rst.txt @@ -7,7 +7,7 @@ Source code on Github_. .. _Github: https://github.com/ros-planning/navigation2/tree/main/nav2_behaviors -The Behavior Server implements the server for handling recovery behavior requests and hosting a vector of plugins implementing various C++ behaviors. +The Behavior Server implements the server for handling various behavior, such as recoveries and docking, requests and hosting a vector of plugins implementing various C++ behaviors. It is also possible to implement independent behavior servers for each custom behavior, but this server will allow multiple behaviors to share resources such as costmaps and TF buffers to lower incremental costs for new behaviors. Note: the wait recovery behavior has no parameters, the duration to wait is given in the action request. diff --git a/_sources/configuration/packages/configuring-bt-navigator.rst.txt b/_sources/configuration/packages/configuring-bt-navigator.rst.txt index da849cb8c..8553242f6 100644 --- a/_sources/configuration/packages/configuring-bt-navigator.rst.txt +++ b/_sources/configuration/packages/configuring-bt-navigator.rst.txt @@ -7,7 +7,7 @@ Source code on Github_. .. _Github: https://github.com/ros-planning/navigation2/tree/main/nav2_bt_navigator -The BT Navigator (Behavior Tree Navigator) module implements the NavigateToPose task interface. +The BT Navigator (Behavior Tree Navigator) module implements the NavigateToPose, NavigateThroughPoses, and other task interfaces. It is a Behavior Tree-based implementation of navigation that is intended to allow for flexibility in the navigation task and provide a way to easily specify complex robot behaviors, including recovery. diff --git a/_sources/configuration/packages/configuring-constrained-smoother.rst.txt b/_sources/configuration/packages/configuring-constrained-smoother.rst.txt index c3f79df75..941b67dfb 100644 --- a/_sources/configuration/packages/configuring-constrained-smoother.rst.txt +++ b/_sources/configuration/packages/configuring-constrained-smoother.rst.txt @@ -10,7 +10,7 @@ Source code on Github_. .. _`RoboTech Vision`: https://robotechvision.com/ A smoother plugin for nav2_smoother based on the original deprecated smoother in nav2_smac_planner and put into operational state by `RoboTech Vision`_. -Suitable for applications which need planned global path to be pushed away from obstacles and/or for Reeds-Shepp motion models. +Suitable for applications which need planned global path to be pushed away from obstacles and/or for Reeds-Shepp motion models. It optimizes for path length, smoothness, distance from obstacles, and curvature in a large Ceres-based optimization program. .. _`TruncatePathLocal BT Node`: bt-plugins/actions/TruncatePathLocal.html diff --git a/_sources/configuration/packages/configuring-controller-server.rst.txt b/_sources/configuration/packages/configuring-controller-server.rst.txt index 8e8bb15e2..9d2073603 100644 --- a/_sources/configuration/packages/configuring-controller-server.rst.txt +++ b/_sources/configuration/packages/configuring-controller-server.rst.txt @@ -9,6 +9,7 @@ Source code on Github_. The Controller Server implements the server for handling the controller requests for the stack and host a map of plugin implementations. It will take in path and plugin names for controller, progress checker and goal checker to use and call the appropriate plugins. +It also hosts the local costmap. Parameters ********** diff --git a/_sources/configuration/packages/configuring-costmaps.rst.txt b/_sources/configuration/packages/configuring-costmaps.rst.txt index 638188243..8cc478ec4 100644 --- a/_sources/configuration/packages/configuring-costmaps.rst.txt +++ b/_sources/configuration/packages/configuring-costmaps.rst.txt @@ -7,7 +7,7 @@ Source code on Github_. .. _Github: https://github.com/ros-planning/navigation2/tree/main/nav2_costmap_2d -The Costmap 2D package implements a 2D grid-based costmap for environmental representations and a number of sensor processing plugins. +The Costmap 2D package implements a 2D grid-based costmap for environmental representations and a number of sensor processing plugins (AI outputs, depth sensor obstacle buffering, semantic information, etc). It is used in the planner and controller servers for creating the space to check for collisions or higher cost areas to negotiate around. Costmap2D ROS Parameters diff --git a/_sources/configuration/packages/configuring-dwb-controller.rst.txt b/_sources/configuration/packages/configuring-dwb-controller.rst.txt index f3f2ac42f..de74372d1 100644 --- a/_sources/configuration/packages/configuring-dwb-controller.rst.txt +++ b/_sources/configuration/packages/configuring-dwb-controller.rst.txt @@ -9,7 +9,7 @@ Source code on Github_. The DWB controller is the default controller. It is a fork of `David Lu's controller `_ -modified for ROS 2. +modified for ROS 2 using the Dynamic Window Approach. Controller ********** diff --git a/_sources/configuration/packages/configuring-mppic.rst.txt b/_sources/configuration/packages/configuring-mppic.rst.txt index a1a2ee176..c41f3bb51 100644 --- a/_sources/configuration/packages/configuring-mppic.rst.txt +++ b/_sources/configuration/packages/configuring-mppic.rst.txt @@ -351,6 +351,8 @@ Ackermann Motion Model Constraint Critic ----------------- +This critic penalizes trajectories that have components outside of the set dynamic or kinematic constraints + :cost_weight: ============== =========================== @@ -376,6 +378,8 @@ Constraint Critic Goal Angle Critic ----------------- +This critic incentivizes navigating to achieve the angle of the goal posewhen in reasonable proximity to goal + :cost_weight: ============== =========================== @@ -412,6 +416,8 @@ Goal Angle Critic Goal Critic ----------- +This critic incentivizes navigating spatially towards the goal when in reasonable proximity to goal + :cost_weight: ============== =========================== @@ -448,6 +454,8 @@ Goal Critic Obstacles Critic ---------------- +This critic incentivizes navigating away from obstacles and critical collisions using either a circular robot point-check or full SE2 footprint check. + :critical_weight: ============== =========================== @@ -550,6 +558,8 @@ Obstacles Critic Path Align Critic ----------------- +This critic incentivizes aligning with the global path, if relevant. It does not implement path following behavior. + :cost_weight: ============== =========================== @@ -619,6 +629,8 @@ Path Align Critic Path Angle Critic ----------------- +This critic penalizes trajectories at a high relative angle to the path. This helps the robot make sharp turns when necessary due to large accumulated angular errors. + :cost_weight: ============== =========================== @@ -689,6 +701,8 @@ Path Angle Critic Path Follow Critic ------------------ +This critic incentivizes making progress along the path. This is what drives the robot forward along the path. + :cost_weight: ============== =========================== @@ -736,6 +750,8 @@ Path Follow Critic Prefer Forward Critic --------------------- +This critic incentivizes moving in the forward direction, rather than reversing. + :cost_weight: ============== =========================== @@ -772,6 +788,8 @@ Prefer Forward Critic Twirling Critic --------------- +This critic penalizes unnecessary 'twisting' with holonomic vehicles. It adds a constraint on the rotation angle to keep it consistent. + :cost_weight: ============== =========================== diff --git a/_sources/configuration/packages/configuring-navfn.rst.txt b/_sources/configuration/packages/configuring-navfn.rst.txt index f72336815..114a51ff5 100644 --- a/_sources/configuration/packages/configuring-navfn.rst.txt +++ b/_sources/configuration/packages/configuring-navfn.rst.txt @@ -7,7 +7,7 @@ Source code on Github_. .. _Github: https://github.com/ros-planning/navigation2/tree/main/nav2_navfn_planner -The Navfn Planner plugin implements a wavefront Dijkstra or A* expanded planner. +The Navfn Planner plugin implements a wavefront Dijkstra or A* expanded holonomic planner. ```` is the corresponding planner plugin ID selected for this type. diff --git a/_sources/configuration/packages/configuring-planner-server.rst.txt b/_sources/configuration/packages/configuring-planner-server.rst.txt index 777c50e50..1cac857de 100644 --- a/_sources/configuration/packages/configuring-planner-server.rst.txt +++ b/_sources/configuration/packages/configuring-planner-server.rst.txt @@ -9,6 +9,7 @@ Source code on Github_. The Planner Server implements the server for handling the planner requests for the stack and host a map of plugin implementations. It will take in a goal and a planner plugin name to use and call the appropriate plugin to compute a path to the goal. +It also hosts the global costmap. Parameters ********** diff --git a/_sources/configuration/packages/configuring-thetastar.rst.txt b/_sources/configuration/packages/configuring-thetastar.rst.txt index eb76219c9..acd4e506f 100644 --- a/_sources/configuration/packages/configuring-thetastar.rst.txt +++ b/_sources/configuration/packages/configuring-thetastar.rst.txt @@ -7,7 +7,7 @@ Theta Star Planner .. .. _Github: https://github.com/ros-planning/navigation2/tree/main/nav2_theta_star_planner -Theta Star Planner implements the Theta* path planner meant to plan any-angled paths using A*. +Theta Star Planner implements the Theta* path planner meant to plan any-angled line-segment focused paths using A*. For the below example the planner took ~46ms (averaged value) to compute the path of 87.5m - diff --git a/_sources/configuration/packages/configuring-velocity-smoother.rst.txt b/_sources/configuration/packages/configuring-velocity-smoother.rst.txt index 7280ded42..ab4844263 100644 --- a/_sources/configuration/packages/configuring-velocity-smoother.rst.txt +++ b/_sources/configuration/packages/configuring-velocity-smoother.rst.txt @@ -9,6 +9,7 @@ Source code on Github_. The ``nav2_velocity_smoother`` is a package containing a lifecycle-component node for smoothing velocities sent by Nav2 to robot controllers. The aim of this package is to implement velocity, acceleration, and deadband smoothing from Nav2 to reduce wear-and-tear on robot motors and hardware controllers by smoothing out the accelerations/jerky movements that might be present with some local trajectory planners' control efforts. +It can also interpolate velocity commands at higher rates than the controller server publishes. See the package's README for more information. diff --git a/_sources/configuration/packages/costmap-plugins/denoise.rst.txt b/_sources/configuration/packages/costmap-plugins/denoise.rst.txt index 8b593c09f..5718ea95a 100644 --- a/_sources/configuration/packages/costmap-plugins/denoise.rst.txt +++ b/_sources/configuration/packages/costmap-plugins/denoise.rst.txt @@ -3,6 +3,8 @@ Denoise Layer Parameters ======================== +This layer attempts to remove simple noise that may exist in a costmap's layers due to sensor noise or discrete raycasting errors. + ```` is the corresponding plugin name selected for this type. :````.enabled: diff --git a/_sources/configuration/packages/costmap-plugins/inflation.rst.txt b/_sources/configuration/packages/costmap-plugins/inflation.rst.txt index b195982b3..582871529 100644 --- a/_sources/configuration/packages/costmap-plugins/inflation.rst.txt +++ b/_sources/configuration/packages/costmap-plugins/inflation.rst.txt @@ -3,6 +3,8 @@ Inflation Layer Parameters ========================== +This layer places an exponential decay functions around obstacles to increase cost to traverse near collision. It also places a lethal cost around obstacles within the robot's fully inscribed radius - even if a robot is non-circular for optimized first-order collision checking. + ```` is the corresponding plugin name selected for this type. diff --git a/_sources/configuration/packages/costmap-plugins/obstacle.rst.txt b/_sources/configuration/packages/costmap-plugins/obstacle.rst.txt index e9ad5d460..d52f3d272 100644 --- a/_sources/configuration/packages/costmap-plugins/obstacle.rst.txt +++ b/_sources/configuration/packages/costmap-plugins/obstacle.rst.txt @@ -3,6 +3,8 @@ Obstacle Layer Parameters ========================= +This costmap layer implements a plugin that uses 2D raycasting for 2D lidars, depth, or other sensors. It contains a 2D costmap model within it that manages the planning space by the parameters specified below. + ```` is the corresponding plugin name selected for this type. ```` is the corresponding observation source name for that sources parameters. diff --git a/_sources/configuration/packages/costmap-plugins/range.rst.txt b/_sources/configuration/packages/costmap-plugins/range.rst.txt index ff0b98df2..1d789d14a 100644 --- a/_sources/configuration/packages/costmap-plugins/range.rst.txt +++ b/_sources/configuration/packages/costmap-plugins/range.rst.txt @@ -3,6 +3,8 @@ Range Sensor Parameters ======================= +This costmap layer implements a plugin that processes sonar, IR, or other 1-D sensors for collision avoidance. + ```` is the corresponding plugin name selected for this type. :````.enabled: diff --git a/_sources/configuration/packages/costmap-plugins/static.rst.txt b/_sources/configuration/packages/costmap-plugins/static.rst.txt index 4cad056eb..2b8efe957 100644 --- a/_sources/configuration/packages/costmap-plugins/static.rst.txt +++ b/_sources/configuration/packages/costmap-plugins/static.rst.txt @@ -3,6 +3,8 @@ Static Layer Parameters ======================= +This implements a costmap layer taking in a map from either SLAM or ``map_server`` (or other) to place into the costmap. It resizes the costmap to its size and places the static obstacles on the planning space. + ```` is the corresponding plugin name selected for this type. :````.enabled: diff --git a/_sources/configuration/packages/costmap-plugins/voxel.rst.txt b/_sources/configuration/packages/costmap-plugins/voxel.rst.txt index c5fbabffe..2a7b0105b 100644 --- a/_sources/configuration/packages/costmap-plugins/voxel.rst.txt +++ b/_sources/configuration/packages/costmap-plugins/voxel.rst.txt @@ -3,6 +3,8 @@ Voxel Layer Parameters ====================== +This costmap layer implements a plugin that uses 3D raycasting for depth, 3D, or other sensors. It contains a 3D environmental model within it that manages the planning space and squashes down to 2D for planning and control by the parameters specified below. + ```` is the corresponding plugin name selected for this type. ```` is the corresponding observation source name for that sources parameters. diff --git a/_sources/configuration/packages/nav2_controller-plugins/simple_progress_checker.rst.txt b/_sources/configuration/packages/nav2_controller-plugins/simple_progress_checker.rst.txt index 36984da13..410dd7ccc 100644 --- a/_sources/configuration/packages/nav2_controller-plugins/simple_progress_checker.rst.txt +++ b/_sources/configuration/packages/nav2_controller-plugins/simple_progress_checker.rst.txt @@ -3,7 +3,7 @@ SimpleProgressChecker ===================== -Checks whether the robot has made progress. +Checks whether the robot has made positional progress. Parameters ********** diff --git a/_sources/configuration/packages/smac/configuring-smac-2d.rst.txt b/_sources/configuration/packages/smac/configuring-smac-2d.rst.txt index b9658edd9..1f96e6a34 100644 --- a/_sources/configuration/packages/smac/configuring-smac-2d.rst.txt +++ b/_sources/configuration/packages/smac/configuring-smac-2d.rst.txt @@ -8,6 +8,8 @@ Smac 2D Planner :alt: Paths generated by the Smac 2D-A* :width: 640px +This planner implements a cost-aware holonomic A* algorithm within the Smac Planner framework sharing the same code and behaviors as the Hybrid-A* and State Lattice planners. + ```` is the corresponding planner plugin ID selected for this type. Parameters diff --git a/_sources/configuration/packages/smac/configuring-smac-hybrid.rst.txt b/_sources/configuration/packages/smac/configuring-smac-hybrid.rst.txt index 66cc8fd36..ec840dda6 100644 --- a/_sources/configuration/packages/smac/configuring-smac-hybrid.rst.txt +++ b/_sources/configuration/packages/smac/configuring-smac-hybrid.rst.txt @@ -8,6 +8,8 @@ Smac Hybrid-A* Planner :alt: Paths generated by the Smac Hybrid-A* :width: 640px +This plugin implements a cost-aware Hybrid-A* global path planner with motion primitives proportionally sized to the minimum required to leave a user's costmap cell allowing for finite moves. + ```` is the corresponding planner plugin ID selected for this type. Parameters diff --git a/_sources/configuration/packages/smac/configuring-smac-lattice.rst.txt b/_sources/configuration/packages/smac/configuring-smac-lattice.rst.txt index 0fb895743..5a155a9f3 100644 --- a/_sources/configuration/packages/smac/configuring-smac-lattice.rst.txt +++ b/_sources/configuration/packages/smac/configuring-smac-lattice.rst.txt @@ -8,6 +8,8 @@ Smac State Lattice Planner :alt: Paths generated by the Smac State Lattice :width: 640px +This planner implements a generic state lattice global path planner using precomputed, offline minimum control sets. The package also contains a python utility for computing minimum control sets based on minimum curvature constraints, in-place rotations, and omnidirectional moves. Though, any other minimum control set may be used as long as it follows the file format specification in the package's README file. + ```` is the corresponding planner plugin ID selected for this type. Note: State Lattice does not have the costmap downsampler due to the minimum control sets being tied with map resolutions on generation. The minimum turning radius is also not a parameter in State Lattice since this was specified at the minimum control set pre-computation phase. See the Smac Planner package to generate custom control sets for your vehicle or use one of our pre-generated examples. diff --git a/configuration/packages/configuring-behavior-server.html b/configuration/packages/configuring-behavior-server.html index f1a84c760..2485776ee 100644 --- a/configuration/packages/configuring-behavior-server.html +++ b/configuration/packages/configuring-behavior-server.html @@ -1005,7 +1005,7 @@

Behavior Server

Source code on Github.

-

The Behavior Server implements the server for handling recovery behavior requests and hosting a vector of plugins implementing various C++ behaviors. +

The Behavior Server implements the server for handling various behavior, such as recoveries and docking, requests and hosting a vector of plugins implementing various C++ behaviors. It is also possible to implement independent behavior servers for each custom behavior, but this server will allow multiple behaviors to share resources such as costmaps and TF buffers to lower incremental costs for new behaviors.

Note: the wait recovery behavior has no parameters, the duration to wait is given in the action request. Note: pre-Rolling/Humble this was the Recovery server, not behavior server. Launch files, behaviors and tests were all renamed.

diff --git a/configuration/packages/configuring-bt-navigator.html b/configuration/packages/configuring-bt-navigator.html index 8e0c3df37..a3100bba9 100644 --- a/configuration/packages/configuring-bt-navigator.html +++ b/configuration/packages/configuring-bt-navigator.html @@ -1005,7 +1005,7 @@

Behavior-Tree Navigator

Source code on Github.

-

The BT Navigator (Behavior Tree Navigator) module implements the NavigateToPose task interface. +

The BT Navigator (Behavior Tree Navigator) module implements the NavigateToPose, NavigateThroughPoses, and other task interfaces. It is a Behavior Tree-based implementation of navigation that is intended to allow for flexibility in the navigation task and provide a way to easily specify complex robot behaviors, including recovery.

Consider checking out the Groot - Interacting with Behavior Trees tutorial for using Groot to visualize and modify behavior trees.

diff --git a/configuration/packages/configuring-constrained-smoother.html b/configuration/packages/configuring-constrained-smoother.html index 8cc4e7caf..7811c3ae0 100644 --- a/configuration/packages/configuring-constrained-smoother.html +++ b/configuration/packages/configuring-constrained-smoother.html @@ -1006,7 +1006,7 @@

Constrained smoother

Source code on Github.

A smoother plugin for nav2_smoother based on the original deprecated smoother in nav2_smac_planner and put into operational state by RoboTech Vision. -Suitable for applications which need planned global path to be pushed away from obstacles and/or for Reeds-Shepp motion models.

+Suitable for applications which need planned global path to be pushed away from obstacles and/or for Reeds-Shepp motion models. It optimizes for path length, smoothness, distance from obstacles, and curvature in a large Ceres-based optimization program.

Important note: Constrained smoother uses a rather heavy optimization algorithm and thus is suggested to be used on a periodically truncated path. TruncatePathLocal BT Node can be used for achieving a proper path length and DistanceController BT Node can be used for achieving periodicity.

Following image depicts how Constrained Smoother can improve quality of an input path (cyan, generated by an outdated version of Smac Planner, intentionally not configured optimally to highlight the power of the smoother), diff --git a/configuration/packages/configuring-controller-server.html b/configuration/packages/configuring-controller-server.html index b92a554ba..6bd6d2fb8 100644 --- a/configuration/packages/configuring-controller-server.html +++ b/configuration/packages/configuring-controller-server.html @@ -1006,7 +1006,8 @@

Controller Server

Source code on Github.

The Controller Server implements the server for handling the controller requests for the stack and host a map of plugin implementations. -It will take in path and plugin names for controller, progress checker and goal checker to use and call the appropriate plugins.

+It will take in path and plugin names for controller, progress checker and goal checker to use and call the appropriate plugins. +It also hosts the local costmap.

Parameters

diff --git a/configuration/packages/configuring-costmaps.html b/configuration/packages/configuring-costmaps.html index e229baa8f..88fa07de4 100644 --- a/configuration/packages/configuring-costmaps.html +++ b/configuration/packages/configuring-costmaps.html @@ -1005,7 +1005,7 @@

Costmap 2D

Source code on Github.

-

The Costmap 2D package implements a 2D grid-based costmap for environmental representations and a number of sensor processing plugins. +

The Costmap 2D package implements a 2D grid-based costmap for environmental representations and a number of sensor processing plugins (AI outputs, depth sensor obstacle buffering, semantic information, etc). It is used in the planner and controller servers for creating the space to check for collisions or higher cost areas to negotiate around.

Costmap2D ROS Parameters

diff --git a/configuration/packages/configuring-dwb-controller.html b/configuration/packages/configuring-dwb-controller.html index 88c46808f..6729033f2 100644 --- a/configuration/packages/configuring-dwb-controller.html +++ b/configuration/packages/configuring-dwb-controller.html @@ -1007,7 +1007,7 @@

Source code on Github.

The DWB controller is the default controller. It is a fork of David Lu’s controller -modified for ROS 2.

+modified for ROS 2 using the Dynamic Window Approach.

Controller

diff --git a/configuration/packages/configuring-mppic.html b/configuration/packages/configuring-mppic.html index db45bef2b..e071e65c6 100644 --- a/configuration/packages/configuring-mppic.html +++ b/configuration/packages/configuring-mppic.html @@ -1596,6 +1596,7 @@

Ackermann Motion Model

Constraint Critic

+

This critic penalizes trajectories that have components outside of the set dynamic or kinematic constraints

cost_weight
@@ -1641,6 +1642,7 @@

Constraint Critic

Goal Angle Critic

+

This critic incentivizes navigating to achieve the angle of the goal posewhen in reasonable proximity to goal

cost_weight

@@ -1706,6 +1708,7 @@

Goal Angle Critic

Goal Critic

+

This critic incentivizes navigating spatially towards the goal when in reasonable proximity to goal

cost_weight

@@ -1771,6 +1774,7 @@

Goal Critic

Obstacles Critic

+

This critic incentivizes navigating away from obstacles and critical collisions using either a circular robot point-check or full SE2 footprint check.

critical_weight

@@ -1956,6 +1960,7 @@

Obstacles Critic

Path Align Critic

+

This critic incentivizes aligning with the global path, if relevant. It does not implement path following behavior.

cost_weight

@@ -2081,6 +2086,7 @@

Path Align Critic

Path Angle Critic

+

This critic penalizes trajectories at a high relative angle to the path. This helps the robot make sharp turns when necessary due to large accumulated angular errors.

cost_weight

@@ -2206,6 +2212,7 @@

Path Angle Critic

Path Follow Critic

+

This critic incentivizes making progress along the path. This is what drives the robot forward along the path.

cost_weight

@@ -2291,6 +2298,7 @@

Path Follow Critic

Prefer Forward Critic

+

This critic incentivizes moving in the forward direction, rather than reversing.

cost_weight

@@ -2356,6 +2364,7 @@

Prefer Forward Critic

Twirling Critic

+

This critic penalizes unnecessary ‘twisting’ with holonomic vehicles. It adds a constraint on the rotation angle to keep it consistent.

cost_weight

diff --git a/configuration/packages/configuring-navfn.html b/configuration/packages/configuring-navfn.html index 468be9061..21aab88e0 100644 --- a/configuration/packages/configuring-navfn.html +++ b/configuration/packages/configuring-navfn.html @@ -1005,7 +1005,7 @@