MoveIt Pro Behavior
Core Behaviors for MoveIt Pro
moveit_studio::behaviors::RetrievePoseParameter Class Referencefinal

Retrieves a stamped pose from the MoveIt Pro parameter manager node. More...

#include <retrieve_pose_parameter.hpp>

Inheritance diagram for moveit_studio::behaviors::RetrievePoseParameter:
Collaboration diagram for moveit_studio::behaviors::RetrievePoseParameter:

Public Member Functions

 RetrievePoseParameter (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources)
 
 RetrievePoseParameter (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources, std::unique_ptr< ClientInterfaceBase< RetrievePose >> client_interface)
 
- Public Member Functions inherited from moveit_studio::behaviors::ServiceClientBehaviorBase< RetrievePose >
 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< RetrievePose >> 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 Member Functions

static BT::PortsList providedPorts ()
 Required implementation of the static providedPorts function. More...
 
static BT::KeyValueVector metadata ()
 

Additional Inherited Members

- Static Public Attributes inherited from moveit_studio::behaviors::ServiceClientBehaviorBase< RetrievePose >
static constexpr std::chrono::seconds kTimeoutWaitForServiceServer
 
- Protected Member Functions inherited from moveit_studio::behaviors::ServiceClientBehaviorBase< RetrievePose >
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< 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
void notifyCanHalt ()
 Called when runAsync() finishes to notify onHalted() that the async process has finished. More...
 
- Protected Attributes inherited from moveit_studio::behaviors::SharedResourcesNode< BT::StatefulActionNode >
std::shared_ptr< BehaviorContextshared_resources_
 

Detailed Description

Retrieves a stamped pose from the MoveIt Pro parameter manager node.

If no parameter is retrieved within the provided "timeout_sec" parameter, this Behavior returns FAILURE. Specifying zero timeout (default) makes this Behavior wait indefinitely to retrieve the parameter.

Data Port Name Port Type Object Type
timeout_sec input double
pose output geometry_msgs::msg::PoseStamped

Constructor & Destructor Documentation

◆ RetrievePoseParameter() [1/2]

moveit_studio::behaviors::RetrievePoseParameter::RetrievePoseParameter ( const std::string &  name,
const BT::NodeConfiguration &  config,
const std::shared_ptr< BehaviorContext > &  shared_resources 
)
explicit

◆ RetrievePoseParameter() [2/2]

moveit_studio::behaviors::RetrievePoseParameter::RetrievePoseParameter ( const std::string &  name,
const BT::NodeConfiguration &  config,
const std::shared_ptr< BehaviorContext > &  shared_resources,
std::unique_ptr< ClientInterfaceBase< RetrievePose >>  client_interface 
)
explicit

Member Function Documentation

◆ metadata()

BT::KeyValueVector moveit_studio::behaviors::RetrievePoseParameter::metadata ( )
static

◆ providedPorts()

BT::PortsList moveit_studio::behaviors::RetrievePoseParameter::providedPorts ( )
static

Required implementation of the static providedPorts function.

Returns
The list of input and output ports used by this Behavior.

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