Navigation Plugins
There are a number of plugin interfaces for users to create their own custom applications or algorithms with. Namely, the costmap layer, planner, controller, behavior tree, and behavior plugins. A list of all known plugins are listed here below for ROS 2 Navigation. If you know of a plugin, or you have created a new plugin, please consider submitting a pull request with that information.
This file can be found and edited under sphinx_docs/plugins/index.rst.
For tutorials on creating your own plugins, please see Writing a New Costmap2D Plugin, Writing a New Behavior Tree Plugin, Writing a New Controller Plugin, Writing a New Planner Plugin, Writing a New Behavior Plugin, or Writing a New Navigator Plugin.
Behavior-Tree Navigators
Plugin Name  | 
Creator  | 
Description  | 
|---|---|---|
Steve Macenski  | 
Point-to-point navigation via a behavior tree action server  | 
|
Steve Macenski  | 
Point-through-points navigation via a behavior tree action server  | 
|
Steve Macenski  | 
Complete coverage navigation (Cartesian or GPS) via a BTs  | 
Costmap Layers
Plugin Name  | 
Creator  | 
Description  | 
|---|---|---|
Eitan Marder-Eppstein  | 
Maintains persistent 3D voxel layer using depth and laser sensor readings and raycasting to clear free space  | 
|
David Lu  | 
Uses a probabilistic model to put data from sensors that publish range msgs on the costmap  | 
|
Eitan Marder-Eppstein  | 
Gets static   | 
|
Eitan Marder-Eppstein  | 
Inflates lethal obstacles in costmap with exponential decay  | 
|
Eitan Marder-Eppstein  | 
Maintains persistent 2D costmap from 2D laser scans with raycasting to clear free space  | 
|
Steve Macenski  | 
Maintains temporal 3D sparse volumetric voxel grid with decay through sensor models  | 
|
Steve Macenski  | 
Maintains 3D occupancy grid consisting only of the most sets of measurements  | 
|
Andrey Ryzhikov  | 
Filters noise-induced standalone obstacles or small obstacles groups  | 
|
Alexander Yuen  | 
Combines the different costmap layers specified under this layer in order populate the same costmap with different isolated combinations of costmap layers  | 
Costmap Filters
Plugin Name  | 
Creator  | 
Description  | 
|---|---|---|
Alexey Merzlyakov  | 
Maintains keep-out/safety zones and preferred lanes for moving  | 
|
Alexey Merzlyakov  | 
Limits maximum velocity of robot in speed restriction areas  | 
|
Alexey Merzlyakov  | 
Enables binary (boolean) mask behavior to trigger actions.  | 
Controllers
Plugin Name  | 
Creator  | 
Description  | 
Drivetrain support  | 
|---|---|---|---|
David Lu!!  | 
A highly configurable DWA implementation with plugin interfaces  | 
Differential, Omnidirectional, Legged  | 
|
Christoph Rösmann  | 
A MPC-like controller suitable for ackermann, differential, and holonomic robots.  | 
Ackermann, Legged, Omnidirectional, Differential  | 
|
Steve Macenski  | 
A service / industrial robot variation on the pure pursuit algorithm with adaptive features.  | 
Ackermann, Legged, Differential  | 
|
Steve Macenski Aleksei Budyakov  | 
A predictive MPC controller with modular & custom cost functions that can accomplish many tasks.  | 
Differential, Omni, Ackermann  | 
|
Steve Macenski  | 
A “shim” controller to rotate to path heading before passing to main controller for tracking.  | 
Differential, Omni, model rotate in place  | 
|
Alberto Tudela  | 
A controller based on a pose-following control law to generate smooth trajectories.  | 
Differential, Omni, Legged  | 
|
Black Coffee Robotics  | 
A controller based on the vector pursuit algorithm useful for high speed accurate path tracking.  | 
Differential, Ackermann, Legged,  | 
Planners
Plugin Name  | 
Creator  | 
Description  | 
Drivetrain support  | 
|---|---|---|---|
Eitan Marder-Eppstein & Kurt Konolige  | 
A navigation function using A* or Dijkstras expansion, assumes 2D holonomic particle  | 
Differential, Omnidirectional, Legged  | 
|
  | 
Steve Macenski  | 
A SE2 Hybrid-A* implementation using either Dubin or Reeds-shepp motion models with smoother and multi-resolution query. Cars, car-like, and ackermann vehicles. Kinematically feasible.  | 
Ackermann, Differential, Omnidirectional, Legged  | 
Steve Macenski  | 
A 2D A* implementation Using either 4 or 8 connected neighborhoods with smoother and multi-resolution query  | 
Differential, Omnidirectional, Legged  | 
|
Steve Macenski  | 
An implementation of State Lattice Planner using pre-generated minimum control sets for kinematically feasible planning with any type of vehicle imaginable. Includes generator script for Ackermann, diff, omni, and legged robots.  | 
Differential, Omnidirectional, Ackermann, Legged, Arbitrary / Custom  | 
|
Anshumaan Singh  | 
An implementation of Theta* using either 4 or 8 connected neighborhoods, assumes the robot as a 2D holonomic particle  | 
Differential, Omnidirectional  | 
Smoothers
Plugin Name  | 
Creator  | 
Description  | 
|---|---|---|
Steve Macenski  | 
A simple path smoother for infeasible (e.g. 2D) planners  | 
|
Matej Vargovcik & Steve Macenski  | 
A path smoother using a constraints problem solver to optimize various criteria such as smoothness or distance from obstacles, maintaining minimum turning radius  | 
|
Steve Macenski  | 
A path smoother using a Savitzky-Golay filter to smooth the path via digital signal processing to remove noise from the path.  | 
Behaviors
Plugin Name  | 
Creator  | 
Description  | 
|---|---|---|
Eitan Marder-Eppstein  | 
A service to clear the given costmap in case of incorrect perception or robot is stuck  | 
|
Steve Macenski  | 
Rotate behavior of configurable angles to clear out free space and nudge robot out of potential local failures  | 
|
Brian Wilcox  | 
Back up behavior of configurable distance to back out of a situation where the robot is stuck  | 
|
Steve Macenski  | 
Wait behavior with configurable time to wait in case of time based obstacle like human traffic or getting more sensor data  | 
|
Joshua Wallace  | 
Drive on heading behavior with configurable distance to drive  | 
|
Joshua Wallace  | 
AssistedTeleop behavior that scales teleop commands to prevent collisions.  | 
Waypoint Task Executors
Plugin Name  | 
Creator  | 
Description  | 
|---|---|---|
Fetullah Atas  | 
A plugin to execute a wait behavior on waypoint arrivals.  | 
|
Fetullah Atas  | 
A plugin to take and save photos to specified directory on waypoint arrivals.  | 
|
Steve Macenski  | 
A plugin to wait for user input before moving onto the next waypoint.  | 
Goal Checkers
Plugin Name  | 
Creator  | 
Description  | 
|---|---|---|
David Lu!!  | 
A plugin check whether robot is within translational distance and rotational distance of goal.  | 
|
David Lu!!  | 
A plugin check whether robot is within translational distance , rotational distance of goal, and velocity threshold.  | 
|
Prabhav Saxena  | 
A plugin check whether robot is within translational distance of goal, without requiring rotational convergence.  | 
Progress Checkers
Plugin Name  | 
Creator  | 
Description  | 
|---|---|---|
David Lu!!  | 
A plugin to check whether the robot was able to move a minimum distance in a given time to make progress towards a goal  | 
|
Guillaume Doisy  | 
A plugin to check whether the robot was able to move a minimum distance or angle in a given time to make progress towards a goal  | 
Behavior Tree Nodes
Action Plugin Name  | 
Creator  | 
Description  | 
|---|---|---|
Michael Jeronimo  | 
Calls backup behavior action  | 
|
Joshua Wallace  | 
Calls drive on heading behavior action  | 
|
Joshua Wallace  | 
Calls assisted teleop behavior action  | 
|
Carl Delsey  | 
Calls clear entire costmap service  | 
|
Guillaume Doisy  | 
Calls clear costmap except region service  | 
|
Guillaume Doisy  | 
Calls clear costmap around robot service  | 
|
Michael Jeronimo  | 
Calls Nav2 planner server  | 
|
Matej Vargovcik  | 
Calls Nav2 smoother server  | 
|
Michael Jeronimo  | 
Calls Nav2 controller server  | 
|
Michael Jeronimo  | 
BT Node for other BehaviorTree.CPP BTs to call Navigation2 as a subtree action  | 
|
Carl Delsey  | 
Reinitialize AMCL to a new pose  | 
|
Carl Delsey  | 
Calls spin behavior action  | 
|
Steve Macenski  | 
Calls wait behavior action  | 
|
Francisco Martín  | 
Modifies a path making it shorter  | 
|
Matej Vargovcik  | 
Extracts a path section around robot  | 
|
Pablo Iñigo Blasco  | 
Selects the global planner based on a topic input, otherwises uses a default planner id  | 
|
Pablo Iñigo Blasco  | 
Selects the controller based on a topic input, otherwises uses a default controller id  | 
|
Pablo Iñigo Blasco  | 
Selects the goal checker based on a topic input, otherwises uses a default goal checker id  | 
|
Owen Hooper  | 
Selects the smoother based on a topic input, otherwises uses a default smoother id  | 
|
Steve Macenski  | 
Selects the progress checker based on a topic input, otherwises uses a default progress checker id  | 
|
Steve Macenski  | 
BT Node for other BehaviorTree.CPP BTs to call Nav2’s NavThroughPoses action  | 
|
Steve Macenski  | 
Removes goal poses passed or within a tolerance for culling old viapoints from path re-planning  | 
|
Tony Najjar  | 
Removes goal poses that have a footprint or point cost above a threshold.  | 
|
Steve Macenski  | 
Computes a path through a set of poses rather than a single end goal pose using the planner plugin specified  | 
|
Steve Macenski  | 
Computes a Route through a navigation graph and returns both a dense path and set of sparse route nodes and edges.  | 
|
Steve Macenski  | 
Computes a Route as above, but also actively tracks progress and triggers route contextual semantic operations.  | 
|
Pradheep Padmanabhan  | 
Cancels Nav2 controller server  | 
|
Pradheep Padmanabhan  | 
Cancels backup behavior action  | 
|
Pradheep Padmanabhan  | 
Cancels spin behavior action  | 
|
Pradheep Padmanabhan  | 
Cancels wait behavior action  | 
|
Steve Macenski  | 
Cancels ComputeAndTrackRoute action  | 
|
Joshua Wallace  | 
Cancels drive on heading behavior action  | 
|
Joshua Wallace  | 
Cancels assisted teleop behavior action  | 
|
Steve Macenski  | 
Cancels compute complete coverage  | 
|
Steve Macenski  | 
Calls coverage planner server  | 
|
Marc Morcos  | 
Extracts a pose from a path  | 
|
Steve Macenski  | 
Calls dock robot action  | 
|
Steve Macenski  | 
Calls undock robot action  | 
|
Steve Macenski  | 
Concatenates 2 paths together  | 
|
Steve Macenski  | 
Gets current pose to the blackboard  | 
|
Steve Macenski  | 
Appends a goal pose to a goals vector  | 
|
Steve Macenski  | 
Converts Route Nodes to Goals  | 
|
Steve Macenski  | 
Obtains the next N goals in a goal vector  | 
|
David Grbac  | 
Calls toggle collision monitor service  | 
Condition Plugin Name  | 
Creator  | 
Description  | 
|---|---|---|
Carl Delsey  | 
Checks if goal is reached within tol.  | 
|
Aitor Miguel Blanco  | 
Checks if goal is preempted.  | 
|
Joshua Wallace  | 
Checks if goal is preempted in the global BT context  | 
|
Carl Delsey  | 
Checks if initial pose has been set  | 
|
Michael Jeronimo  | 
Checks if robot is making progress or stuck  | 
|
Tony Najjar  | 
Checks if robot is stopped for a duration  | 
|
Steve Macenski  | 
Checks if a TF transformation is available. When succeeds returns success for subsequent calls.  | 
|
Sarthak Mittal  | 
Checks is robot has traveled a given distance.  | 
|
Sarthak Mittal  | 
Checks if a given time period has passed.  | 
|
Sarthak Mittal  | 
Checks if battery percentage is below a specified value.  | 
|
Joshua Wallace  | 
Checks if a path is valid by making sure there are no LETHAL obstacles along the path.  | 
|
Joshua Wallace  | 
Checks if the timer has expired. The timer is reset if the path gets updated.  | 
|
Joshua Wallace  | 
Checks if the specified error codes are present.  | 
|
Joshua Wallace  | 
Checks if a controller recovery could help clear the controller server error code.  | 
|
Joshua Wallace  | 
Checks if a planner recovery could help clear the planner server error code.  | 
|
Joshua Wallace  | 
Checks if a Smoother recovery could help clear the smoother server error code.  | 
|
Steve Macenski  | 
Checks if a Route recovery could help clear the route server error code.  | 
|
Alberto Tudela  | 
Checks if the battery is charging.  | 
|
Steve Macenski  | 
Checks if 2 poses are nearby to each other.  | 
|
Maurice Alexander Purnawan  | 
Checks if a pose is occupied.  | 
Decorator Plugin Name  | 
Creator  | 
Description  | 
|---|---|---|
Michael Jeronimo  | 
Throttles child node to a given rate  | 
|
Sarthak Mittal  | 
Ticks child node based on the distance traveled by the robot  | 
|
Sarthak Mittal  | 
Throttles child node to a rate based on current robot speed.  | 
|
Francisco Martín  | 
Updates the goal received via topic subscription.  | 
|
Steve Macenski  | 
Triggers nodes/subtrees below only a single time per BT run.  | 
|
Pradheep Padmanabhan  | 
Triggers child nodes if the new global path is significantly larger than the old global path on approach to the goal  | 
|
Sophia Koffler  | 
Ticks child node if the goal has been updated  | 
Control Plugin Name  | 
Creator  | 
Description  | 
|---|---|---|
Carl Delsey  | 
A variant of a sequence node that will re-tick previous children even if another child is running  | 
|
Carl Delsey  | 
Node must contain 2 children and returns success if first succeeds. If first fails, the second will be ticked. If successful, it will retry the first and then return its value  | 
|
Mohammad Haghighipanah  | 
Will tick   | 
|
Alexander Yuen  | 
A variant of a sequence node that will tick through the whole sequence even if a child returns running. On reticks of this control node, successful children will be ticked once again to prevent a stale state from being latched.  | 
|
Enjoy Robotics  | 
A variant of a sequence node that
exposes   | 
|
Enjoy Robotics  | 
Controlled through service calls to pause and resume the execution of the tree.  | 
Route Plugins
Edge Scorers
Plugin Name  | 
Creator  | 
Description  | 
|---|---|---|
DistanceScorer  | 
Steve Macenski  | 
Scores an edge’s length, optionally scaled by relative speed limits.  | 
TimeScorer  | 
Steve Macenski  | 
Scores and edge traversal time using absolute speed limits or previous traversal times.  | 
PenaltyScorer  | 
Steve Macenski  | 
Scores using a static semantic penalty.  | 
SemanticScorer  | 
Steve Macenski  | 
Scores using stored semantic data regarding the edge and/or nodes.  | 
StartPoseOrientationScorer  | 
Alex Yuen  | 
Scores based on the initial pose and start edge orientations.  | 
GoalPoseOrientationScorer  | 
Alex Yuen  | 
Scores based on the goal pose and goal edge orientations.  | 
DynamicEdgesScorer  | 
Steve Macenski  | 
Scores based on a dynamically set service cost and/or closure.  | 
Route Operations
Plugin Name  | 
Creator  | 
Description  | 
|---|---|---|
AdjustSpeedLimit  | 
Steve Macenski  | 
Adjusts robot speed limits using an edge’s semantic data.  | 
CollisionMoniter  | 
Steve Macenski  | 
Checks for collision in the immediate future which tracking a route.  | 
TimeMarker  | 
Steve Macenski  | 
Records the traversal time for an edge in the edge’s metadata.  | 
ReroutingService  | 
Steve Macenski  | 
Triggers a rereoute from an external server.  | 
TriggerEvent  | 
Steve Macenski  | 
Triggers an event based on a configurable server name.  | 
Graph File Parsers
Currently, only geojson parsing is supported.