41 #include <moveit_msgs/msg/robot_trajectory.hpp>
43 #include <rclcpp/rclcpp.hpp>
71 explicit operator bool()
const
128 virtual bool sendTrajectory(
const moveit_msgs::msg::RobotTrajectory& trajectory) = 0;
141 virtual bool waitForExecution(
const rclcpp::Duration& timeout = rclcpp::Duration::from_nanoseconds(-1)) = 0;
186 virtual void initialize(
const rclcpp::Node::SharedPtr& node) = 0;
211 const std::vector<std::string>& deactivate) = 0;
MoveIt sends commands to a controller via a handle that satisfies this interface.
virtual ExecutionStatus getLastExecutionStatus()=0
Return the execution status of the last trajectory sent to the controller.
const std::string & getName() const
Get the name of the controller this handle can send commands to.
virtual ~MoveItControllerHandle()
virtual bool waitForExecution(const rclcpp::Duration &timeout=rclcpp::Duration::from_nanoseconds(-1))=0
Wait for the current execution to complete, or until the timeout is reached.
virtual bool cancelExecution()=0
Cancel the execution of any motion using this controller.
virtual bool sendTrajectory(const moveit_msgs::msg::RobotTrajectory &trajectory)=0
Send a trajectory to the controller.
MoveItControllerHandle(const std::string &name)
Each controller has a name. The handle is initialized with that name.
MoveIt does not enforce how controllers are implemented. To make your controllers usable by MoveIt,...
virtual void getActiveControllers(std::vector< std::string > &names)=0
Get the list of active controllers.
virtual void getControllersList(std::vector< std::string > &names)=0
Get the list of known controller names.
virtual MoveItControllerHandlePtr getControllerHandle(const std::string &name)=0
Return a given named controller.
virtual ControllerState getControllerState(const std::string &name)=0
Report the state of a controller, given its name.
virtual ~MoveItControllerManager()
MoveItControllerManager()
Default constructor. This needs to have no arguments so that the plugin system can construct the obje...
virtual bool switchControllers(const std::vector< std::string > &activate, const std::vector< std::string > &deactivate)=0
Activate and deactivate controllers.
virtual void getControllerJoints(const std::string &name, std::vector< std::string > &joints)=0
Report the joints a controller operates on, given the controller name.
virtual void initialize(const rclcpp::Node::SharedPtr &node)=0
Namespace for the base class of a MoveIt controller manager.
MOVEIT_CLASS_FORWARD(MoveItControllerHandle)
The reported execution status.
ExecutionStatus(Value value=UNKNOWN)
std::string asString() const
Convert the execution status to a string.
Each controller known to MoveIt has a state. This structure describes that controller's state.
bool default_
It is often the case that multiple controllers could be used to execute a motion. Marking a controlle...
bool active_
A controller can be active or inactive. This means that MoveIt could activate the controller when nee...