37 #ifndef MOVEIT_MOVEIT_CONTROLLER_MANAGER_ 38 #define MOVEIT_MOVEIT_CONTROLLER_MANAGER_ 42 #include <moveit_msgs/RobotTrajectory.h> 71 explicit operator bool()
const 126 virtual bool sendTrajectory(
const moveit_msgs::RobotTrajectory&
trajectory) = 0;
130 virtual bool cancelExecution() = 0;
184 virtual MoveItControllerHandlePtr getControllerHandle(
const std::string& name) = 0;
187 virtual void getControllersList(std::vector<std::string>& names) = 0;
192 virtual void getActiveControllers(std::vector<std::string>& names) = 0;
196 virtual void getControllerJoints(
const std::string& name, std::vector<std::string>& joints) = 0;
199 virtual ControllerState getControllerState(
const std::string& name) = 0;
202 virtual bool switchControllers(
const std::vector<std::string>& activate,
203 const std::vector<std::string>& deactivate) = 0;
MoveIt! sends commands to a controller via a handle that satisfies this interface.
ExecutionStatus(Value value=UNKNOWN)
virtual ~MoveItControllerManager()
bool default_
It is often the case that multiple controllers could be used to execute a motion. Marking a controlle...
const std::string & getName() const
Get the name of the controller this handle can send commands to.
virtual ~MoveItControllerHandle()
MoveIt! does not enforce how controllers are implemented. To make your controllers usable by MoveIt...
robot_trajectory::RobotTrajectory trajectory(rmodel,"right_arm")
bool active_
A controller can be active or inactive. This means that MoveIt! could activate the controller when ne...
MoveItControllerManager()
Default constructor. This needs to have no arguments so that the plugin system can construct the obje...
Each controller known to MoveIt! has a state. This structure describes that controller's state...
MoveItControllerHandle(const std::string &name)
Each controller has a name. The handle is initialized with that name.
MOVEIT_CLASS_FORWARD(MoveItControllerHandle)
The reported execution status.
Namespace for the base class of a MoveIt! controller manager.
std::string asString() const
Convert the execution status to a string.