15 #ifndef NAV2_ROUTE__PLUGINS__ROUTE_OPERATIONS__ADJUST_SPEED_LIMIT_HPP_
16 #define NAV2_ROUTE__PLUGINS__ROUTE_OPERATIONS__ADJUST_SPEED_LIMIT_HPP_
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"
52 const rclcpp_lifecycle::LifecycleNode::SharedPtr node,
53 std::shared_ptr<nav2_costmap_2d::CostmapSubscriber> costmap_subscriber,
54 const std::string & name)
override;
60 std::string
getName()
override {
return name_;}
67 RouteOperationType
processType()
override {
return RouteOperationType::ON_STATUS_CHANGE;}
85 const geometry_msgs::msg::PoseStamped & curr_pose,
86 const Metadata * mdata =
nullptr)
override;
90 std::string speed_tag_;
91 rclcpp::Logger logger_{rclcpp::get_logger(
"AdjustSpeedLimit")};
92 rclcpp_lifecycle::LifecyclePublisher<nav2_msgs::msg::SpeedLimit>::SharedPtr speed_limit_pub_;
A route operation to process on state changes to evaluate if speed limits should be adjusted based on...
std::string getName() override
Get name of the plugin for parameter scope mapping.
virtual ~AdjustSpeedLimit()=default
destructor
AdjustSpeedLimit()=default
Constructor.
void configure(const rclcpp_lifecycle::LifecycleNode::SharedPtr node, std::shared_ptr< nav2_costmap_2d::CostmapSubscriber > costmap_subscriber, const std::string &name) override
Configure.
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.
RouteOperationType processType() override
Indication that the adjust speed limit route operation is performed on all state changes.
A plugin interface to perform an operation while tracking the route such as triggered from the graph ...
An object representing edges between nodes.
An object to store the nodes in the graph file.
a struct to hold return from an operation
An ordered set of nodes and edges corresponding to the planned route.