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

A base class for behaviors which need to send a goal to a ROS action client and wait for a result. If the behavior is halted before the action result is received, the action goal will be canceled. More...

#include <action_client_behavior_base.hpp>

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

Classes

class  ClientInterfaceBase
 Provides an interface to an action client that can handle a single goal at a time. More...
 
class  RclcppClientInterface
 Implements ClientInterfaceBase for the rclcpp action client. More...
 

Public Types

using ClientGoalHandle = rclcpp_action::ClientGoalHandle< ActionT >
 

Public Member Functions

 ActionClientBehaviorBase (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources)
 Constructs ActionClientBehaviorBase using the RclcppClientInterface. More...
 
 ActionClientBehaviorBase (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources, std::unique_ptr< ClientInterfaceBase > client_interface)
 Constructs ActionClientBehaviorBase using a user-provided implementation of ClientInterfaceBase. More...
 
virtual ~ActionClientBehaviorBase ()=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...
 

Protected Member Functions

virtual tl::expected< std::string, std::string > getActionName ()=0
 User-provided function to get the name of the action when initializing the action client. More...
 
virtual tl::expected< std::chrono::duration< double >, std::string > getResultTimeout ()
 Optional user-provided function to set the timeout used when waiting for the action result. More...
 
virtual tl::expected< typename ActionT::Goal, std::string > createGoal ()=0
 User-provided function to create the action goal before sending the action goal request. More...
 
virtual tl::expected< bool, std::string > processResult (const std::shared_ptr< typename ActionT::Result >)
 Optional user-provided function to process the action result after the action has finished. More...
 
virtual void processFeedback (const std::shared_ptr< const typename ActionT::Feedback >)
 Optional user-provided function to process feedback sent by the action server. 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 ActionT>
class moveit_studio::behaviors::ActionClientBehaviorBase< ActionT >

A base class for behaviors which need to send a goal to a ROS action client and wait for a result. If the behavior is halted before the action result is received, the action goal will be canceled.

Important: If a halt is requested before the action goal request is sent to the action server or before the action goal response has been received from the action server, the behavior will wait to halt until the action goal response has been received then request that the action goal be canceled, and will finally wait until the in-progress action goal has finished.

Template Parameters
ActionTROS action message type used to specialize this class for a specific action

Member Typedef Documentation

◆ ClientGoalHandle

template<typename ActionT >
using moveit_studio::behaviors::ActionClientBehaviorBase< ActionT >::ClientGoalHandle = rclcpp_action::ClientGoalHandle<ActionT>

Constructor & Destructor Documentation

◆ ActionClientBehaviorBase() [1/2]

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

◆ ActionClientBehaviorBase() [2/2]

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

Constructs ActionClientBehaviorBase using a user-provided implementation of ClientInterfaceBase.

◆ ~ActionClientBehaviorBase()

template<typename ActionT >
virtual moveit_studio::behaviors::ActionClientBehaviorBase< ActionT >::~ActionClientBehaviorBase ( )
virtualdefault

Member Function Documentation

◆ createGoal()

template<typename ActionT >
virtual tl::expected<typename ActionT::Goal, std::string> moveit_studio::behaviors::ActionClientBehaviorBase< ActionT >::createGoal ( )
protectedpure virtual

User-provided function to create the action goal before sending the action goal request.

Returns
Returns an action goal 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.

◆ getActionName()

template<typename ActionT >
virtual tl::expected<std::string, std::string> moveit_studio::behaviors::ActionClientBehaviorBase< ActionT >::getActionName ( )
protectedpure virtual

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

Returns
Returns the name of the action. 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.

◆ getResultTimeout()

template<typename ActionT >
virtual tl::expected<std::chrono::duration<double>, std::string> moveit_studio::behaviors::ActionClientBehaviorBase< ActionT >::getResultTimeout ( )
inlineprotectedvirtual

Optional user-provided function to set the timeout used when waiting for the action result.

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

Returns
Returns the action result 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.

◆ processFeedback()

template<typename ActionT >
virtual void moveit_studio::behaviors::ActionClientBehaviorBase< ActionT >::processFeedback ( const std::shared_ptr< const typename ActionT::Feedback >  )
inlineprotectedvirtual

Optional user-provided function to process feedback sent by the action server.

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

Parameters
feedbackAction feedback message to process.

◆ processResult()

template<typename ActionT >
virtual tl::expected<bool, std::string> moveit_studio::behaviors::ActionClientBehaviorBase< ActionT >::processResult ( const std::shared_ptr< typename ActionT::Result >  )
inlineprotectedvirtual

Optional user-provided function to process the action result after the action has finished.

If no user-defined implementation is provided, then no additional processing will be performed on succeeding action results and this function will always return true.

Parameters
resultAction result message to process.
Returns
By default, always returns true. If a user-defined implementation of this function is provided, returns true or false if the result was processed successfully, or an error message if the result could not be processed. Note that the criteria for success or failure in this case is defined by the user's implementation of this function.

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