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

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

#include <action_client_behavior_base.hpp>

Inheritance diagram for moveit_studio::behaviors::ActionClientBehaviorBase< ActionT >::RclcppClientInterface:
Collaboration diagram for moveit_studio::behaviors::ActionClientBehaviorBase< ActionT >::RclcppClientInterface:

Public Member Functions

 RclcppClientInterface (const std::shared_ptr< rclcpp::Node > node)
 Constructor for this implementation. More...
 
void initialize (const std::string &action_name, std::chrono::duration< double > wait_for_server_timeout, std::chrono::duration< double > goal_response_timeout, std::chrono::duration< double > goal_result_timeout, std::chrono::duration< double > cancel_response_timeout) override
 Implementation of ClientInterfaceBase::initialize for an rclcpp action client. More...
 
bool waitForActionServer () const override
 Implementation of ClientInterfaceBase::waitForActionServer for an rclcpp action client. More...
 
tl::expected< void, std::string > syncSendGoal (const typename ActionT::Goal &goal, typename ClientGoalHandle::FeedbackCallback feedback_fn) override
 Implementation of ClientInterfaceBase::syncSendGoal for an rclcpp action client. More...
 
tl::expected< typename ActionClientBehaviorBase::ClientGoalHandle::WrappedResult, std::string > syncGetResult () const override
 Implementation of ClientInterfaceBase::syncGetResult for an rclcpp action client. More...
 
tl::expected< std::shared_ptr< typename ActionT::Impl::CancelGoalService::Response >, std::string > syncCancelGoal () const override
 Implementation of ClientInterfaceBase::syncCancelGoal for an rclcpp action client. More...
 
- Public Member Functions inherited from moveit_studio::behaviors::ActionClientBehaviorBase< ActionT >::ClientInterfaceBase
virtual ~ClientInterfaceBase ()=default
 

Detailed Description

template<typename ActionT>
class moveit_studio::behaviors::ActionClientBehaviorBase< ActionT >::RclcppClientInterface

Implements ClientInterfaceBase for the rclcpp action client.

Constructor & Destructor Documentation

◆ RclcppClientInterface()

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

Constructor for this implementation.

Parameters
nodeNode to use when initializing the action client.

Member Function Documentation

◆ initialize()

template<typename ActionT >
void moveit_studio::behaviors::ActionClientBehaviorBase< ActionT >::RclcppClientInterface::initialize ( const std::string &  action_name,
std::chrono::duration< double >  wait_for_server_timeout,
std::chrono::duration< double >  goal_response_timeout,
std::chrono::duration< double >  goal_result_timeout,
std::chrono::duration< double >  cancel_response_timeout 
)
overridevirtual

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

Sets client_ to a new action client instance

Implements moveit_studio::behaviors::ActionClientBehaviorBase< ActionT >::ClientInterfaceBase.

◆ syncCancelGoal()

template<typename ActionT >
tl::expected< std::shared_ptr< typename ActionT::Impl::CancelGoalService::Response >, std::string > moveit_studio::behaviors::ActionClientBehaviorBase< ActionT >::RclcppClientInterface::syncCancelGoal
overridevirtual

Implementation of ClientInterfaceBase::syncCancelGoal for an rclcpp action client.

Calls the action client's async_cancel_goal function and blocks while waiting on the future which it returns. This implementation also returns an error result if the action goal handle is not initialized or not in-progress.

Implements moveit_studio::behaviors::ActionClientBehaviorBase< ActionT >::ClientInterfaceBase.

◆ syncGetResult()

template<typename ActionT >
tl::expected< typename ActionClientBehaviorBase< ActionT >::ClientGoalHandle::WrappedResult, std::string > moveit_studio::behaviors::ActionClientBehaviorBase< ActionT >::RclcppClientInterface::syncGetResult
overridevirtual

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

Calls the action client's async_get_result function and blocks while waiting on the future which it returns. This implementation also returns an error result if the action goal handle is not initialized or not in-progress.

Implements moveit_studio::behaviors::ActionClientBehaviorBase< ActionT >::ClientInterfaceBase.

◆ syncSendGoal()

template<typename ActionT >
tl::expected< void, std::string > moveit_studio::behaviors::ActionClientBehaviorBase< ActionT >::RclcppClientInterface::syncSendGoal ( const typename ActionT::Goal &  goal,
typename ClientGoalHandle::FeedbackCallback  feedback_fn 
)
overridevirtual

Implementation of ClientInterfaceBase::syncSendGoal for an rclcpp action client.

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

Implements moveit_studio::behaviors::ActionClientBehaviorBase< ActionT >::ClientInterfaceBase.

◆ waitForActionServer()

template<typename ActionT >
bool moveit_studio::behaviors::ActionClientBehaviorBase< ActionT >::RclcppClientInterface::waitForActionServer
overridevirtual

Implementation of ClientInterfaceBase::waitForActionServer for an rclcpp action client.

Calls the action client's wait_for_action_server function.

Implements moveit_studio::behaviors::ActionClientBehaviorBase< ActionT >::ClientInterfaceBase.


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