Public Member Functions | Protected Member Functions | Private Member Functions
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]

List of all members.

Public Member Functions

 Controller ()
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.
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.
virtual ~Controller ()

Protected Member Functions

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

Private Member Functions

 Controller (const Controller< T > &c)
Controller< T > & operator= (const Controller< T > &c)

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.


Constructor & Destructor Documentation

template<class T>
controller_interface::Controller< T >::Controller ( ) [inline]

Definition at line 55 of file controller.h.

template<class T>
virtual controller_interface::Controller< T >::~Controller ( ) [inline, virtual]

Definition at line 56 of file controller.h.

template<class T>
controller_interface::Controller< T >::Controller ( const Controller< T > &  c) [private]

Member Function Documentation

template<class T>
virtual std::string controller_interface::Controller< T >::getHardwareInterfaceType ( ) const [inline, protected, virtual]

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

Implements controller_interface::ControllerBase.

Definition at line 133 of file controller.h.

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

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 71 of file controller.h.

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

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 88 of file controller.h.

template<class T>
virtual bool controller_interface::Controller< T >::initRequest ( hardware_interface::RobotHW robot_hw,
ros::NodeHandle root_nh,
ros::NodeHandle controller_nh,
std::set< std::string > &  claimed_resources 
) [inline, protected, virtual]

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 98 of file controller.h.

template<class T>
Controller<T>& controller_interface::Controller< T >::operator= ( const Controller< T > &  c) [private]

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


controller_interface
Author(s): Wim Meeussen
autogenerated on Sat Jun 8 2019 20:09:22