MoveIt Pro Behavior
Core Behaviors for MoveIt Pro
Loading...
Searching...
No Matches
moveit_studio::behaviors::GetPoseFromUser Class Referencefinal

Sends a service request to the UI so that the user can click in the UI and return a pose. More...

#include <get_pose_from_user.hpp>

Inheritance diagram for moveit_studio::behaviors::GetPoseFromUser:
Collaboration diagram for moveit_studio::behaviors::GetPoseFromUser:

Public Member Functions

 GetPoseFromUser (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources)
 Constructor for the GetPoseFromUser behavior.
 
 GetPoseFromUser (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources, std::unique_ptr< ClientInterfaceBase< GetPoseFromUserSrv > > client_interface)
 
- Public Member Functions inherited from moveit_studio::behaviors::ServiceClientBehaviorBase< GetPoseFromUserSrv >
 ServiceClientBehaviorBase (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources)
 Constructs ServiceClientBehaviorBase using the RclcppClientInterface.
 
 ServiceClientBehaviorBase (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources, std::unique_ptr< ClientInterfaceBase< GetPoseFromUserSrv > > client_interface)
 Constructs ServiceClientBehaviorBase using a user-provided implementation of ClientInterfaceBase.
 
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().
 
BT::NodeStatus onRunning () override
 Required implementation of BT::StatefulActionNode::onRunning().
 
void onHalted () override
 Required implementation of BT::StatefulActionNode::onHalted().
 
void resetStatus ()
 Resets the internal status of this node.
 
- 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.
 

Static Public Member Functions

static BT::PortsList providedPorts ()
 
static BT::KeyValueVector metadata ()
 

Additional Inherited Members

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

Detailed Description

Sends a service request to the UI so that the user can click in the UI and return a pose.

Data Port Name Port Type Object Type
view_name Input std::string
pose_prompt Input std::string
is_normal Input bool
user_pose Output geometry_msgs::msg::PoseStamped

Constructor & Destructor Documentation

◆ GetPoseFromUser() [1/2]

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

Constructor for the GetPoseFromUser behavior.

Parameters
nameSee SharedResourcesNode
configSee SharedResourcesNode
shared_resourcesSee SharedResourcesNode

◆ GetPoseFromUser() [2/2]

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

Member Function Documentation

◆ metadata()

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

◆ providedPorts()

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

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