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

Takes an MTC Solution message via an input data port, and executes the lowest-cost trajectory in that Solution using the MTC ExecuteTaskSolution MoveGroup capability's /execute_task_solution action server. More...

#include <execute_mtc_task.hpp>

Inheritance diagram for moveit_studio::behaviors::ExecuteMTCTask:
Collaboration diagram for moveit_studio::behaviors::ExecuteMTCTask:

Public Member Functions

 ExecuteMTCTask (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources)
 
- Public Member Functions inherited from moveit_studio::behaviors::ActionClientBehaviorBase< ExecuteTaskSolution >
 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...
 

Static Public Member Functions

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

Additional Inherited Members

- Public Types inherited from moveit_studio::behaviors::ActionClientBehaviorBase< ExecuteTaskSolution >
using ClientGoalHandle = rclcpp_action::ClientGoalHandle< ExecuteTaskSolution >
 
- Protected Member Functions inherited from moveit_studio::behaviors::ActionClientBehaviorBase< ExecuteTaskSolution >
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< 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...
 
virtual std::string getAbortedMessage (const std::shared_ptr< const typename ActionT::Result >) const
 Optional user-provided function to retrieve and surface an error message from an aborted action server result. 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

Takes an MTC Solution message via an input data port, and executes the lowest-cost trajectory in that Solution using the MTC ExecuteTaskSolution MoveGroup capability's /execute_task_solution action server.

Data Port Name Port Type Object Type
solution Input moveit_task_constructor_msgs::msg::Solution

Constructor & Destructor Documentation

◆ ExecuteMTCTask()

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

Member Function Documentation

◆ metadata()

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

◆ providedPorts()

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

Required implementation of static providedPorts function.


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