Go to the documentation of this file.
   41 #include <moveit_msgs/RobotTrajectory.h> 
   65   operator Value()
 const 
   70   explicit operator bool()
 const 
  104 class MoveItControllerHandle
 
  117   const std::string& 
getName()
 const 
  127   virtual bool sendTrajectory(
const moveit_msgs::RobotTrajectory& trajectory) = 0;
 
  161   struct ControllerState
 
  208                                  const std::vector<std::string>& deactivate) = 0;
 
  
Namespace for the base class of a MoveIt controller manager.
 
MoveItControllerHandle(const std::string &name)
Each controller has a name. The handle is initialized with that name.
 
virtual ControllerState getControllerState(const std::string &name)=0
Report the state of a controller, given its name.
 
MOVEIT_CLASS_FORWARD(MoveItControllerHandle)
 
virtual void getActiveControllers(std::vector< std::string > &names)=0
Get the list of active controllers.
 
virtual MoveItControllerHandlePtr getControllerHandle(const std::string &name)=0
Return a given named controller.
 
bool active_
A controller can be active or inactive. This means that MoveIt could activate the controller when nee...
 
virtual bool switchControllers(const std::vector< std::string > &activate, const std::vector< std::string > &deactivate)=0
Activate and deactivate controllers.
 
virtual void getControllersList(std::vector< std::string > &names)=0
Get the list of known controller names.
 
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.
 
virtual ~MoveItControllerManager()
 
virtual ~MoveItControllerHandle()
 
virtual ExecutionStatus getLastExecutionStatus()=0
Return the execution status of the last trajectory sent to the controller.
 
virtual bool cancelExecution()=0
Cancel the execution of any motion using this controller.
 
virtual bool sendTrajectory(const moveit_msgs::RobotTrajectory &trajectory)=0
Send a trajectory to the controller.
 
MoveIt does not enforce how controllers are implemented. To make your controllers usable by MoveIt,...
 
ExecutionStatus(Value value=UNKNOWN)
 
virtual bool waitForExecution(const ros::Duration &timeout=ros::Duration(0))=0
Wait for the current execution to complete, or until the timeout is reached.
 
virtual void getControllerJoints(const std::string &name, std::vector< std::string > &joints)=0
Report the joints a controller operates on, given the controller name.
 
The reported execution status.
 
const std::string & getName() const
Get the name of the controller this handle can send commands to.
 
bool default_
It is often the case that multiple controllers could be used to execute a motion. Marking a controlle...
 
std::string asString() const
Convert the execution status to a string.
 
moveit_core
Author(s): Ioan Sucan 
, Sachin Chitta , Acorn Pooley 
autogenerated on Sat May 3 2025 02:25:32