15 #ifndef NAV2_ROUTE__PLUGINS__ROUTE_OPERATIONS__REROUTING_SERVICE_HPP_
16 #define NAV2_ROUTE__PLUGINS__ROUTE_OPERATIONS__REROUTING_SERVICE_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 "std_srvs/srv/trigger.hpp"
51 const rclcpp_lifecycle::LifecycleNode::SharedPtr node,
52 std::shared_ptr<nav2_costmap_2d::CostmapSubscriber> costmap_subscriber,
53 const std::string & name)
override;
59 std::string
getName()
override {
return name_;}
66 RouteOperationType
processType()
override {
return RouteOperationType::ON_QUERY;}
84 const geometry_msgs::msg::PoseStamped & curr_pose,
85 const Metadata * mdata =
nullptr)
override;
93 const std::shared_ptr<rmw_request_id_t> request_header,
94 const std::shared_ptr<std_srvs::srv::Trigger::Request> request,
95 std::shared_ptr<std_srvs::srv::Trigger::Response> response);
99 std::atomic_bool reroute_;
100 rclcpp::Logger logger_{rclcpp::get_logger(
"ReroutingService")};
101 rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr service_;
A route operation to process requests from an external server for rerouting.
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.
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.
RouteOperationType processType() override
Indication that the adjust speed limit route operation is performed on all state changes.
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.
std::string getName() override
Get name of the plugin for parameter scope mapping.
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.