Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
Public Types | Public Member Functions | List of all members
nav2_route::RouteOperation Class Referenceabstract

A plugin interface to perform an operation while tracking the route such as triggered from the graph file when a particular node is achieved, edge is entered or exited. The API also supports triggering arbitrary operations when a status has changed (e.g. any node is achieved) or at a regular frequency on query set at a fixed rate of tracker_update_rate. Operations can request the system to reroute and avoid certain edges. Example operations may be to: reroute when blocked or at a required rate (though may want to use BTs instead), adjust speed limits, wait, call an external service or action to perform a task such as calling an elevator or opening an automatic door, etc. Operations may throw nav2_core::OperationFailed exceptions in failure cases. More...

#include <nav2_route/include/nav2_route/interfaces/route_operation.hpp>

Inheritance diagram for nav2_route::RouteOperation:
Inheritance graph
[legend]

Public Types

using Ptr = std::shared_ptr< nav2_route::RouteOperation >
 

Public Member Functions

 RouteOperation ()=default
 Constructor.
 
virtual ~RouteOperation ()=default
 Destructor.
 
virtual void configure (const rclcpp_lifecycle::LifecycleNode::SharedPtr node, std::shared_ptr< nav2_costmap_2d::CostmapSubscriber > costmap_subscriber, const std::string &name)=0
 Configure the operation plugin (get params, create interfaces, etc) More...
 
virtual std::string getName ()=0
 An API to get the name of a particular operation for triggering, query or logging. More...
 
virtual RouteOperationType processType ()
 Indication of which type of route operation this plugin is. Whether it is be called by the graph's nodes or edges, whether it should be triggered at any status change, or whether it should be called constantly on any query. By default, it will create operations that are only called when a graph's node or edge requests it. Note that On Query, On Status Change, and On Graph are mutually exclusive since each operation type is merely a subset of the previous level's specificity. More...
 
virtual OperationResult perform (NodePtr node_achieved, EdgePtr edge_entered, EdgePtr edge_exited, const Route &route, const geometry_msgs::msg::PoseStamped &curr_pose, const Metadata *mdata=nullptr)=0
 The main route operation API to perform an operation when triggered. The return value indicates if the route operation is requesting rerouting when returning true. Could be if this operation is checking if a route is in collision or operation failed (to open a door, for example) and thus this current route is now invalid. More...
 

Detailed Description

A plugin interface to perform an operation while tracking the route such as triggered from the graph file when a particular node is achieved, edge is entered or exited. The API also supports triggering arbitrary operations when a status has changed (e.g. any node is achieved) or at a regular frequency on query set at a fixed rate of tracker_update_rate. Operations can request the system to reroute and avoid certain edges. Example operations may be to: reroute when blocked or at a required rate (though may want to use BTs instead), adjust speed limits, wait, call an external service or action to perform a task such as calling an elevator or opening an automatic door, etc. Operations may throw nav2_core::OperationFailed exceptions in failure cases.

Definition at line 65 of file route_operation.hpp.

Member Function Documentation

◆ configure()

virtual void nav2_route::RouteOperation::configure ( const rclcpp_lifecycle::LifecycleNode::SharedPtr  node,
std::shared_ptr< nav2_costmap_2d::CostmapSubscriber costmap_subscriber,
const std::string &  name 
)
pure virtual

Configure the operation plugin (get params, create interfaces, etc)

Parameters
nodeA node to use
namethe plugin's name set by the param file that may need to be used to correlate an operation instance to the navigation graph operation calls

Implemented in nav2_route::RouteOperationClient< SrvT >, nav2_route::RouteOperationClient< std_srvs::srv::Trigger >, nav2_route::TimeMarker, nav2_route::ReroutingService, nav2_route::CollisionMonitor, and nav2_route::AdjustSpeedLimit.

◆ getName()

virtual std::string nav2_route::RouteOperation::getName ( )
pure virtual

An API to get the name of a particular operation for triggering, query or logging.

Returns
the plugin's name

Implemented in nav2_route::TimeMarker, nav2_route::ReroutingService, nav2_route::CollisionMonitor, nav2_route::AdjustSpeedLimit, nav2_route::RouteOperationClient< SrvT >, and nav2_route::RouteOperationClient< std_srvs::srv::Trigger >.

◆ perform()

virtual OperationResult nav2_route::RouteOperation::perform ( NodePtr  node_achieved,
EdgePtr  edge_entered,
EdgePtr  edge_exited,
const Route route,
const geometry_msgs::msg::PoseStamped &  curr_pose,
const Metadata mdata = nullptr 
)
pure virtual

The main route operation API to perform an operation when triggered. The return value indicates if the route operation is requesting rerouting when returning true. Could be if this operation is checking if a route is in collision or operation failed (to open a door, for example) and thus this current route is now invalid.

Parameters
mdataMetadata corresponding to the operation in the navigation graph. If metadata is invalid or irrelevant, a nullptr is given
node_achievedNode achieved, for additional context (must check nullptr if at goal)
edge_enteredEdge entered by node achievement, for additional context (must check if nullptr if no future edge, at goal)
edge_exitedEdge exited by node achievement, for additional context (must check if nullptr if no last edge, starting)
routeCurrent route being tracked in full, for additional context
curr_poseCurrent robot pose in the route frame, for additional context
Returns
Whether to perform rerouting and report blocked edges in that case

Implemented in nav2_route::CollisionMonitor, nav2_route::RouteOperationClient< SrvT >, nav2_route::RouteOperationClient< std_srvs::srv::Trigger >, nav2_route::TimeMarker, nav2_route::AdjustSpeedLimit, and nav2_route::ReroutingService.

◆ processType()

virtual RouteOperationType nav2_route::RouteOperation::processType ( )
inlinevirtual

Indication of which type of route operation this plugin is. Whether it is be called by the graph's nodes or edges, whether it should be triggered at any status change, or whether it should be called constantly on any query. By default, it will create operations that are only called when a graph's node or edge requests it. Note that On Query, On Status Change, and On Graph are mutually exclusive since each operation type is merely a subset of the previous level's specificity.

Returns
The type of operation (on graph call, on status changes, or constantly)

Reimplemented in nav2_route::TimeMarker, nav2_route::ReroutingService, nav2_route::CollisionMonitor, nav2_route::AdjustSpeedLimit, nav2_route::RouteOperationClient< SrvT >, and nav2_route::RouteOperationClient< std_srvs::srv::Trigger >.

Definition at line 107 of file route_operation.hpp.


The documentation for this class was generated from the following file: