AutoAPMS
Resilient Robot Mission Management
|
#include <auto_apms_behavior_tree/node/ros_service_node.hpp>
Public Types | |
using | ServiceType = ServiceT |
using | Request = typename ServiceT::Request |
using | Response = typename ServiceT::Response |
using | Config = BT::NodeConfig |
using | Context = RosNodeContext |
Public Member Functions | |
RosServiceNode (const std::string &instance_name, const Config &config, const Context &context) | |
virtual | ~RosServiceNode ()=default |
BT::NodeStatus | tick () override |
void | halt () override |
virtual bool | setRequest (typename Request::SharedPtr &request) |
virtual BT::NodeStatus | onResponseReceived (const typename Response::SharedPtr &response) |
virtual BT::NodeStatus | onFailure (ServiceNodeErrorCode error) |
std::string | getFullName () const |
Static Public Member Functions | |
static BT::PortsList | providedBasicPorts (BT::PortsList addition) |
static BT::PortsList | providedPorts () |
Protected Member Functions | |
const Context & | getRosContext () |
void | setServiceName (const std::string &service_name) |
Static Protected Member Functions | |
static std::mutex & | getMutex () |
static ClientsRegistry & | getRegistry () |
Protected Attributes | |
const rclcpp::Logger | logger_ |
Abstract class use to wrap rclcpp::Client<>
For instance, given the type AddTwoInts described in this tutorial: https://docs.ros.org/en/humble/Tutorials/Beginner-Client-Libraries/Writing-A-Simple-Cpp-Service-And-Client.html
the corresponding wrapper would be:
class AddTwoNumbers: public RosServiceNode<example_interfaces::srv::AddTwoInts>
RosServiceNode will try to be non-blocking for the entire duration of the call. The derived class must reimplement the virtual methods as described below.
The name of the service will be determined as follows:
Definition at line 72 of file ros_service_node.hpp.
using ServiceType = ServiceT |
Definition at line 89 of file ros_service_node.hpp.
using Request = typename ServiceT::Request |
Definition at line 90 of file ros_service_node.hpp.
using Response = typename ServiceT::Response |
Definition at line 91 of file ros_service_node.hpp.
using Config = BT::NodeConfig |
Definition at line 92 of file ros_service_node.hpp.
using Context = RosNodeContext |
Definition at line 93 of file ros_service_node.hpp.
|
inlineexplicit |
Definition at line 191 of file ros_service_node.hpp.
|
virtualdefault |
|
inlinestatic |
Any subclass of RosServiceNode that has ports must implement a providedPorts method and call providedBasicPorts in it.
addition | Additional ports to add to BT port list |
Definition at line 106 of file ros_service_node.hpp.
|
inlinestatic |
Creates list of BT ports.
Definition at line 117 of file ros_service_node.hpp.
|
inlineoverride |
Definition at line 260 of file ros_service_node.hpp.
|
inlineoverride |
The default halt() implementation.
Definition at line 365 of file ros_service_node.hpp.
|
inlinevirtual |
setRequest is a callback that allows the user to set the request message (ServiceT::Request).
request | the request to be sent to the service provider. |
Definition at line 374 of file ros_service_node.hpp.
|
inlinevirtual |
Callback invoked when the response is received by the server. It is up to the user to define if this returns SUCCESS or FAILURE.
Definition at line 380 of file ros_service_node.hpp.
|
inlinevirtual |
Callback invoked when something goes wrong; you can override it. It must return either SUCCESS or FAILURE.
Definition at line 386 of file ros_service_node.hpp.
|
inline |
Definition at line 393 of file ros_service_node.hpp.
|
inlineprotected |
Definition at line 405 of file ros_service_node.hpp.
|
inlinestaticprotected |
Definition at line 411 of file ros_service_node.hpp.
|
inlineprotected |
Definition at line 418 of file ros_service_node.hpp.
|
inlinestaticprotected |
Definition at line 425 of file ros_service_node.hpp.
|
protected |
Definition at line 160 of file ros_service_node.hpp.