Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
nav2_route::OperationsManager Class Reference

Manages operations plugins to call on route tracking. More...

#include <nav2_route/include/nav2_route/operations_manager.hpp>

Public Types

typedef std::vector< RouteOperation::Ptr >::const_iterator OperationsIter
 

Public Member Functions

 OperationsManager (rclcpp_lifecycle::LifecycleNode::SharedPtr node, std::shared_ptr< nav2_costmap_2d::CostmapSubscriber > costmap_subscriber)
 A constructor for nav2_route::OperationsManager.
 
 ~OperationsManager ()=default
 A Destructor for nav2_route::OperationsManager.
 
OperationPtrs findGraphOperations (const NodePtr node, const EdgePtr edge_enter, const EdgePtr edge_exit)
 Finds the set of operations stored in the graph to trigger at this transition. More...
 
template<typename T >
void findGraphOperationsToProcess (T &obj, const OperationTrigger &trigger, OperationPtrs &operations)
 Finds the set of operations stored in graph objects, by event. More...
 
void updateResult (const std::string &name, const OperationResult &op_result, OperationsResult &result)
 Updates manager result state by an individual operation's result. More...
 
OperationsResult process (const bool status_change, const RouteTrackingState &state, const Route &route, const geometry_msgs::msg::PoseStamped &pose, const ReroutingState &rerouting_info)
 Processes the operations at this tracker state. More...
 

Protected Member Functions

void processOperationsPluginVector (const std::vector< RouteOperation::Ptr > &operations, OperationsResult &result, const NodePtr node, const EdgePtr edge_entered, const EdgePtr edge_exited, const Route &route, const geometry_msgs::msg::PoseStamped &pose)
 Processes a vector of operations plugins, by trigger. More...
 

Protected Attributes

pluginlib::ClassLoader< RouteOperationplugin_loader_
 
std::unordered_map< std::string, RouteOperation::Ptr > graph_operations_
 
std::vector< RouteOperation::Ptr > change_operations_
 
std::vector< RouteOperation::Ptr > query_operations_
 
rclcpp::Logger logger_ {rclcpp::get_logger("OperationsManager")}
 

Detailed Description

Manages operations plugins to call on route tracking.

Definition at line 39 of file operations_manager.hpp.

Member Function Documentation

◆ findGraphOperations()

OperationPtrs nav2_route::OperationsManager::findGraphOperations ( const NodePtr  node,
const EdgePtr  edge_enter,
const EdgePtr  edge_exit 
)

Finds the set of operations stored in the graph to trigger at this transition.

Parameters
nodeNode to check
edge_enteredEdge entered to check for ON_ENTER events
edge_exitEdge exit to check for ON_EXIT events
Returns
OperationPtrs A vector of operation pointers to execute

Definition at line 91 of file operations_manager.cpp.

References findGraphOperationsToProcess().

Referenced by process().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ findGraphOperationsToProcess()

template<typename T >
void nav2_route::OperationsManager::findGraphOperationsToProcess ( T &  obj,
const OperationTrigger &  trigger,
OperationPtrs &  operations 
)

Finds the set of operations stored in graph objects, by event.

Parameters
nodeop_vec Operations vector to check
triggerTrigger for which operations in op_vec should be included
operationsOutput vector populated with relevant operations

Definition at line 75 of file operations_manager.cpp.

Referenced by findGraphOperations().

Here is the caller graph for this function:

◆ process()

OperationsResult nav2_route::OperationsManager::process ( const bool  status_change,
const RouteTrackingState state,
const Route route,
const geometry_msgs::msg::PoseStamped &  pose,
const ReroutingState rerouting_info 
)

Processes the operations at this tracker state.

Parameters
status_changeWhether something meaningful has changed
stateThe route tracking state to check for state info
routeThe raw route being tracked
poserobot pose
rerouting_infoRerouting information regarding previous partial state
Returns
A result vector whether the operations are requesting something to occur

Definition at line 126 of file operations_manager.cpp.

References findGraphOperations(), processOperationsPluginVector(), and updateResult().

Here is the call graph for this function:

◆ processOperationsPluginVector()

void nav2_route::OperationsManager::processOperationsPluginVector ( const std::vector< RouteOperation::Ptr > &  operations,
OperationsResult result,
const NodePtr  node,
const EdgePtr  edge_entered,
const EdgePtr  edge_exited,
const Route route,
const geometry_msgs::msg::PoseStamped &  pose 
)
protected

Processes a vector of operations plugins, by trigger.

Parameters
operationsOperations to trigger
Resultsto populate from operations

Definition at line 110 of file operations_manager.cpp.

References updateResult().

Referenced by process().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ updateResult()

void nav2_route::OperationsManager::updateResult ( const std::string &  name,
const OperationResult op_result,
OperationsResult result 
)

Updates manager result state by an individual operation's result.

Parameters
nameOperations' name
op_resultOperations' result
resultManager's result to update

Definition at line 101 of file operations_manager.cpp.

Referenced by process(), and processOperationsPluginVector().

Here is the caller graph for this function:

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