MoveIt Pro API
Core Behaviors for MoveIt Pro
Loading...
Searching...
No Matches
moveit_studio::behaviors::ExecuteMTCSolution Class Referencefinal

Execute each joint trajectory contained in an MTC solution by sending sequential goals to a JTAC or JTC-like controller, depending on the value of execution_pipeline. After each subtrajectory succeeds, apply the corresponding planning scene diff so that scene updates from the MTC task persist. More...

#include <execute_mtc_solution.hpp>

Inheritance diagram for moveit_studio::behaviors::ExecuteMTCSolution:
Collaboration diagram for moveit_studio::behaviors::ExecuteMTCSolution:

Public Types

using ServiceClient = rclcpp::Client< moveit_msgs::srv::ApplyPlanningScene >
 

Public Member Functions

 ExecuteMTCSolution (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources)
 
std::shared_future< tl::expected< bool, std::string > > & getFuture () override
 Gets the shared future which is used to monitor the progress of the async process.
 
- 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 ()
 

Protected Member Functions

tl::expected< bool, std::string > doWork () override
 User-implemented function which handles executing the potentially-long-running process.
 
tl::expected< void, std::string > doHalt () override
 Optionally implement additional work needed to cleanly interrupt the async process.
 
- Protected Member Functions inherited from moveit_studio::behaviors::AsyncBehaviorBase
void notifyCanHalt ()
 Called when runAsync() finishes to notify onHalted() that the async process has finished.
 

Additional Inherited Members

- Protected Attributes inherited from moveit_studio::behaviors::SharedResourcesNode< BT::StatefulActionNode >
std::shared_ptr< BehaviorContextshared_resources_
 

Detailed Description

Execute each joint trajectory contained in an MTC solution by sending sequential goals to a JTAC or JTC-like controller, depending on the value of execution_pipeline. After each subtrajectory succeeds, apply the corresponding planning scene diff so that scene updates from the MTC task persist.

This behavior is useful when Motion Task Constructor stages rely on planning scene changes such as attaching or detaching collision objects and the execution pipeline must run through a compliant controller, or just a standard JTC-like controller.

The behavior processes each sub-trajectory in the MTC solution sequentially, sending them to the controller and applying any associated planning scene changes after successful execution.

Data Port Name Port Type Object Type
solution input moveit_task_constructor_msgs::msg::Solution
admittance_parameters_msg input moveit_pro_controllers_msgs::msg::AdmittanceParameters
controller_action_name input std::string
goal_position_tolerance input double
path_position_tolerance input double
absolute_force_torque_threshold input std::vector<double>
goal_duration_tolerance input double
apply_planning_scene_service input std::string
apply_start_scene input bool

Member Typedef Documentation

◆ ServiceClient

using moveit_studio::behaviors::ExecuteMTCSolution::ServiceClient = rclcpp::Client<moveit_msgs::srv::ApplyPlanningScene>

Constructor & Destructor Documentation

◆ ExecuteMTCSolution()

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

Member Function Documentation

◆ doHalt()

tl::expected< void, std::string > moveit_studio::behaviors::ExecuteMTCSolution::doHalt ( )
overrideprotectedvirtual

Optionally implement additional work needed to cleanly interrupt the async process.

The default implementation of this function is a no-op which will not interrupt the async process. This will mean that onHalted will wait until the process finishes before returning.

Returns
Return an empty tl::expected<void, std::string> if the additional work to halt was successful. Return an error message if something failed while doing additional work to halt.

Reimplemented from moveit_studio::behaviors::AsyncBehaviorBase.

◆ doWork()

tl::expected< bool, std::string > moveit_studio::behaviors::ExecuteMTCSolution::doWork ( )
overrideprotectedvirtual

User-implemented function which handles executing the potentially-long-running process.

This function is called within an async process in a separate thread.

Returns
A tl::expected which contains a bool indicating task success if the process completed successfully or was canceled, or an error message if the process failed unexpectedly.

Implements moveit_studio::behaviors::AsyncBehaviorBase.

◆ getFuture()

std::shared_future< tl::expected< bool, std::string > > & moveit_studio::behaviors::ExecuteMTCSolution::getFuture ( )
overridevirtual

Gets the shared future which is used to monitor the progress of the async process.

Classes derived from AsyncBehaviorBase must implement getFuture() so that it returns a shared_future class member.

This exists to prevent destruction of the derived class while the async process is still in-progress. If the derived class is destroyed, the definitions of the functions used within doWork() will be destroyed too, which will result in the virtual functions in the base class being called instead and cause a fault.

This function will force derived classes to add an instance of this type and return a reference to it. The base class can then use this virtual function to access the shared future in functions like onStart.

By adding this virtual function we're properly demonstrating how this future depends on things from the derived class and the natural flow of object lifetimes will do the hard work for us. The std::shared_future destructor will get the value of the future before the derived class is destructed assuming it's the last reference to the shared state. Doing it this way means neither the base nor derived class should need to implement a destructor which is a nice property to have.

Returns
Returns the shared_future, which should be owned by the child class.

Implements moveit_studio::behaviors::AsyncBehaviorBase.

◆ metadata()

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

◆ providedPorts()

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

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