15 #include "pluginlib/class_loader.hpp"
16 #include "pluginlib/class_list_macros.hpp"
17 #include "nav2_util/node_utils.hpp"
18 #include "nav2_util/lifecycle_node.hpp"
19 #include "nav2_route/types.hpp"
20 #include "nav2_route/utils.hpp"
21 #include "nav2_route/interfaces/route_operation.hpp"
22 #include "nav2_route/operations_manager.hpp"
28 nav2_util::LifecycleNode::SharedPtr node,
29 std::shared_ptr<nav2_costmap_2d::CostmapSubscriber> costmap_subscriber)
30 : plugin_loader_(
"nav2_route",
"nav2_route::RouteOperation")
32 logger_ = node->get_logger();
35 const std::vector<std::string> default_plugin_ids(
36 {
"AdjustSpeedLimit",
"ReroutingService"});
37 const std::vector<std::string> default_plugin_types(
38 {
"nav2_route::AdjustSpeedLimit",
"nav2_route::ReroutingService"});
40 nav2_util::declare_parameter_if_not_declared(
41 node,
"operations", rclcpp::ParameterValue(default_plugin_ids));
42 auto operation_ids = node->get_parameter(
"operations").as_string_array();
44 if (operation_ids == default_plugin_ids) {
45 for (
unsigned int i = 0; i != operation_ids.size(); i++) {
46 nav2_util::declare_parameter_if_not_declared(
47 node, default_plugin_ids[i] +
".plugin", rclcpp::ParameterValue(default_plugin_types[i]));
52 for (
size_t i = 0; i != operation_ids.size(); i++) {
54 std::string type = nav2_util::get_plugin_type_param(node, operation_ids[i]);
55 RouteOperation::Ptr operation = plugin_loader_.createSharedInstance(type);
57 node->get_logger(),
"Created route operation %s of type %s",
58 operation_ids[i].c_str(), type.c_str());
59 operation->configure(node, costmap_subscriber, operation_ids[i]);
60 RouteOperationType process_type = operation->processType();
61 if (process_type == RouteOperationType::ON_QUERY) {
62 query_operations_.push_back(std::move(operation));
63 }
else if (process_type == RouteOperationType::ON_STATUS_CHANGE) {
64 change_operations_.push_back(std::move(operation));
66 graph_operations_[operation->getName()] = operation;
68 }
catch (
const pluginlib::PluginlibException & ex) {
76 T & obj,
const OperationTrigger & trigger,
77 OperationPtrs & operations)
83 Operations & op_vec = obj->operations;
84 for (Operations::iterator it = op_vec.begin(); it != op_vec.end(); ++it) {
85 if (it->trigger == trigger) {
86 operations.push_back(&(*it));
104 result.reroute = result.reroute || op_result.reroute;
105 result.blocked_ids.insert(
106 result.blocked_ids.end(), op_result.blocked_ids.begin(), op_result.blocked_ids.end());
107 result.operations_triggered.push_back(name);
111 const std::vector<RouteOperation::Ptr> & route_operations,
117 const geometry_msgs::msg::PoseStamped & pose)
119 for (OperationsIter it = route_operations.begin(); it != route_operations.end(); ++it) {
120 const RouteOperation::Ptr & plugin = *it;
121 OperationResult op_result = plugin->perform(node, edge_entered, edge_exited, route, pose);
127 const bool status_change,
130 const geometry_msgs::msg::PoseStamped & pose,
135 NodePtr node = state.last_node;
136 EdgePtr edge_entered = state.current_edge;
138 state.route_edges_idx > 0 ? route.edges[state.route_edges_idx - 1] :
nullptr;
142 if (state.route_edges_idx == 0 && rerouting_info.curr_edge) {
143 edge_exited = rerouting_info.curr_edge;
149 for (
unsigned int i = 0; i != operations.size(); i++) {
150 auto op = graph_operations_.find(operations[i]->type);
151 if (op != graph_operations_.end()) {
153 node, edge_entered, edge_exited, route, pose, &operations[i]->metadata);
157 "Operation " + operations[i]->type +
158 " does not exist in route operations loaded!");
164 change_operations_, result, node, edge_entered, edge_exited, route, pose);
169 query_operations_, result, node, edge_entered , edge_exited, route, pose);
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.
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.