Nav2 Navigation Stack - kilted  kilted
ROS 2 Navigation Stack
route_operation.hpp
1 // Copyright (c) 2025 Open Navigation LLC
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #ifndef NAV2_ROUTE__INTERFACES__ROUTE_OPERATION_HPP_
16 #define NAV2_ROUTE__INTERFACES__ROUTE_OPERATION_HPP_
17 
18 #include <memory>
19 #include <string>
20 #include <vector>
21 
22 #include "rclcpp/rclcpp.hpp"
23 #include "rclcpp_lifecycle/lifecycle_node.hpp"
24 #include "pluginlib/class_loader.hpp"
25 #include "nav2_route/types.hpp"
26 #include "geometry_msgs/msg/pose_stamped.hpp"
27 #include "nav2_costmap_2d/costmap_subscriber.hpp"
28 
29 namespace nav2_route
30 {
31 
37 {
38  bool reroute{false};
39  std::vector<unsigned int> blocked_ids;
40 };
41 
46 enum class RouteOperationType
47 {
48  ON_GRAPH = 0,
49  ON_STATUS_CHANGE = 1,
50  ON_QUERY = 2
51 };
52 
67 {
68 public:
69  using Ptr = std::shared_ptr<nav2_route::RouteOperation>;
70 
74  RouteOperation() = default;
75 
79  virtual ~RouteOperation() = default;
80 
87  virtual void configure(
88  const rclcpp_lifecycle::LifecycleNode::SharedPtr node,
89  std::shared_ptr<nav2_costmap_2d::CostmapSubscriber> costmap_subscriber,
90  const std::string & name) = 0;
91 
97  virtual std::string getName() = 0;
98 
108  virtual RouteOperationType processType() {return RouteOperationType::ON_GRAPH;}
109 
128  NodePtr node_achieved,
129  EdgePtr edge_entered,
130  EdgePtr edge_exited,
131  const Route & route,
132  const geometry_msgs::msg::PoseStamped & curr_pose,
133  const Metadata * mdata = nullptr) = 0;
134 };
135 
136 } // namespace nav2_route
137 
138 #endif // NAV2_ROUTE__INTERFACES__ROUTE_OPERATION_HPP_
A plugin interface to perform an operation while tracking the route such as triggered from the graph ...
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)
virtual std::string getName()=0
An API to get the name of a particular operation for triggering, query or logging.
virtual RouteOperationType processType()
Indication of which type of route operation this plugin is. Whether it is be called by the graph's no...
RouteOperation()=default
Constructor.
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 th...
An object representing edges between nodes.
Definition: types.hpp:134
An object to store arbitrary metadata regarding nodes from the graph file.
Definition: types.hpp:35
An object to store the nodes in the graph file.
Definition: types.hpp:183
a struct to hold return from an operation
An ordered set of nodes and edges corresponding to the planned route.
Definition: types.hpp:211