pr2_controller_interface::Controller Class Reference

#include <controller.h>

List of all members.

Public Types

enum  { BEFORE_ME, AFTER_ME }
enum  { CONSTRUCTED, INITIALIZED, RUNNING }

Public Member Functions

 Controller ()
template<class ControllerType >
bool getController (const std::string &name, int sched, ControllerType *&c)
 Method to get access to another controller by name and type.
virtual bool init (pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)=0
 The init function is called to initialize the controller from a non-realtime thread.
bool initRequest (ControllerProvider *cp, pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)
bool isRunning ()
 Check if the controller is running.
virtual void starting ()
 The starting method is called just before the first update from within the realtime thread.
bool startRequest ()
virtual void stopping ()
 The stopping method is called by the realtime thread just after the last update call.
bool stopRequest ()
virtual void update (void)=0
 The update method is called periodically by the realtime thread when the controller is running.
void updateRequest ()
virtual ~Controller ()

Public Attributes

std::vector< std::string > after_list_
std::vector< std::string > before_list_
enum
pr2_controller_interface::Controller:: { ... }  
state_

Private Member Functions

 Controller (const Controller &c)
Controlleroperator= (const Controller &c)

Private Attributes

ControllerProvidercontr_prov_

Detailed Description

Definition at line 50 of file controller.h.


Member Enumeration Documentation

anonymous enum
Enumerator:
BEFORE_ME 
AFTER_ME 

Definition at line 50 of file controller.h.

anonymous enum
Enumerator:
CONSTRUCTED 
INITIALIZED 
RUNNING 

Definition at line 156 of file controller.h.


Constructor & Destructor Documentation

pr2_controller_interface::Controller::Controller (  )  [inline]

Definition at line 52 of file controller.h.

virtual pr2_controller_interface::Controller::~Controller (  )  [inline, virtual]

Definition at line 53 of file controller.h.

pr2_controller_interface::Controller::Controller ( const Controller c  )  [private]

Member Function Documentation

template<class ControllerType >
bool pr2_controller_interface::Controller::getController ( const std::string &  name,
int  sched,
ControllerType *&  c 
) [inline]

Method to get access to another controller by name and type.

Definition at line 80 of file controller.h.

virtual bool pr2_controller_interface::Controller::init ( pr2_mechanism_model::RobotState *  robot,
ros::NodeHandle &  n 
) [pure virtual]

The init function is called to initialize the controller from a non-realtime thread.

Parameters:
robot A RobotState object which can be used to read joint states and write out effort commands.
n A NodeHandle in the namespace from which the controller should read its configuration, and where it should set up its ROS interface.
Returns:
True if initialization was successful and the controller is ready to be started.
bool pr2_controller_interface::Controller::initRequest ( ControllerProvider cp,
pr2_mechanism_model::RobotState *  robot,
ros::NodeHandle &  n 
) [inline]

Definition at line 136 of file controller.h.

bool pr2_controller_interface::Controller::isRunning (  )  [inline]

Check if the controller is running.

Definition at line 100 of file controller.h.

Controller& pr2_controller_interface::Controller::operator= ( const Controller c  )  [private]
virtual void pr2_controller_interface::Controller::starting (  )  [inline, virtual]

The starting method is called just before the first update from within the realtime thread.

Definition at line 56 of file controller.h.

bool pr2_controller_interface::Controller::startRequest (  )  [inline]

Definition at line 111 of file controller.h.

virtual void pr2_controller_interface::Controller::stopping (  )  [inline, virtual]

The stopping method is called by the realtime thread just after the last update call.

Definition at line 62 of file controller.h.

bool pr2_controller_interface::Controller::stopRequest (  )  [inline]

Definition at line 124 of file controller.h.

virtual void pr2_controller_interface::Controller::update ( void   )  [pure virtual]

The update method is called periodically by the realtime thread when the controller is running.

void pr2_controller_interface::Controller::updateRequest (  )  [inline]

Definition at line 105 of file controller.h.


Member Data Documentation

Definition at line 154 of file controller.h.

Definition at line 154 of file controller.h.

Definition at line 161 of file controller.h.


The documentation for this class was generated from the following file:
 All Classes Namespaces Files Functions Variables Enumerator


pr2_controller_interface
Author(s): Wim Meeussen
autogenerated on Fri Jan 11 09:55:04 2013