Public Types | Public Member Functions | Public Attributes | Private Member Functions | Private Attributes
pr2_controller_interface::Controller Class Reference

#include <controller.h>

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

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.
void starting (const ros::Time &time)
virtual void starting ()
 The starting method is called just before the first update from within the realtime thread.
bool startRequest ()
void stopping (const ros::Time &time)
virtual void stopping ()
 The stopping method is called by the realtime thread just after the last update call.
bool stopRequest ()
void update (const ros::Time &time, const ros::Duration &period)
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 53 of file controller.h.


Member Enumeration Documentation

anonymous enum
Enumerator:
BEFORE_ME 
AFTER_ME 

Definition at line 56 of file controller.h.

anonymous enum
Enumerator:
CONSTRUCTED 
INITIALIZED 
RUNNING 

Definition at line 166 of file controller.h.


Constructor & Destructor Documentation


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 90 of file controller.h.

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

Parameters:
robotA RobotState object which can be used to read joint states and write out effort commands.
nA 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.

Reimplemented from controller_interface::Controller< pr2_mechanism_model::RobotState >.

Definition at line 146 of file controller.h.

Check if the controller is running.

Reimplemented from controller_interface::ControllerBase.

Definition at line 110 of file controller.h.

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

Reimplemented from controller_interface::ControllerBase.

Definition at line 61 of file controller.h.

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 66 of file controller.h.

Definition at line 121 of file controller.h.

void pr2_controller_interface::Controller::stopping ( const ros::Time time) [inline, virtual]

Reimplemented from controller_interface::ControllerBase.

Definition at line 63 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 72 of file controller.h.

Definition at line 134 of file controller.h.

void pr2_controller_interface::Controller::update ( const ros::Time time,
const ros::Duration period 
) [inline, virtual]

Implements controller_interface::ControllerBase.

Definition at line 62 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.

Definition at line 115 of file controller.h.


Member Data Documentation

Definition at line 164 of file controller.h.

Definition at line 164 of file controller.h.

Definition at line 171 of file controller.h.


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


pr2_controller_interface
Author(s): Wim Meeussen
autogenerated on Thu Jun 6 2019 21:11:35