AutoAPMS
Resilient Robot Mission Management
Loading...
Searching...
No Matches
RosServiceNode< ServiceT > Class Template Reference

#include <auto_apms_behavior_tree/node/ros_service_node.hpp>

Inheritance diagram for RosServiceNode< ServiceT >:

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 ContextgetRosContext ()
 
void setServiceName (const std::string &service_name)
 

Static Protected Member Functions

static std::mutex & getMutex ()
 
static ClientsRegistry & getRegistry ()
 

Protected Attributes

const rclcpp::Logger logger_
 

Detailed Description

template<class ServiceT>
class auto_apms_behavior_tree::RosServiceNode< ServiceT >

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:

  1. If a value is passes in the BT::InputPort "service_name", use that
  2. Otherwise, use the value in RosNodeContext::default_port_name.

Definition at line 72 of file ros_service_node.hpp.

Member Typedef Documentation

◆ ServiceType

template<class ServiceT >
using ServiceType = ServiceT

Definition at line 89 of file ros_service_node.hpp.

◆ Request

template<class ServiceT >
using Request = typename ServiceT::Request

Definition at line 90 of file ros_service_node.hpp.

◆ Response

template<class ServiceT >
using Response = typename ServiceT::Response

Definition at line 91 of file ros_service_node.hpp.

◆ Config

template<class ServiceT >
using Config = BT::NodeConfig

Definition at line 92 of file ros_service_node.hpp.

◆ Context

template<class ServiceT >
using Context = RosNodeContext

Definition at line 93 of file ros_service_node.hpp.

Constructor & Destructor Documentation

◆ RosServiceNode()

template<class ServiceT >
RosServiceNode ( const std::string & instance_name,
const Config & config,
const Context & context )
inlineexplicit

Definition at line 191 of file ros_service_node.hpp.

◆ ~RosServiceNode()

template<class ServiceT >
virtual ~RosServiceNode ( )
virtualdefault

Member Function Documentation

◆ providedBasicPorts()

template<class ServiceT >
static BT::PortsList providedBasicPorts ( BT::PortsList addition)
inlinestatic

Any subclass of RosServiceNode that has ports must implement a providedPorts method and call providedBasicPorts in it.

Parameters
additionAdditional ports to add to BT port list
Returns
BT::PortsList containing basic ports along with node-specific ports

Definition at line 106 of file ros_service_node.hpp.

◆ providedPorts()

template<class ServiceT >
static BT::PortsList providedPorts ( )
inlinestatic

Creates list of BT ports.

Returns
BT::PortsList Containing basic ports along with node-specific ports

Definition at line 117 of file ros_service_node.hpp.

◆ tick()

template<class ServiceT >
BT::NodeStatus tick ( )
inlineoverride

Definition at line 260 of file ros_service_node.hpp.

◆ halt()

template<class ServiceT >
void halt ( )
inlineoverride

The default halt() implementation.

Definition at line 365 of file ros_service_node.hpp.

◆ setRequest()

template<class ServiceT >
bool setRequest ( typename Request::SharedPtr & request)
inlinevirtual

setRequest is a callback that allows the user to set the request message (ServiceT::Request).

Parameters
requestthe request to be sent to the service provider.
Returns
false if the request should not be sent. In that case, RosServiceNode::onFailure(INVALID_REQUEST) will be called.

Definition at line 374 of file ros_service_node.hpp.

◆ onResponseReceived()

template<class ServiceT >
BT::NodeStatus onResponseReceived ( const typename Response::SharedPtr & response)
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.

◆ onFailure()

template<class ServiceT >
BT::NodeStatus onFailure ( ServiceNodeErrorCode error)
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.

◆ getFullName()

template<class ServiceT >
std::string getFullName ( ) const
inline

Definition at line 393 of file ros_service_node.hpp.

◆ getRosContext()

template<class ServiceT >
const RosServiceNode< ServiceT >::Context & getRosContext ( )
inlineprotected

Definition at line 405 of file ros_service_node.hpp.

◆ getMutex()

template<class ServiceT >
std::mutex & getMutex ( )
inlinestaticprotected

Definition at line 411 of file ros_service_node.hpp.

◆ setServiceName()

template<class ServiceT >
void setServiceName ( const std::string & service_name)
inlineprotected

Definition at line 418 of file ros_service_node.hpp.

◆ getRegistry()

template<class ServiceT >
RosServiceNode< ServiceT >::ClientsRegistry & getRegistry ( )
inlinestaticprotected

Definition at line 425 of file ros_service_node.hpp.

Member Data Documentation

◆ logger_

template<class ServiceT >
const rclcpp::Logger logger_
protected

Definition at line 160 of file ros_service_node.hpp.


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