Base class for a controller. Is derived from a Handle, so that controllers can be passed from ControllerManager::getHandle(), thus allowing controllers to access other controllers (to stack their commands. More...
#include <controller.h>
Public Member Functions | |
Controller () | |
Default constructor, does almost nothing, all setup is done in init(). | |
virtual std::vector< std::string > | getClaimedNames ()=0 |
Get the names of joints/controllers which this controller exclusively claims. | |
virtual std::vector< std::string > | getCommandedNames ()=0 |
Get the names of joints/controllers which this controller commands. | |
std::string | getName () |
Get the name of this controller. | |
virtual std::string | getType () |
Get the type of this controller. | |
virtual int | init (ros::NodeHandle &nh, ControllerManager *manager) |
Initialize the controller and any required data structures. | |
virtual bool | reset ()=0 |
Cleanly reset the controller to it's initial state. Some controllers may choose to stop themselves. This is mainly used in the case of the the robot exiting some fault condition. | |
virtual bool | start ()=0 |
Attempt to start the controller. This should be called only by the ControllerManager instance. | |
virtual bool | stop (bool force)=0 |
Attempt to stop the controller. This should be called only by the ControllerManager instance. | |
virtual void | update (const ros::Time &time, const ros::Duration &dt)=0 |
This is the update loop for the controller. | |
virtual | ~Controller () |
Ensure proper cleanup with virtual destructor. | |
Private Attributes | |
std::string | name_ |
Base class for a controller. Is derived from a Handle, so that controllers can be passed from ControllerManager::getHandle(), thus allowing controllers to access other controllers (to stack their commands.
Definition at line 66 of file controller.h.
robot_controllers::Controller::Controller | ( | ) | [inline] |
Default constructor, does almost nothing, all setup is done in init().
Definition at line 72 of file controller.h.
virtual robot_controllers::Controller::~Controller | ( | ) | [inline, virtual] |
Ensure proper cleanup with virtual destructor.
Definition at line 77 of file controller.h.
virtual std::vector<std::string> robot_controllers::Controller::getClaimedNames | ( | ) | [pure virtual] |
Get the names of joints/controllers which this controller exclusively claims.
virtual std::vector<std::string> robot_controllers::Controller::getCommandedNames | ( | ) | [pure virtual] |
Get the names of joints/controllers which this controller commands.
std::string robot_controllers::Controller::getName | ( | ) | [inline, virtual] |
Get the name of this controller.
Implements robot_controllers::Handle.
Definition at line 129 of file controller.h.
virtual std::string robot_controllers::Controller::getType | ( | ) | [inline, virtual] |
Get the type of this controller.
Definition at line 135 of file controller.h.
virtual int robot_controllers::Controller::init | ( | ros::NodeHandle & | nh, |
ControllerManager * | manager | ||
) | [inline, virtual] |
Initialize the controller and any required data structures.
nh | Node handle for this controller. |
manager | The controller manager instance, this is needed for the controller to get information about joints, etc. |
Definition at line 88 of file controller.h.
virtual bool robot_controllers::Controller::reset | ( | ) | [pure virtual] |
Cleanly reset the controller to it's initial state. Some controllers may choose to stop themselves. This is mainly used in the case of the the robot exiting some fault condition.
virtual bool robot_controllers::Controller::start | ( | ) | [pure virtual] |
Attempt to start the controller. This should be called only by the ControllerManager instance.
virtual bool robot_controllers::Controller::stop | ( | bool | force | ) | [pure virtual] |
Attempt to stop the controller. This should be called only by the ControllerManager instance.
force | Should we force the controller to stop? Some controllers may wish to continue running until they absolutely have to stop. |
virtual void robot_controllers::Controller::update | ( | const ros::Time & | time, |
const ros::Duration & | dt | ||
) | [pure virtual] |
This is the update loop for the controller.
time | The system time. |
dt | The timestep since last call to update. |
std::string robot_controllers::Controller::name_ [private] |
Definition at line 147 of file controller.h.