Nav2 Navigation Stack - kilted  kilted
ROS 2 Navigation Stack
Public Member Functions | Protected Attributes | List of all members
nav2_route::ReroutingService Class Reference

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>

Inheritance diagram for nav2_route::ReroutingService:
Inheritance graph
[legend]
Collaboration diagram for nav2_route::ReroutingService:
Collaboration graph
[legend]

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< 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 >
 

Detailed Description

A route operation to process requests from an external server for rerouting.

Definition at line 34 of file rerouting_service.hpp.

Member Function Documentation

◆ getName()

std::string nav2_route::ReroutingService::getName ( )
inlineoverridevirtual

Get name of the plugin for parameter scope mapping.

Returns
Name

Implements nav2_route::RouteOperation.

Definition at line 59 of file rerouting_service.hpp.

Referenced by configure().

Here is the caller graph for this function:

◆ perform()

OperationResult nav2_route::ReroutingService::perform ( NodePtr  node,
EdgePtr  edge_entered,
EdgePtr  edge_exited,
const Route route,
const geometry_msgs::msg::PoseStamped &  curr_pose,
const Metadata mdata = nullptr 
)
overridevirtual

The main speed limit operation to adjust the maximum speed of the vehicle.

Parameters
mdataMetadata corresponding to the operation in the navigation graph. If metadata is invalid or irrelevant, a nullptr is given
node_achievedNode achieved, for additional context
edge_enteredEdge entered by node achievement, for additional context
edge_exitedEdge exited by node achievement, for additional context
routeCurrent route being tracked in full, for additional context
curr_poseCurrent robot pose in the route frame, for additional context
Returns
Whether to perform rerouting and report blocked edges in that case

Implements nav2_route::RouteOperation.

Definition at line 49 of file rerouting_service.cpp.

◆ processType()

RouteOperationType nav2_route::ReroutingService::processType ( )
inlineoverridevirtual

Indication that the adjust speed limit route operation is performed on all state changes.

Returns
The type of operation (on graph call, on status changes, or constantly)

Reimplemented from nav2_route::RouteOperation.

Definition at line 66 of file rerouting_service.hpp.

◆ serviceCb()

void nav2_route::ReroutingService::serviceCb ( 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.

Parameters
request,empty
response,returnssuccess

Definition at line 40 of file rerouting_service.cpp.

Referenced by configure().

Here is the caller graph for this function:

The documentation for this class was generated from the following files: