15 #include <unordered_map>
20 #include "pluginlib/class_loader.hpp"
21 #include "pluginlib/class_list_macros.hpp"
22 #include "nav2_util/node_utils.hpp"
23 #include "nav2_core/route_exceptions.hpp"
24 #include "nav2_util/lifecycle_node.hpp"
25 #include "nav2_route/types.hpp"
26 #include "nav2_route/utils.hpp"
27 #include "nav2_route/interfaces/route_operation.hpp"
29 #ifndef NAV2_ROUTE__OPERATIONS_MANAGER_HPP_
30 #define NAV2_ROUTE__OPERATIONS_MANAGER_HPP_
42 typedef std::vector<RouteOperation::Ptr>::const_iterator OperationsIter;
48 nav2_util::LifecycleNode::SharedPtr node,
49 std::shared_ptr<nav2_costmap_2d::CostmapSubscriber> costmap_subscriber);
75 const OperationTrigger & trigger,
76 OperationPtrs & operations);
97 const bool status_change,
100 const geometry_msgs::msg::PoseStamped & pose,
110 const std::vector<RouteOperation::Ptr> & operations,
OperationsResult & result,
115 const geometry_msgs::msg::PoseStamped & pose);
117 pluginlib::ClassLoader<RouteOperation> plugin_loader_;
118 std::unordered_map<std::string, RouteOperation::Ptr> graph_operations_;
119 std::vector<RouteOperation::Ptr> change_operations_;
120 std::vector<RouteOperation::Ptr> query_operations_;
121 rclcpp::Logger logger_{rclcpp::get_logger(
"OperationsManager")};
Manages operations plugins to call on route tracking.
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.
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.
~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.
void findGraphOperationsToProcess(T &obj, const OperationTrigger &trigger, OperationPtrs &operations)
Finds the set of operations stored in graph objects, by event.
void updateResult(const std::string &name, const OperationResult &op_result, OperationsResult &result)
Updates manager result state by an individual operation's result.
OperationsManager(nav2_util::LifecycleNode::SharedPtr node, std::shared_ptr< nav2_costmap_2d::CostmapSubscriber > costmap_subscriber)
A constructor for nav2_route::OperationsManager.
An object representing edges between nodes.
An object to store the nodes in the graph file.
a struct to hold return from an operation
Result information from the operations manager.
State shared to objects to communicate important rerouting data to avoid rerouting over blocked edges...
Current state management of route tracking class.
An ordered set of nodes and edges corresponding to the planned route.