Public Member Functions | List of all members
controller_interface::ControllerBase Class Referenceabstract

Abstract Controller Interface. More...

#include <controller_base.h>

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

Public Member Functions

 ControllerBase ()=default
 
 ControllerBase (const ControllerBase &)=delete
 
 ControllerBase (ControllerBase &&)=delete
 
ControllerBaseoperator= (const ControllerBase &)=delete
 
ControllerBaseoperator= (ControllerBase &&)=delete
 
virtual ~ControllerBase ()=default
 
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. More...
 
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. More...
 
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. More...
 
virtual void waiting (const ros::Time &)
 This is called from within the realtime thread while the controller is waiting to start. More...
 
virtual void aborting (const ros::Time &)
 This is called from within the realtime thread when the controller needs to be aborted. More...
 
bool isInitialized () const
 Check if the controller is initialized. More...
 
bool isRunning () const
 Check if the controller is running. More...
 
bool isStopped () const
 Check if the controller is stopped. More...
 
bool isWaiting () const
 Check if the controller is waiting. More...
 
bool isAborted () const
 Check if the controller is aborted. More...
 
void updateRequest (const ros::Time &time, const ros::Duration &period)
 Calls update only if this controller is running. More...
 
bool startRequest (const ros::Time &time)
 Calls starting unless this controller is just constructed. More...
 
bool stopRequest (const ros::Time &time)
 Calls stopping unless this controller is just constructed. More...
 
bool waitRequest (const ros::Time &time)
 Calls waiting unless this controller is just constructed. More...
 
bool abortRequest (const ros::Time &time)
 Calls abort unless this controller is just constructed. More...
 

Non Real-Time Safe Functions

enum  ControllerState {
  ControllerState::CONSTRUCTED, ControllerState::INITIALIZED, ControllerState::RUNNING, ControllerState::STOPPED,
  ControllerState::WAITING, ControllerState::ABORTED
}
 
typedef std::vector< hardware_interface::InterfaceResourcesClaimedResources
 
ControllerState state_ = ControllerState::CONSTRUCTED
 The current execution state of the controller. More...
 
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. More...
 

Detailed Description

Abstract Controller Interface.

Definition at line 48 of file controller_base.h.

Member Typedef Documentation

◆ ClaimedResources

Definition at line 218 of file controller_base.h.

Member Enumeration Documentation

◆ ControllerState

Enumerator
CONSTRUCTED 
INITIALIZED 
RUNNING 
STOPPED 
WAITING 
ABORTED 

Definition at line 243 of file controller_base.h.

Constructor & Destructor Documentation

◆ ControllerBase() [1/3]

controller_interface::ControllerBase::ControllerBase ( )
default

◆ ~ControllerBase()

virtual controller_interface::ControllerBase::~ControllerBase ( )
virtualdefault

◆ ControllerBase() [2/3]

controller_interface::ControllerBase::ControllerBase ( const ControllerBase )
delete

◆ ControllerBase() [3/3]

controller_interface::ControllerBase::ControllerBase ( ControllerBase &&  )
delete

Member Function Documentation

◆ aborting()

virtual void controller_interface::ControllerBase::aborting ( const ros::Time )
inlinevirtual

This is called from within the realtime thread when the controller needs to be aborted.

Parameters
timeThe current time

Definition at line 94 of file controller_base.h.

◆ abortRequest()

bool controller_interface::ControllerBase::abortRequest ( const ros::Time time)
inline

Calls abort unless this controller is just constructed.

Definition at line 197 of file controller_base.h.

◆ initRequest()

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< T >, and controller_interface::Controller< T >.

◆ isAborted()

bool controller_interface::ControllerBase::isAborted ( ) const
inline

Check if the controller is aborted.

Returns
true if the controller is aborted

Definition at line 131 of file controller_base.h.

◆ isInitialized()

bool controller_interface::ControllerBase::isInitialized ( ) const
inline

Check if the controller is initialized.

Returns
true if the controller is initialized

Definition at line 99 of file controller_base.h.

◆ isRunning()

bool controller_interface::ControllerBase::isRunning ( ) const
inline

Check if the controller is running.

Returns
true if the controller is running

Definition at line 107 of file controller_base.h.

◆ isStopped()

bool controller_interface::ControllerBase::isStopped ( ) const
inline

Check if the controller is stopped.

Returns
true if the controller is stopped

Definition at line 115 of file controller_base.h.

◆ isWaiting()

bool controller_interface::ControllerBase::isWaiting ( ) const
inline

Check if the controller is waiting.

Returns
true if the controller is waiting

Definition at line 123 of file controller_base.h.

◆ operator=() [1/2]

ControllerBase& controller_interface::ControllerBase::operator= ( const ControllerBase )
delete

◆ operator=() [2/2]

ControllerBase& controller_interface::ControllerBase::operator= ( ControllerBase &&  )
delete

◆ starting()

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
timeThe current time

Definition at line 66 of file controller_base.h.

◆ startRequest()

bool controller_interface::ControllerBase::startRequest ( const ros::Time time)
inline

Calls starting unless this controller is just constructed.

Definition at line 146 of file controller_base.h.

◆ stopping()

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
timeThe current time

Definition at line 80 of file controller_base.h.

◆ stopRequest()

bool controller_interface::ControllerBase::stopRequest ( const ros::Time time)
inline

Calls stopping unless this controller is just constructed.

Definition at line 163 of file controller_base.h.

◆ update()

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

◆ updateRequest()

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 137 of file controller_base.h.

◆ waiting()

virtual void controller_interface::ControllerBase::waiting ( const ros::Time )
inlinevirtual

This is called from within the realtime thread while the controller is waiting to start.

Parameters
timeThe current time

Definition at line 87 of file controller_base.h.

◆ waitRequest()

bool controller_interface::ControllerBase::waitRequest ( const ros::Time time)
inline

Calls waiting unless this controller is just constructed.

Definition at line 180 of file controller_base.h.

Member Data Documentation

◆ state_

ControllerState controller_interface::ControllerBase::state_ = ControllerState::CONSTRUCTED

The current execution state of the controller.

Definition at line 254 of file controller_base.h.


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


controller_interface
Author(s): Wim Meeussen
autogenerated on Tue Oct 15 2024 02:08:21