#include <controller.h>
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) | |
Controller & | operator= (const Controller &c) |
Private Attributes | |
ControllerProvider * | contr_prov_ |
Definition at line 53 of file controller.h.
anonymous enum |
Definition at line 56 of file controller.h.
anonymous enum |
Definition at line 166 of file controller.h.
pr2_controller_interface::Controller::Controller | ( | ) | [inline] |
Definition at line 58 of file controller.h.
virtual pr2_controller_interface::Controller::~Controller | ( | ) | [inline, virtual] |
Definition at line 59 of file controller.h.
pr2_controller_interface::Controller::Controller | ( | const Controller & | c | ) | [private] |
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.
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.
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. |
bool pr2_controller_interface::Controller::initRequest | ( | ControllerProvider * | cp, |
pr2_mechanism_model::RobotState * | robot, | ||
ros::NodeHandle & | n | ||
) | [inline] |
Definition at line 146 of file controller.h.
bool pr2_controller_interface::Controller::isRunning | ( | ) | [inline] |
Check if the controller is running.
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] |
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.
bool pr2_controller_interface::Controller::startRequest | ( | ) | [inline] |
Definition at line 121 of file controller.h.
void pr2_controller_interface::Controller::stopping | ( | const ros::Time & | time | ) | [inline] |
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.
bool pr2_controller_interface::Controller::stopRequest | ( | ) | [inline] |
Definition at line 134 of file controller.h.
void pr2_controller_interface::Controller::update | ( | const ros::Time & | time, |
const ros::Duration & | period | ||
) | [inline] |
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.
void pr2_controller_interface::Controller::updateRequest | ( | ) | [inline] |
Definition at line 115 of file controller.h.
Definition at line 164 of file controller.h.
Definition at line 164 of file controller.h.
Definition at line 171 of file controller.h.
enum { ... } pr2_controller_interface::Controller::state_ |