Class CpTrajectoryExecutor
Defined in File cp_trajectory_executor.hpp
Inheritance Relationships
Base Type
public smacc2::ISmaccComponent
Class Documentation
-
class CpTrajectoryExecutor : public smacc2::ISmaccComponent
Component for centralized trajectory execution.
This component provides a unified interface for executing trajectories with:
Automatic recording to CpTrajectoryHistory
Consistent error handling and event posting
Execution options (velocity/acceleration scaling)
Execution time tracking
Pattern: Executor with signals (like action clients)
Public Functions
-
CpTrajectoryExecutor() = default
-
virtual ~CpTrajectoryExecutor() = default
-
inline void onInitialize() override
Initialize the component and get references to required components/clients.
-
inline ExecutionResult execute(const moveit_msgs::msg::RobotTrajectory &trajectory, const ExecutionOptions &options = {})
Execute a trajectory synchronously.
- Parameters:
trajectory – The robot trajectory to execute
options – Execution configuration options
- Returns:
ExecutionResult with success status and error information
-
inline ExecutionResult executePlan(const moveit::planning_interface::MoveGroupInterface::Plan &plan, const ExecutionOptions &options = {})
Execute a motion plan synchronously.
Convenience method that accepts a MoveGroupInterface::Plan directly
- Parameters:
plan – The motion plan containing the trajectory
options – Execution configuration options
- Returns:
ExecutionResult with success status and error information
-
inline void cancel()
Cancel ongoing execution.
Note: This is a best-effort cancellation and may not immediately stop the robot
-
inline CpTrajectoryHistory *getTrajectoryHistory()
Get the trajectory history component.
- Returns:
Pointer to CpTrajectoryHistory, or nullptr if not available