40#include <rclcpp/rclcpp.hpp>
56 bool sendTrajectory(
const moveit_msgs::msg::RobotTrajectory& trajectory)
override
58 RCLCPP_ERROR_STREAM(logger_,
"This controller handle does not support trajectory execution.");
86 const rclcpp::Logger logger_;
MoveIt sends commands to a controller via a handle that satisfies this interface.
MoveItControllerHandle(const std::string &name)
Each controller has a name. The handle is initialized with that name.
moveit_controller_manager::ExecutionStatus getLastExecutionStatus() override
Gets the last trajectory execution status.
bool waitForExecution(const rclcpp::Duration &) override
Function called when the TrajectoryExecutionManager waits for a trajectory to finish.
bool sendTrajectory(const moveit_msgs::msg::RobotTrajectory &trajectory) override
Send a trajectory to the controller.
bool cancelExecution() override
Cancel the execution of any motion using this controller.
EmptyControllerHandle(const std::string &name, const std::string &logger_name)
Namespace for the base class of a MoveIt controller manager.
The reported execution status.