Nav2 Navigation Stack - rolling
main
ROS 2 Navigation Stack
|
A route operation base class to trigger a service event at a node or edge. This is meant to be named accordingly to the event of query in the parameter file (e.g. OpenDoor, CallElevator). Thus, a single RouteOperationClient implementation can support many different operation instances calling different services. The template type may be overridden for any applications. It may be set up to either trigger a single service if the service_name
is set in the parameter file at launch for all calls or trigger different services depending on the service_name
set in the metadata of the node or edge operation given.
More...
#include <nav2_route/include/nav2_route/plugins/route_operation_client.hpp>
Public Member Functions | |
RouteOperationClient ()=default | |
Constructor. | |
virtual | ~RouteOperationClient ()=default |
destructor | |
virtual void | configureEvent (const nav2::LifecycleNode::SharedPtr, const std::string &) |
Configure client with any necessary parameters, etc. May change or reset main_srv_name_ variable to control main service name and existence. | |
virtual void | populateRequest (std::shared_ptr< typename SrvT::Request >, const Metadata *) |
Populate request with details for service, if necessary. | |
virtual OperationResult | processResponse (std::shared_ptr< typename SrvT::Response >) |
Process response from service to populate a result, if necessary. | |
![]() | |
RouteOperation ()=default | |
Constructor. | |
virtual | ~RouteOperation ()=default |
Destructor. | |
Protected Member Functions | |
void | configure (const nav2::LifecycleNode::SharedPtr node, std::shared_ptr< nav2_costmap_2d::CostmapSubscriber >, const std::string &name) final |
Configure. | |
OperationResult | perform (NodePtr node_achieved, EdgePtr, EdgePtr, const Route &, const geometry_msgs::msg::PoseStamped &, const Metadata *mdata) final |
The main operation to call a service of arbitrary type and arbitrary name. More... | |
std::string | getName () override |
Get name of the plugin for parameter scope mapping. More... | |
RouteOperationType | processType () final |
Indication that the adjust speed limit route operation is performed on all state changes. More... | |
Protected Attributes | |
std::string | name_ |
std::string | main_srv_name_ |
std::atomic_bool | reroute_ |
rclcpp::Logger | logger_ {rclcpp::get_logger("RouteOperationClient")} |
nav2::ServiceClient< SrvT >::SharedPtr | main_client_ |
nav2::LifecycleNode::WeakPtr | node_ |
Additional Inherited Members | |
![]() | |
using | Ptr = std::shared_ptr< nav2_route::RouteOperation > |
A route operation base class to trigger a service event at a node or edge. This is meant to be named accordingly to the event of query in the parameter file (e.g. OpenDoor, CallElevator). Thus, a single RouteOperationClient implementation can support many different operation instances calling different services. The template type may be overridden for any applications. It may be set up to either trigger a single service if the service_name
is set in the parameter file at launch for all calls or trigger different services depending on the service_name
set in the metadata of the node or edge operation given.
For example: OpenDoor<nav2_msgs::srv::OpenDoor> RouteOperationClient instance can open a door at service "/open_door" set in the parameter file that it calls every time the OpenDoor operation is triggered in the graph (ceneralized service). Or the OpenDoor instance can call any service whose service_name
is set in the operation's metadata (e.g. "/open_door1", "/open_door2", ...) corresponding to other instances of similar use. In this case, the specification of "OpenDoor" operation is less to do with the service name and more to do with the type of service template (nav2_msgs) used to populate the request (decentralized). This allows for massive reuse of a single plugin implementation in centralized or decentralized applications.
The templated nature of this node makes it a base class for any such service containing additional request or response fields by implementing the virtual interfaces configureEvent, populateRequest, processResponse appropriately. The std_srvs/Trigger example TriggerEvent can be thought of as a useful entry level demo and useful working primitive
Definition at line 62 of file route_operation_client.hpp.
|
inlineoverrideprotectedvirtual |
Get name of the plugin for parameter scope mapping.
Implements nav2_route::RouteOperation.
Definition at line 187 of file route_operation_client.hpp.
|
inlinefinalprotectedvirtual |
The main operation to call a service of arbitrary type and arbitrary name.
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 136 of file route_operation_client.hpp.
|
inlinefinalprotectedvirtual |
Indication that the adjust speed limit route operation is performed on all state changes.
Reimplemented from nav2_route::RouteOperation.
Definition at line 194 of file route_operation_client.hpp.