|
Nav2 Navigation Stack - humble
humble
ROS 2 Navigation Stack
|
A route operation to process requests from an external server for rerouting. More...
#include <nav2_route/include/nav2_route/plugins/route_operations/rerouting_service.hpp>


Public Member Functions | |
| ReroutingService ()=default | |
| Constructor. | |
| virtual | ~ReroutingService ()=default |
| destructor | |
| void | configure (const rclcpp_lifecycle::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, 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... | |
| void | serviceCb (const std::shared_ptr< rmw_request_id_t > request_header, const std::shared_ptr< std_srvs::srv::Trigger::Request > request, std::shared_ptr< std_srvs::srv::Trigger::Response > response) |
| Service callback to trigger a reroute externally. More... | |
Public Member Functions inherited from nav2_route::RouteOperation | |
| RouteOperation ()=default | |
| Constructor. | |
| virtual | ~RouteOperation ()=default |
| Destructor. | |
Protected Attributes | |
| std::string | name_ |
| std::atomic_bool | reroute_ |
| rclcpp::Logger | logger_ {rclcpp::get_logger("ReroutingService")} |
| rclcpp::Service< std_srvs::srv::Trigger >::SharedPtr | service_ |
Additional Inherited Members | |
Public Types inherited from nav2_route::RouteOperation | |
| using | Ptr = std::shared_ptr< nav2_route::RouteOperation > |
A route operation to process requests from an external server for rerouting.
Definition at line 34 of file rerouting_service.hpp.
|
inlineoverridevirtual |
Get name of the plugin for parameter scope mapping.
Implements nav2_route::RouteOperation.
Definition at line 59 of file rerouting_service.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 50 of file rerouting_service.cpp.
|
inlineoverridevirtual |
Indication that the adjust speed limit route operation is performed on all state changes.
Reimplemented from nav2_route::RouteOperation.
Definition at line 66 of file rerouting_service.hpp.
| void nav2_route::ReroutingService::serviceCb | ( | const std::shared_ptr< rmw_request_id_t > | request_header, |
| const std::shared_ptr< std_srvs::srv::Trigger::Request > | request, | ||
| std::shared_ptr< std_srvs::srv::Trigger::Response > | response | ||
| ) |
Service callback to trigger a reroute externally.
| request,empty | |
| response,returns | success |
Definition at line 40 of file rerouting_service.cpp.
Referenced by configure().
