#include <controller.h>
|
| | 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. More...
|
| |
| 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. More...
|
| |
| bool | initRequest (ControllerProvider *cp, pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n) |
| |
| bool | isRunning () |
| | Check if the controller is running. More...
|
| |
| void | starting (const ros::Time &time) |
| |
| virtual void | starting () |
| | The starting method is called just before the first update from within the realtime thread. More...
|
| |
| 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. More...
|
| |
| 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. More...
|
| |
| void | updateRequest () |
| |
| virtual | ~Controller () |
| |
| | Controller () |
| |
| virtual bool | init (pr2_mechanism_model::RobotState *, ros::NodeHandle &, ros::NodeHandle &) |
| |
| | ControllerBase () |
| |
| bool | isRunning () |
| |
| bool | isRunning () |
| |
| bool | startRequest (const ros::Time &time) |
| |
| bool | startRequest (const ros::Time &time) |
| |
| bool | stopRequest (const ros::Time &time) |
| |
| bool | stopRequest (const ros::Time &time) |
| |
| void | updateRequest (const ros::Time &time, const ros::Duration &period) |
| |
| void | updateRequest (const ros::Time &time, const ros::Duration &period) |
| |
| virtual | ~ControllerBase () |
| |
Definition at line 53 of file controller.h.
| Enumerator |
|---|
| BEFORE_ME |
|
| AFTER_ME |
|
Definition at line 56 of file controller.h.
| Enumerator |
|---|
| CONSTRUCTED |
|
| INITIALIZED |
|
| RUNNING |
|
Definition at line 166 of file controller.h.
| pr2_controller_interface::Controller::Controller |
( |
| ) |
|
|
inline |
| virtual pr2_controller_interface::Controller::~Controller |
( |
| ) |
|
|
inlinevirtual |
| pr2_controller_interface::Controller::Controller |
( |
const Controller & |
c | ) |
|
|
private |
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
-
| 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.
Reimplemented from controller_interface::Controller< pr2_mechanism_model::RobotState >.
| bool pr2_controller_interface::Controller::isRunning |
( |
| ) |
|
|
inline |
Check if the controller is running.
Definition at line 110 of file controller.h.
| void pr2_controller_interface::Controller::starting |
( |
const ros::Time & |
time | ) |
|
|
inlinevirtual |
| virtual void pr2_controller_interface::Controller::starting |
( |
| ) |
|
|
inlinevirtual |
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 |
| void pr2_controller_interface::Controller::stopping |
( |
const ros::Time & |
time | ) |
|
|
inlinevirtual |
| virtual void pr2_controller_interface::Controller::stopping |
( |
| ) |
|
|
inlinevirtual |
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 |
| 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 |
| std::vector<std::string> pr2_controller_interface::Controller::after_list_ |
| std::vector<std::string> pr2_controller_interface::Controller::before_list_ |
| enum { ... } pr2_controller_interface::Controller::state_ |
The documentation for this class was generated from the following file: