MoveIt Pro Behavior Interface  5.0.1
Library for developing custom behaviors for use in MoveIt Pro
moveit_studio::behaviors::RclcppClientInterface< ServiceT > Class Template Reference

Implements ClientInterfaceBase for the rclcpp service client. More...

#include <service_client_interface.hpp>

Inheritance diagram for moveit_studio::behaviors::RclcppClientInterface< ServiceT >:
Collaboration diagram for moveit_studio::behaviors::RclcppClientInterface< ServiceT >:

Public Member Functions

 RclcppClientInterface (const std::shared_ptr< rclcpp::Node > node)
 Constructor for this implementation. More...
 
void initialize (const std::string &service_name, std::chrono::duration< double > wait_for_server_timeout, std::chrono::duration< double > result_timeout) override
 Implementation of ClientInterfaceBase::initialize for an rclcpp service client. More...
 
bool waitForServiceServer () const override
 Implementation of ClientInterfaceBase::waitForServiceServer for an rclcpp service client. More...
 
tl::expected< typename ServiceT::Response, std::string > syncSendRequest (const typename ServiceT::Request &request) override
 Implementation of ClientInterfaceBase::syncGetResult for an rclcpp service client. More...
 
void cancelRequest () override
 Implementation of ClientInterfaceBase::cancelRequest for an rclcpp service client. More...
 
- Public Member Functions inherited from moveit_studio::behaviors::ClientInterfaceBase< ServiceT >
virtual ~ClientInterfaceBase ()=default
 

Static Public Attributes

static constexpr std::chrono::milliseconds kResponseBusyWaitPeriod { 100 }
 

Detailed Description

template<typename ServiceT>
class moveit_studio::behaviors::RclcppClientInterface< ServiceT >

Implements ClientInterfaceBase for the rclcpp service client.

Constructor & Destructor Documentation

◆ RclcppClientInterface()

template<typename ServiceT >
moveit_studio::behaviors::RclcppClientInterface< ServiceT >::RclcppClientInterface ( const std::shared_ptr< rclcpp::Node >  node)
explicit

Constructor for this implementation.

Parameters
nodeNode to use when initializing the service client.

Member Function Documentation

◆ cancelRequest()

template<typename ServiceT >
void moveit_studio::behaviors::RclcppClientInterface< ServiceT >::cancelRequest
overridevirtual

Implementation of ClientInterfaceBase::cancelRequest for an rclcpp service client.

Aborts the busy-waiting request loop causing it to return (almost) immediately.

Implements moveit_studio::behaviors::ClientInterfaceBase< ServiceT >.

◆ initialize()

template<typename ServiceT >
void moveit_studio::behaviors::RclcppClientInterface< ServiceT >::initialize ( const std::string &  service_name,
std::chrono::duration< double >  wait_for_server_timeout,
std::chrono::duration< double >  result_timeout 
)
overridevirtual

Implementation of ClientInterfaceBase::initialize for an rclcpp service client.

Sets client_ to a new service client instance

Implements moveit_studio::behaviors::ClientInterfaceBase< ServiceT >.

◆ syncSendRequest()

template<typename ServiceT >
tl::expected< typename ServiceT::Response, std::string > moveit_studio::behaviors::RclcppClientInterface< ServiceT >::syncSendRequest ( const typename ServiceT::Request &  request)
overridevirtual

Implementation of ClientInterfaceBase::syncGetResult for an rclcpp service client.

Calls the service client's async_send_request function and blocks while waiting on the future which it returns.

Implements moveit_studio::behaviors::ClientInterfaceBase< ServiceT >.

◆ waitForServiceServer()

template<typename ServiceT >
bool moveit_studio::behaviors::RclcppClientInterface< ServiceT >::waitForServiceServer
overridevirtual

Implementation of ClientInterfaceBase::waitForServiceServer for an rclcpp service client.

Calls the service client's wait_for_service function.

Implements moveit_studio::behaviors::ClientInterfaceBase< ServiceT >.

Member Data Documentation

◆ kResponseBusyWaitPeriod

template<typename ServiceT >
constexpr std::chrono::milliseconds moveit_studio::behaviors::RclcppClientInterface< ServiceT >::kResponseBusyWaitPeriod { 100 }
staticconstexpr

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