31 #ifndef ROBOT_CONTROLLERS_INTERFACE_CONTROLLER_H 32 #define ROBOT_CONTROLLERS_INTERFACE_CONTROLLER_H 36 #include <boost/shared_ptr.hpp> 92 if (
name_.at(0) ==
'/')
102 virtual bool start() = 0;
111 virtual bool stop(
bool force) = 0;
119 virtual bool reset() = 0;
137 return "UnknownType";
155 #endif // ROBOT_CONTROLLERS_INTERFACE_CONTROLLER_H Controller()
Default constructor, does almost nothing, all setup is done in init().
virtual bool start()=0
Attempt to start the controller. This should be called only by the ControllerManager instance...
virtual bool reset()=0
Cleanly reset the controller to it's initial state. Some controllers may choose to stop themselves...
virtual std::vector< std::string > getCommandedNames()=0
Get the names of joints/controllers which this controller commands.
virtual void update(const ros::Time &time, const ros::Duration &dt)=0
This is the update loop for the controller.
boost::shared_ptr< Controller > ControllerPtr
Base class for a controller manager.
const std::string & getNamespace() const
virtual std::string getType()
Get the type of this controller.
virtual std::vector< std::string > getClaimedNames()=0
Get the names of joints/controllers which this controller exclusively claims.
Base class for a controller. Is derived from a Handle, so that controllers can be passed from Control...
virtual bool stop(bool force)=0
Attempt to stop the controller. This should be called only by the ControllerManager instance...
virtual int init(ros::NodeHandle &nh, ControllerManager *manager)
Initialize the controller and any required data structures.
std::string getName()
Get the name of this controller.
virtual ~Controller()
Ensure proper cleanup with virtual destructor.