|
MoveIt Pro API
Core Behaviors for MoveIt Pro
|
Abstract interface for trajectory execution pipelines. More...
#include <execute_mtc_solution.hpp>

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. | |
Abstract interface for trajectory execution pipelines.
This interface hides the specific ActionType details and allows for different trajectory execution implementations (JTAC, JTC-like, etc.).
|
virtualdefault |
|
pure virtual |
Cancel the currently active trajectory execution.
Implemented in moveit_studio::behaviors::JTACTrajectoryExecutor, and moveit_studio::behaviors::StandardTrajectoryExecutor.
|
pure virtual |
Execute a trajectory with the given parameters.
| joint_trajectory | The joint trajectory to execute. |
| admittance_params | Admittance control parameters (may be ignored by non-JTAC implementations). |
| goal_tolerance | Optional goal position tolerance. |
| path_tolerance | Optional path position tolerance. |
| absolute_force_torque_threshold | Optional force/torque limits (JTAC-specific). |
| goal_duration_tolerance_seconds | Timeout in seconds (negative means wait indefinitely). |
| index | Sub-trajectory index for error reporting. |
Implemented in moveit_studio::behaviors::JTACTrajectoryExecutor, and moveit_studio::behaviors::StandardTrajectoryExecutor.
|
pure virtual |
Initialize the trajectory execution pipeline.
| action_name | Name of the trajectory action server |
Implemented in moveit_studio::behaviors::JTACTrajectoryExecutor, and moveit_studio::behaviors::StandardTrajectoryExecutor.