Controller with a specific hardware interface More...
#include <controller.h>

Public Member Functions | |
| Controller () | |
| virtual bool | init (T *hw, ros::NodeHandle &controller_nh) |
| 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 *hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh) |
| 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) |
Controller with a specific hardware interface
| T | The 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.
| controller_interface::Controller< T >::Controller | ( | ) | [inline] |
Definition at line 55 of file controller.h.
| virtual controller_interface::Controller< T >::~Controller | ( | ) | [inline, virtual] |
Definition at line 56 of file controller.h.
| controller_interface::Controller< T >::Controller | ( | const Controller< T > & | c | ) | [private] |
| 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.
| virtual bool controller_interface::Controller< T >::init | ( | T * | hw, |
| ros::NodeHandle & | controller_nh | ||
| ) | [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.
| hw | The specific hardware interface used by this controller. |
| controller_nh | A NodeHandle in the namespace from which the controller should read its configuration, and where it should set up its ROS interface. |
Definition at line 71 of file controller.h.
| virtual bool controller_interface::Controller< T >::init | ( | T * | hw, |
| ros::NodeHandle & | root_nh, | ||
| ros::NodeHandle & | controller_nh | ||
| ) | [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.
| hw | The specific hardware interface used by this controller. |
| 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. |
Definition at line 88 of file controller.h.
| 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.
| Controller<T>& controller_interface::Controller< T >::operator= | ( | const Controller< T > & | c | ) | [private] |