Abstract Controller Interface. More...
#include <controller_base.h>
Public Types | |
enum | { CONSTRUCTED, INITIALIZED, RUNNING } |
The current execution state of the controller. More... | |
Public Member Functions | |
ControllerBase () | |
virtual | ~ControllerBase () |
Real-Time Safe Functions | |
virtual void | starting (const ros::Time &time) |
This is called from within the realtime thread just before the first call to update. | |
virtual void | update (const ros::Time &time, const ros::Duration &period)=0 |
This is called periodically by the realtime thread when the controller is running. | |
virtual void | stopping (const ros::Time &time) |
This is called from within the realtime thread just after the last update call before the controller is stopped. | |
bool | isRunning () |
Check if the controller is running. | |
void | updateRequest (const ros::Time &time, const ros::Duration &period) |
Calls update only if this controller is running. | |
bool | startRequest (const ros::Time &time) |
Calls starting only if this controller is initialized or already running. | |
bool | stopRequest (const ros::Time &time) |
Calls stopping only if this controller is initialized or already running. | |
Non Real-Time Safe Functions | |
virtual std::string | getHardwareInterfaceType () const =0 |
Get the name of this controller's hardware interface type. | |
virtual bool | initRequest (hardware_interface::RobotHW *hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh, std::set< std::string > &claimed_resources)=0 |
Request that the controller be initialized. | |
Public Attributes | |
enum controller_interface::ControllerBase:: { ... } | state_ |
The current execution state of the controller. | |
Private Member Functions | |
ControllerBase (const ControllerBase &c) | |
ControllerBase & | operator= (const ControllerBase &c) |
Abstract Controller Interface.
Definition at line 49 of file controller_base.h.
anonymous enum |
The current execution state of the controller.
Definition at line 149 of file controller_base.h.
controller_interface::ControllerBase::ControllerBase | ( | ) | [inline] |
Definition at line 52 of file controller_base.h.
virtual controller_interface::ControllerBase::~ControllerBase | ( | ) | [inline, virtual] |
Definition at line 53 of file controller_base.h.
controller_interface::ControllerBase::ControllerBase | ( | const ControllerBase & | c | ) | [private] |
virtual std::string controller_interface::ControllerBase::getHardwareInterfaceType | ( | ) | const [pure virtual] |
Get the name of this controller's hardware interface type.
Implemented in controller_interface::Controller< T >.
virtual bool controller_interface::ControllerBase::initRequest | ( | hardware_interface::RobotHW * | hw, |
ros::NodeHandle & | root_nh, | ||
ros::NodeHandle & | controller_nh, | ||
std::set< std::string > & | claimed_resources | ||
) | [pure virtual] |
Request that the controller be initialized.
hw | The hardware interface to the robot. | |
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. |
Implemented in controller_interface::Controller< T >.
bool controller_interface::ControllerBase::isRunning | ( | ) | [inline] |
Check if the controller is running.
Definition at line 82 of file controller_base.h.
ControllerBase& controller_interface::ControllerBase::operator= | ( | const ControllerBase & | c | ) | [private] |
virtual void controller_interface::ControllerBase::starting | ( | const ros::Time & | time | ) | [inline, virtual] |
This is called from within the realtime thread just before the first call to update.
time | The current time |
Definition at line 63 of file controller_base.h.
bool controller_interface::ControllerBase::startRequest | ( | const ros::Time & | time | ) | [inline] |
Calls starting only if this controller is initialized or already running.
Definition at line 95 of file controller_base.h.
virtual void controller_interface::ControllerBase::stopping | ( | const ros::Time & | time | ) | [inline, virtual] |
This is called from within the realtime thread just after the last update call before the controller is stopped.
time | The current time |
Definition at line 77 of file controller_base.h.
bool controller_interface::ControllerBase::stopRequest | ( | const ros::Time & | time | ) | [inline] |
Calls stopping only if this controller is initialized or already running.
Definition at line 108 of file controller_base.h.
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.
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] |
Calls update only if this controller is running.
Definition at line 88 of file controller_base.h.
enum { ... } controller_interface::ControllerBase::state_ |
The current execution state of the controller.