Public Member Functions | Protected Member Functions | List of all members
controller_interface::Controller< T > Class Template Reference

Controller with a specific hardware interface More...

#include <controller.h>

Inheritance diagram for controller_interface::Controller< T >:
Inheritance graph
[legend]

Public Member Functions

virtual bool init (T *, ros::NodeHandle &)
 The init function is called to initialize the controller from a non-realtime thread with a pointer to the hardware interface, itself, instead of a pointer to a RobotHW. More...
 
virtual bool init (T *, ros::NodeHandle &, ros::NodeHandle &)
 The init function is called to initialize the controller from a non-realtime thread with a pointer to the hardware interface, itself, instead of a pointer to a RobotHW. More...
 
- Public Member Functions inherited from controller_interface::ControllerBase
 ControllerBase ()=default
 
 ControllerBase (const ControllerBase &)=delete
 
 ControllerBase (ControllerBase &&)=delete
 
ControllerBaseoperator= (const ControllerBase &)=delete
 
ControllerBaseoperator= (ControllerBase &&)=delete
 
virtual ~ControllerBase ()=default
 
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...
 

Protected Member Functions

std::string getHardwareInterfaceType () const
 Get the name of this controller's hardware interface type. More...
 
bool initRequest (hardware_interface::RobotHW *robot_hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh, ClaimedResources &claimed_resources) override
 Initialize the controller from a RobotHW pointer. More...
 

Additional Inherited Members

- Public Types inherited from controller_interface::ControllerBase
enum  {
  CONSTRUCTED, INITIALIZED, RUNNING, STOPPED,
  WAITING, ABORTED
}
 The current execution state of the controller. More...
 
typedef std::vector< hardware_interface::InterfaceResourcesClaimedResources
 
- Public Attributes inherited from controller_interface::ControllerBase
enum controller_interface::ControllerBase:: { ... }  state_ = {CONSTRUCTED}
 The current execution state of the controller. More...
 

Detailed Description

template<class T>
class controller_interface::Controller< T >

Controller with a specific hardware interface

Template Parameters
TThe hardware interface type used by this controller. This enforces semantic compatibility between the controller and the hardware it's meant to control.

Definition at line 52 of file controller.h.

Member Function Documentation

◆ getHardwareInterfaceType()

template<class T >
std::string controller_interface::Controller< T >::getHardwareInterfaceType ( ) const
inlineprotected

Get the name of this controller's hardware interface type.

Definition at line 134 of file controller.h.

◆ init() [1/2]

template<class T >
virtual bool controller_interface::Controller< T >::init ( T *  ,
ros::NodeHandle  
)
inlinevirtual

The init function is called to initialize the controller from a non-realtime thread with a pointer to the hardware interface, itself, instead of a pointer to a RobotHW.

Parameters
hwThe specific hardware interface used by this controller.
controller_nhA 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.

Definition at line 69 of file controller.h.

◆ init() [2/2]

template<class T >
virtual bool controller_interface::Controller< T >::init ( T *  ,
ros::NodeHandle ,
ros::NodeHandle  
)
inlinevirtual

The init function is called to initialize the controller from a non-realtime thread with a pointer to the hardware interface, itself, instead of a pointer to a RobotHW.

Parameters
hwThe specific hardware interface used by this controller.
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.
Returns
True if initialization was successful and the controller is ready to be started.

Definition at line 86 of file controller.h.

◆ initRequest()

template<class T >
bool controller_interface::Controller< T >::initRequest ( hardware_interface::RobotHW robot_hw,
ros::NodeHandle root_nh,
ros::NodeHandle controller_nh,
ClaimedResources claimed_resources 
)
inlineoverrideprotectedvirtual

Initialize the controller from a RobotHW pointer.

This calls init with the hardware interface for this controller if it can extract the correct interface from robot_hw.

Implements controller_interface::ControllerBase.

Definition at line 96 of file controller.h.


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


controller_interface
Author(s): Wim Meeussen
autogenerated on Mon Feb 28 2022 23:30:15