Nav2 Navigation Stack - kilted  kilted
ROS 2 Navigation Stack
time_marker.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__PLUGINS__ROUTE_OPERATIONS__TIME_MARKER_HPP_
16 #define NAV2_ROUTE__PLUGINS__ROUTE_OPERATIONS__TIME_MARKER_HPP_
17 
18 #include <memory>
19 #include <string>
20 
21 #include "rclcpp/rclcpp.hpp"
22 #include "rclcpp_lifecycle/lifecycle_node.hpp"
23 #include "nav2_route/interfaces/route_operation.hpp"
24 #include "nav2_util/node_utils.hpp"
25 #include "nav2_msgs/msg/speed_limit.hpp"
26 
27 namespace nav2_route
28 {
29 
35 class TimeMarker : public RouteOperation
36 {
37 public:
41  TimeMarker() = default;
42 
46  virtual ~TimeMarker() = default;
47 
51  void configure(
52  const rclcpp_lifecycle::LifecycleNode::SharedPtr node,
53  std::shared_ptr<nav2_costmap_2d::CostmapSubscriber> costmap_subscriber,
54  const std::string & name) override;
55 
60  std::string getName() override {return name_;}
61 
67  RouteOperationType processType() override {return RouteOperationType::ON_STATUS_CHANGE;}
68 
81  NodePtr node_achieved,
82  EdgePtr edge_entered,
83  EdgePtr edge_exited,
84  const Route & route,
85  const geometry_msgs::msg::PoseStamped & curr_pose,
86  const Metadata * mdata = nullptr) override;
87 
88 protected:
89  std::string name_;
90  std::string time_tag_;
91  rclcpp::Clock::SharedPtr clock_;
92  rclcpp::Time edge_start_time_;
93  unsigned int curr_edge_;
94 };
95 
96 } // namespace nav2_route
97 
98 #endif // NAV2_ROUTE__PLUGINS__ROUTE_OPERATIONS__TIME_MARKER_HPP_
A plugin interface to perform an operation while tracking the route such as triggered from the graph ...
A route operation to add accurate times to the graph's edges after navigation to use in later iterati...
Definition: time_marker.hpp:36
TimeMarker()=default
Constructor.
RouteOperationType processType() override
Indication that the adjust speed limit route operation is performed on all state changes.
Definition: time_marker.hpp:67
void configure(const rclcpp_lifecycle::LifecycleNode::SharedPtr node, std::shared_ptr< nav2_costmap_2d::CostmapSubscriber > costmap_subscriber, const std::string &name) override
Configure.
Definition: time_marker.cpp:24
virtual ~TimeMarker()=default
destructor
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) override
The main speed limit operation to adjust the maximum speed of the vehicle.
Definition: time_marker.cpp:38
std::string getName() override
Get name of the plugin for parameter scope mapping.
Definition: time_marker.hpp:60
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