MoveIt Pro Behavior
Core Behaviors for MoveIt Pro
moveit_studio::behaviors::ServiceClientBehaviorBase< ServiceT > Class Template Referenceabstract

A base class for behaviors which need to send a request to a ROS service client and wait for a result. More...

#include <service_client_behavior_base.hpp>

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

Public Member Functions

 ServiceClientBehaviorBase (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources)
 Constructs ServiceClientBehaviorBase using the RclcppClientInterface. More...
 
 ServiceClientBehaviorBase (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources, std::unique_ptr< ClientInterfaceBase< ServiceT >> client_interface)
 Constructs ServiceClientBehaviorBase using a user-provided implementation of ClientInterfaceBase. More...
 
virtual ~ServiceClientBehaviorBase ()=default
 
- Public Member Functions inherited from moveit_studio::behaviors::AsyncBehaviorBase
 AsyncBehaviorBase (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources)
 
virtual ~AsyncBehaviorBase ()=default
 
BT::NodeStatus onStart () override
 Required implementation of BT::StatefulActionNode::onStart(). More...
 
BT::NodeStatus onRunning () override
 Required implementation of BT::StatefulActionNode::onRunning(). More...
 
void onHalted () override
 Required implementation of BT::StatefulActionNode::onHalted(). More...
 
void resetStatus ()
 Resets the internal status of this node. More...
 
- Public Member Functions inherited from moveit_studio::behaviors::SharedResourcesNode< BT::StatefulActionNode >
 SharedResourcesNode (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources)
 Constructor for SharedResourcesNode. Called by BT::BehaviorTreeFactory when creating a new behavior tree containing this node. More...
 

Static Public Attributes

static constexpr std::chrono::seconds kTimeoutWaitForServiceServer { 3 }
 

Protected Member Functions

virtual tl::expected< std::string, std::string > getServiceName ()=0
 User-provided function to get the name of the service when initializing the service client. More...
 
virtual tl::expected< std::chrono::duration< double >, std::string > getResponseTimeout ()
 Optional user-provided function to set the timeout used when waiting for the service response. More...
 
virtual tl::expected< typename ServiceT::Request, std::string > createRequest ()=0
 User-provided function to create the service request. More...
 
virtual tl::expected< bool, std::string > processResponse (const typename ServiceT::Response &)
 Optional user-provided function to process the service response after the service has finished. More...
 
- Protected Member Functions inherited from moveit_studio::behaviors::AsyncBehaviorBase
virtual std::shared_future< tl::expected< bool, std::string > > & getFuture ()=0
 Gets the shared future which is used to monitor the progress of the async process. More...
 
void notifyCanHalt ()
 Called when runAsync() finishes to notify onHalted() that the async process has finished. More...
 

Additional Inherited Members

- Protected Attributes inherited from moveit_studio::behaviors::SharedResourcesNode< BT::StatefulActionNode >
std::shared_ptr< BehaviorContextshared_resources_
 

Detailed Description

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

A base class for behaviors which need to send a request to a ROS service client and wait for a result.

Important: If a halt is requested before the service request is sent to the service server, the behavior will wait to halt until the service response has been received or the timeout duration has elapsed.

Template Parameters
ServiceTROS service message type used to specialize this class for a specific service.

Constructor & Destructor Documentation

◆ ServiceClientBehaviorBase() [1/2]

template<typename ServiceT >
moveit_studio::behaviors::ServiceClientBehaviorBase< ServiceT >::ServiceClientBehaviorBase ( const std::string &  name,
const BT::NodeConfiguration &  config,
const std::shared_ptr< BehaviorContext > &  shared_resources 
)

◆ ServiceClientBehaviorBase() [2/2]

template<typename ServiceT >
moveit_studio::behaviors::ServiceClientBehaviorBase< ServiceT >::ServiceClientBehaviorBase ( const std::string &  name,
const BT::NodeConfiguration &  config,
const std::shared_ptr< BehaviorContext > &  shared_resources,
std::unique_ptr< ClientInterfaceBase< ServiceT >>  client_interface 
)

Constructs ServiceClientBehaviorBase using a user-provided implementation of ClientInterfaceBase.

◆ ~ServiceClientBehaviorBase()

template<typename ServiceT >
virtual moveit_studio::behaviors::ServiceClientBehaviorBase< ServiceT >::~ServiceClientBehaviorBase ( )
virtualdefault

Member Function Documentation

◆ createRequest()

template<typename ServiceT >
virtual tl::expected<typename ServiceT::Request, std::string> moveit_studio::behaviors::ServiceClientBehaviorBase< ServiceT >::createRequest ( )
protectedpure virtual

User-provided function to create the service request.

Returns
Returns a service request message. If not successful, returns an error message. Note that the criteria for success or failure is defined by the user's implementation of this function.

◆ getResponseTimeout()

template<typename ServiceT >
virtual tl::expected<std::chrono::duration<double>, std::string> moveit_studio::behaviors::ServiceClientBehaviorBase< ServiceT >::getResponseTimeout ( )
inlineprotectedvirtual

Optional user-provided function to set the timeout used when waiting for the service response.

If no user-defined implementation is provided, the default implementation returns a negative duration, which will cause the service client to wait for the response without timing out.

Returns
Returns the service response timeout duration. If not successful, returns an error message. Note that the criteria for success or failure is defined by the user's implementation of this function.

◆ getServiceName()

template<typename ServiceT >
virtual tl::expected<std::string, std::string> moveit_studio::behaviors::ServiceClientBehaviorBase< ServiceT >::getServiceName ( )
protectedpure virtual

User-provided function to get the name of the service when initializing the service client.

Returns
Returns the name of the service. If not successful, returns an error message. Note that the criteria for success or failure is defined by the user's implementation of this function.

◆ processResponse()

template<typename ServiceT >
virtual tl::expected<bool, std::string> moveit_studio::behaviors::ServiceClientBehaviorBase< ServiceT >::processResponse ( const typename ServiceT::Response &  )
inlineprotectedvirtual

Optional user-provided function to process the service response after the service has finished.

If no user-defined implementation is provided, then no additional processing will be performed on succeeding service responses and this function will always return void.

Parameters
responseService response message to process.
Returns
Returns true or false depending on the user's implementation if the service response could be processed successfully. If the service response could not be processed, returns an error message. Note that the criteria for success or failure is defined by the user's implementation of this function.

Member Data Documentation

◆ kTimeoutWaitForServiceServer

template<typename ServiceT >
constexpr std::chrono::seconds moveit_studio::behaviors::ServiceClientBehaviorBase< ServiceT >::kTimeoutWaitForServiceServer { 3 }
staticconstexpr

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