MoveIt Pro API
Core Behaviors for MoveIt Pro
Loading...
Searching...
No Matches
moveit_studio::behaviors::TrajectoryExecutionPipeline Class Referenceabstract

Abstract interface for trajectory execution pipelines. More...

#include <execute_mtc_solution.hpp>

Inheritance diagram for moveit_studio::behaviors::TrajectoryExecutionPipeline:

Public Member Functions

virtual ~TrajectoryExecutionPipeline ()=default
 
virtual tl::expected< bool, std::string > initialize (const std::string &action_name)=0
 Initialize the trajectory execution pipeline.
 
virtual tl::expected< bool, std::string > executeTrajectory (const trajectory_msgs::msg::JointTrajectory &joint_trajectory, const std::optional< moveit_pro_controllers_msgs::msg::AdmittanceParameters > &admittance_params, const std::optional< double > &goal_tolerance, const std::optional< double > &path_tolerance, const std::optional< std::vector< double > > &absolute_force_torque_threshold, double goal_duration_tolerance_seconds, std::size_t index)=0
 Execute a trajectory with the given parameters.
 
virtual tl::expected< void, std::string > cancelExecution ()=0
 Cancel the currently active trajectory execution.
 

Detailed Description

Abstract interface for trajectory execution pipelines.

This interface hides the specific ActionType details and allows for different trajectory execution implementations (JTAC, JTC-like, etc.).

Constructor & Destructor Documentation

◆ ~TrajectoryExecutionPipeline()

virtual moveit_studio::behaviors::TrajectoryExecutionPipeline::~TrajectoryExecutionPipeline ( )
virtualdefault

Member Function Documentation

◆ cancelExecution()

virtual tl::expected< void, std::string > moveit_studio::behaviors::TrajectoryExecutionPipeline::cancelExecution ( )
pure virtual

Cancel the currently active trajectory execution.

Returns
Success/failure with error message.

Implemented in moveit_studio::behaviors::JTACTrajectoryExecutor, and moveit_studio::behaviors::StandardTrajectoryExecutor.

◆ executeTrajectory()

virtual tl::expected< bool, std::string > moveit_studio::behaviors::TrajectoryExecutionPipeline::executeTrajectory ( const trajectory_msgs::msg::JointTrajectory &  joint_trajectory,
const std::optional< moveit_pro_controllers_msgs::msg::AdmittanceParameters > &  admittance_params,
const std::optional< double > &  goal_tolerance,
const std::optional< double > &  path_tolerance,
const std::optional< std::vector< double > > &  absolute_force_torque_threshold,
double  goal_duration_tolerance_seconds,
std::size_t  index 
)
pure virtual

Execute a trajectory with the given parameters.

Parameters
joint_trajectoryThe joint trajectory to execute.
admittance_paramsAdmittance control parameters (may be ignored by non-JTAC implementations).
goal_toleranceOptional goal position tolerance.
path_toleranceOptional path position tolerance.
absolute_force_torque_thresholdOptional force/torque limits (JTAC-specific).
goal_duration_tolerance_secondsTimeout in seconds (negative means wait indefinitely).
indexSub-trajectory index for error reporting.
Returns
Success/failure with error message

Implemented in moveit_studio::behaviors::JTACTrajectoryExecutor, and moveit_studio::behaviors::StandardTrajectoryExecutor.

◆ initialize()

virtual tl::expected< bool, std::string > moveit_studio::behaviors::TrajectoryExecutionPipeline::initialize ( const std::string &  action_name)
pure virtual

Initialize the trajectory execution pipeline.

Parameters
action_nameName of the trajectory action server
Returns
Success/failure with error message

Implemented in moveit_studio::behaviors::JTACTrajectoryExecutor, and moveit_studio::behaviors::StandardTrajectoryExecutor.


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