Public Member Functions | Private Attributes | List of all members
robot_controllers::Controller Class Referenceabstract

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>

Inheritance diagram for robot_controllers::Controller:
Inheritance graph
[legend]

Public Member Functions

 Controller ()
 Default constructor, does almost nothing, all setup is done in init(). More...
 
virtual std::vector< std::string > getClaimedNames ()=0
 Get the names of joints/controllers which this controller exclusively claims. More...
 
virtual std::vector< std::string > getCommandedNames ()=0
 Get the names of joints/controllers which this controller commands. More...
 
std::string getName ()
 Get the name of this controller. More...
 
virtual std::string getType ()
 Get the type of this controller. More...
 
virtual int init (ros::NodeHandle &nh, ControllerManager *manager)
 Initialize the controller and any required data structures. More...
 
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. More...
 
virtual bool start ()=0
 Attempt to start the controller. This should be called only by the ControllerManager instance. More...
 
virtual bool stop (bool force)=0
 Attempt to stop the controller. This should be called only by the ControllerManager instance. More...
 
virtual void update (const ros::Time &time, const ros::Duration &dt)=0
 This is the update loop for the controller. More...
 
virtual ~Controller ()
 Ensure proper cleanup with virtual destructor. More...
 
- Public Member Functions inherited from robot_controllers::Handle
 Handle ()
 
virtual ~Handle ()
 Ensure proper cleanup with virtual destructor. More...
 

Private Attributes

std::string name_
 

Detailed Description

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.

Constructor & Destructor Documentation

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 ( )
inlinevirtual

Ensure proper cleanup with virtual destructor.

Definition at line 77 of file controller.h.

Member Function Documentation

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 ( )
inlinevirtual

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 ( )
inlinevirtual

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 
)
inlinevirtual

Initialize the controller and any required data structures.

Parameters
nhNode handle for this controller.
managerThe controller manager instance, this is needed for the controller to get information about joints, etc.
Returns
0 if succesfully configured, negative values are error codes.

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.

Returns
True if successfully reset, false otherwise.
virtual bool robot_controllers::Controller::start ( )
pure virtual

Attempt to start the controller. This should be called only by the ControllerManager instance.

Returns
True if successfully started, false otherwise.
virtual bool robot_controllers::Controller::stop ( bool  force)
pure virtual

Attempt to stop the controller. This should be called only by the ControllerManager instance.

Parameters
forceShould we force the controller to stop? Some controllers may wish to continue running until they absolutely have to stop.
Returns
True if successfully stopped, false otherwise.
virtual void robot_controllers::Controller::update ( const ros::Time time,
const ros::Duration dt 
)
pure virtual

This is the update loop for the controller.

Parameters
timeThe system time.
dtThe timestep since last call to update.

Member Data Documentation

std::string robot_controllers::Controller::name_
private

Definition at line 147 of file controller.h.


The documentation for this class was generated from the following file:


robot_controllers_interface
Author(s): Michael Ferguson
autogenerated on Sun Sep 27 2020 03:22:36