19 #include "nav2_route/plugins/route_operations/adjust_speed_limit.hpp"
25 const nav2::LifecycleNode::SharedPtr node,
26 std::shared_ptr<nav2_costmap_2d::CostmapSubscriber>,
27 const std::string & name)
29 RCLCPP_INFO(node->get_logger(),
"Configuring Adjust speed limit operation.");
31 logger_ = node->get_logger();
32 nav2::declare_parameter_if_not_declared(
33 node,
getName() +
".speed_tag", rclcpp::ParameterValue(
"speed_limit"));
34 speed_tag_ = node->get_parameter(
getName() +
".speed_tag").as_string();
37 nav2::declare_parameter_if_not_declared(
38 node,
getName() +
".speed_limit_topic", rclcpp::ParameterValue(
"speed_limit"));
39 std::string topic = node->get_parameter(
getName() +
".speed_tag").as_string();
41 speed_limit_pub_ = node->create_publisher<nav2_msgs::msg::SpeedLimit>(topic);
42 speed_limit_pub_->on_activate();
50 const geometry_msgs::msg::PoseStamped & ,
58 float speed_limit = 100.0;
59 speed_limit = edge_entered->metadata.getValue<
float>(speed_tag_, speed_limit);
60 RCLCPP_DEBUG(logger_,
"Setting speed limit to %.2f%% of maximum.", speed_limit);
62 auto msg = std::make_unique<nav2_msgs::msg::SpeedLimit>();
63 msg->percentage =
true;
64 msg->speed_limit = speed_limit;
65 speed_limit_pub_->publish(std::move(msg));
71 #include "pluginlib/class_list_macros.hpp"
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.
void configure(const nav2::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.
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.