Nav2 Navigation Stack - rolling
main
ROS 2 Navigation Stack
|
A route operation to process on state changes to evaluate if speed limits should be adjusted based on graph edge metadata. More...
#include <nav2_route/include/nav2_route/plugins/route_operations/adjust_speed_limit.hpp>
Public Member Functions | |
AdjustSpeedLimit ()=default | |
Constructor. | |
virtual | ~AdjustSpeedLimit ()=default |
destructor | |
void | configure (const nav2::LifecycleNode::SharedPtr node, std::shared_ptr< nav2_costmap_2d::CostmapSubscriber > costmap_subscriber, const std::string &name) override |
Configure. | |
std::string | getName () override |
Get name of the plugin for parameter scope mapping. More... | |
RouteOperationType | processType () override |
Indication that the adjust speed limit route operation is performed on all state changes. More... | |
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. More... | |
![]() | |
RouteOperation ()=default | |
Constructor. | |
virtual | ~RouteOperation ()=default |
Destructor. | |
Protected Attributes | |
std::string | name_ |
std::string | speed_tag_ |
rclcpp::Logger | logger_ {rclcpp::get_logger("AdjustSpeedLimit")} |
nav2::Publisher< nav2_msgs::msg::SpeedLimit >::SharedPtr | speed_limit_pub_ |
Additional Inherited Members | |
![]() | |
using | Ptr = std::shared_ptr< nav2_route::RouteOperation > |
A route operation to process on state changes to evaluate if speed limits should be adjusted based on graph edge metadata.
Definition at line 35 of file adjust_speed_limit.hpp.
|
inlineoverridevirtual |
Get name of the plugin for parameter scope mapping.
Implements nav2_route::RouteOperation.
Definition at line 60 of file adjust_speed_limit.hpp.
Referenced by configure().
|
overridevirtual |
The main speed limit operation to adjust the maximum speed of the vehicle.
mdata | Metadata corresponding to the operation in the navigation graph. If metadata is invalid or irrelevant, a nullptr is given |
node_achieved | Node achieved, for additional context |
edge_entered | Edge entered by node achievement, for additional context |
edge_exited | Edge exited by node achievement, for additional context |
route | Current route being tracked in full, for additional context |
curr_pose | Current robot pose in the route frame, for additional context |
Implements nav2_route::RouteOperation.
Definition at line 45 of file adjust_speed_limit.cpp.
|
inlineoverridevirtual |
Indication that the adjust speed limit route operation is performed on all state changes.
Reimplemented from nav2_route::RouteOperation.
Definition at line 67 of file adjust_speed_limit.hpp.