Public Types | Public Member Functions | Public Attributes | Private Member Functions
controller_interface::ControllerBase Class Reference

Abstract Controller Interface. More...

#include <controller_base.h>

Inheritance diagram for controller_interface::ControllerBase:
Inheritance graph
[legend]

List of all members.

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 &)
 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 &)
 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.

Public Attributes

enum
controller_interface::ControllerBase:: { ... }  
state_
 The current execution state of the controller.

Private Member Functions

 ControllerBase (const ControllerBase &c)
ControllerBaseoperator= (const ControllerBase &c)

Non Real-Time Safe Functions

typedef std::vector
< hardware_interface::InterfaceResources
ClaimedResources
virtual bool initRequest (hardware_interface::RobotHW *robot_hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh, ClaimedResources &claimed_resources)=0
 Request that the controller be initialized.

Detailed Description

Abstract Controller Interface.

Definition at line 53 of file controller_base.h.


Member Typedef Documentation

Definition at line 129 of file controller_base.h.


Member Enumeration Documentation

anonymous enum

The current execution state of the controller.

Enumerator:
CONSTRUCTED 
INITIALIZED 
RUNNING 

Definition at line 155 of file controller_base.h.


Constructor & Destructor Documentation

Definition at line 56 of file controller_base.h.

Definition at line 57 of file controller_base.h.


Member Function Documentation

virtual bool controller_interface::ControllerBase::initRequest ( hardware_interface::RobotHW robot_hw,
ros::NodeHandle root_nh,
ros::NodeHandle controller_nh,
ClaimedResources claimed_resources 
) [pure virtual]

Request that the controller be initialized.

Parameters:
robot_hwThe robot hardware abstraction.
root_nhA NodeHandle in the root of the controller manager namespace. This is where the ROS interfaces are setup (publishers, subscribers, services).
controller_nhA NodeHandle in the namespace of the controller. This is where the controller-specific configuration resides.
[out]claimed_resourcesThe 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 >.

Check if the controller is running.

Returns:
true if the controller is running

Definition at line 86 of file controller_base.h.

ControllerBase& controller_interface::ControllerBase::operator= ( const ControllerBase c) [private]
virtual void controller_interface::ControllerBase::starting ( const ros::Time ) [inline, virtual]

This is called from within the realtime thread just before the first call to update.

Parameters:
timeThe current time

Definition at line 67 of file controller_base.h.

Calls starting only if this controller is initialized or already running.

Definition at line 99 of file controller_base.h.

virtual void controller_interface::ControllerBase::stopping ( const ros::Time ) [inline, virtual]

This is called from within the realtime thread just after the last update call before the controller is stopped.

Parameters:
timeThe current time

Definition at line 81 of file controller_base.h.

Calls stopping only if this controller is initialized or already running.

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

Parameters:
timeThe current time
periodThe 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 92 of file controller_base.h.


Member Data Documentation

The current execution state of the controller.


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


controller_interface
Author(s): Wim Meeussen
autogenerated on Thu Dec 1 2016 03:45:58