Abstract Controller Interface.
More...
#include <controller_base.h>
|
enum controller_interface::ControllerBase:: { ... } | state_ |
| The current execution state of the controller. More...
|
|
Abstract Controller Interface.
Definition at line 49 of file controller_base.h.
The current execution state of the controller.
Enumerator |
---|
CONSTRUCTED |
|
INITIALIZED |
|
RUNNING |
|
Definition at line 151 of file controller_base.h.
controller_interface::ControllerBase::ControllerBase |
( |
| ) |
|
|
inline |
virtual controller_interface::ControllerBase::~ControllerBase |
( |
| ) |
|
|
inlinevirtual |
controller_interface::ControllerBase::ControllerBase |
( |
const ControllerBase & |
c | ) |
|
|
private |
Request that the controller be initialized.
- Parameters
-
| robot_hw | The robot hardware abstraction. |
| root_nh | A NodeHandle in the root of the controller manager namespace. This is where the ROS interfaces are setup (publishers, subscribers, services). |
| controller_nh | A NodeHandle in the namespace of the controller. This is where the controller-specific configuration resides. |
[out] | claimed_resources | The resources claimed by this controller. They can belong to multiple hardware interfaces. |
- Returns
- True if initialization was successful and the controller is ready to be started.
Implemented in controller_interface::MultiInterfaceController< T1, T2, T3, T4 >, and controller_interface::Controller< T >.
bool controller_interface::ControllerBase::isRunning |
( |
| ) |
|
|
inline |
Check if the controller is running.
- Returns
- true if the controller is running
Definition at line 82 of file controller_base.h.
virtual void controller_interface::ControllerBase::starting |
( |
const ros::Time & |
| ) |
|
|
inlinevirtual |
This is called from within the realtime thread just before the first call to update.
- Parameters
-
Definition at line 63 of file controller_base.h.
bool controller_interface::ControllerBase::startRequest |
( |
const ros::Time & |
time | ) |
|
|
inline |
virtual void controller_interface::ControllerBase::stopping |
( |
const ros::Time & |
| ) |
|
|
inlinevirtual |
This is called from within the realtime thread just after the last update call before the controller is stopped.
- Parameters
-
Definition at line 77 of file controller_base.h.
bool controller_interface::ControllerBase::stopRequest |
( |
const ros::Time & |
time | ) |
|
|
inline |
virtual void controller_interface::ControllerBase::update |
( |
const ros::Time & |
time, |
|
|
const ros::Duration & |
period |
|
) |
| |
|
pure virtual |
This is called periodically by the realtime thread when the controller is running.
- Parameters
-
time | The current time |
period | The time passed since the last call to update |
void controller_interface::ControllerBase::updateRequest |
( |
const ros::Time & |
time, |
|
|
const ros::Duration & |
period |
|
) |
| |
|
inline |
enum { ... } controller_interface::ControllerBase::state_ |
The current execution state of the controller.
The documentation for this class was generated from the following file: