Controller able to claim resources from multiple hardware interfaces. More...
#include <multi_interface_controller.h>
Public Member Functions | |
MultiInterfaceController (bool allow_optional_interfaces=false) | |
virtual | ~MultiInterfaceController () |
Protected Member Functions | |
virtual std::string | getHardwareInterfaceType () const |
Static Protected Member Functions | |
static void | clearClaims (hardware_interface::RobotHW *robot_hw) |
Clear claims from all hardware interfaces requested by this controller. | |
static void | extractInterfaceResources (hardware_interface::RobotHW *robot_hw_in, hardware_interface::RobotHW *robot_hw_out) |
Extract all hardware interfaces requested by this controller from robot_hw_in , and add them also to robot_hw_out . | |
static bool | hasRequiredInterfaces (hardware_interface::RobotHW *robot_hw) |
Check if robot hardware abstraction contains all required interfaces. | |
static void | populateClaimedResources (hardware_interface::RobotHW *robot_hw, std::set< std::string > &claimed_resources) |
Extract all hardware interfaces requested by this controller from robot_hw_in , and add them also to robot_hw_out . | |
Protected Attributes | |
bool | allow_optional_interfaces_ |
hardware_interface::RobotHW | robot_hw_ctrl_ |
Private Member Functions | |
MultiInterfaceController (const MultiInterfaceController &c) | |
MultiInterfaceController & | operator= (const MultiInterfaceController &c) |
Non Real-Time Safe Functions | |
virtual bool | init (hardware_interface::RobotHW *, ros::NodeHandle &) |
Custom controller initialization logic. | |
virtual bool | init (hardware_interface::RobotHW *, ros::NodeHandle &, ros::NodeHandle &) |
Custom controller initialization logic. | |
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. |
Controller able to claim resources from multiple hardware interfaces.
This particular controller implementation allows to claim resources from one up to four different hardware interfaces. The types of these hardware interfaces are specified as template parameters.
An example multi-interface controller could claim, for instance, resources from a position-controlled arm and velocity-controlled wheels. Another example would be a controller claiming both position and effort interfaces for the same robot resources, but this would require a robot with a custom (non-exclusive) resource handling policy.
By default, all specified hardware interfaces are required, and their existence will be enforced by initRequest. It is possible to make hardware interfaces optional by means of the allow_optional_interfaces
constructor parameter. This allows to write controllers where some interfaces are mandatory, and others, if present, improve controller performance, but whose absence does not prevent the controller from running.
The following is an example of a controller claiming resources from velocity- and effort-controlled joints.
#include <controller_interface/multi_interface_controller.h> #include <hardware_interface/joint_command_interface.h> using namespace hardawre_interface; class VelEffController : public controller_interface::MultiInterfaceController<VelocityJointInterface, EffortJointInterface> { public: VelEffController() {} bool init(hardware_interface::RobotHW* robot_hw, ros::NodeHandle &n) { // robot_hw pointer only contains the two interfaces requested by the // controller. It is a subset of the entire robot, which may have more // hardware interfaces // v and e below are guarranteed to be valid VelocityJointInterface* v = robot_hw->get<VelocityJointInterface>; EffortJointInterface* e = robot_hw->get<EffortJointInterface>; // Fetch resources from interfaces, perform rest of initialization //... return true; } void starting(const ros::Time& time); void update(const ros::Time& time, const ros::Duration& period); void stopping(const ros::Time& time); };
The following fragment is a modified version of the above example, where controller interfaces are not required. It is left to the controller implementer to verify interface validity. Only the initialization code is shown.
class VelEffController : public controller_interface::MultiInterfaceController<VelocityJointInterface, EffortJointInterface> { public: // Note true flag passed to parent class, allowing requested hardware // interfaces to be optional VelEffController() : controller_interface::MultiInterfaceController<VelocityJointInterface, EffortJointInterface> (true) {} bool init(hardware_interface::RobotHW* robot_hw, ros::NodeHandle &n) { // robot_hw pointer contains at most the two interfaces requested by the // controller. It may have none, only one or both, depending on whether the // robot exposes them // v is a required interface VelocityJointInterface* v = robot_hw->get<VelocityJointInterface>; if (!v) { return false; } // e is an optional interface. If present, additional features are enabled. // Controller can still function if interface or some of its resources are // absent EffortJointInterface* e = robot_hw->get<EffortJointInterface>; // Fetch resources from interfaces, perform rest of initialization //... return true; } ... };
T1 | Hardware interface type. This parameter is required. |
T2 | Hardware interface type. This parameter is optional. Leave unspecified if controller only claims resources from a single hardware interface. |
T3 | Hardware interface type. This parameter is optional. Leave unspecified if controller only claims resources from two hardware interfaces. |
T4 | Hardware interface type. This parameter is optional. Leave unspecified if controller only claims resources from three hardware interfaces. |
T1
to T4
must be different types. Definition at line 198 of file multi_interface_controller.h.
controller_interface::MultiInterfaceController< T1, T2, T3, T4 >::MultiInterfaceController | ( | bool | allow_optional_interfaces = false | ) | [inline] |
allow_optional_interfaces | If set to true, initRequest will not fail if one or more of the requested interfaces is not present. If set to false (the default), all requested interfaces are required. |
Definition at line 206 of file multi_interface_controller.h.
virtual controller_interface::MultiInterfaceController< T1, T2, T3, T4 >::~MultiInterfaceController | ( | ) | [inline, virtual] |
Definition at line 210 of file multi_interface_controller.h.
controller_interface::MultiInterfaceController< T1, T2, T3, T4 >::MultiInterfaceController | ( | const MultiInterfaceController< T1, T2, T3, T4 > & | c | ) | [private] |
static void controller_interface::MultiInterfaceController< T1, T2, T3, T4 >::clearClaims | ( | hardware_interface::RobotHW * | robot_hw | ) | [inline, static, protected] |
Clear claims from all hardware interfaces requested by this controller.
robot_hw | Robot hardware abstraction containing the interfaces whose claims will be cleared. |
Definition at line 363 of file multi_interface_controller.h.
static void controller_interface::MultiInterfaceController< T1, T2, T3, T4 >::extractInterfaceResources | ( | hardware_interface::RobotHW * | robot_hw_in, |
hardware_interface::RobotHW * | robot_hw_out | ||
) | [inline, static, protected] |
Extract all hardware interfaces requested by this controller from robot_hw_in
, and add them also to robot_hw_out
.
[in] | robot_hw_in | Robot hardware abstraction containing the interfaces requested by this controller, and potentially others. |
[out] | robot_hw_out | Robot hardware abstraction containing only the interfaces requested by this controller. |
Definition at line 380 of file multi_interface_controller.h.
virtual std::string controller_interface::MultiInterfaceController< T1, T2, T3, T4 >::getHardwareInterfaceType | ( | ) | const [inline, protected, virtual] |
Implements controller_interface::ControllerBase.
Definition at line 338 of file multi_interface_controller.h.
static bool controller_interface::MultiInterfaceController< T1, T2, T3, T4 >::hasRequiredInterfaces | ( | hardware_interface::RobotHW * | robot_hw | ) | [inline, static, protected] |
Check if robot hardware abstraction contains all required interfaces.
robot_hw | Robot hardware abstraction. |
robot_hw
, false otherwise. Definition at line 349 of file multi_interface_controller.h.
virtual bool controller_interface::MultiInterfaceController< T1, T2, T3, T4 >::init | ( | hardware_interface::RobotHW * | , |
ros::NodeHandle & | |||
) | [inline, virtual] |
Custom controller initialization logic.
In this method resources from different interfaces are claimed, and other non real-time initialization is performed, such as setup of ROS interfaces and resource pre-allocation.
robot_hw | Robot hardware abstraction containing a subset of the entire robot. If MultiInterfaceController was called with allow_optional_interfaces set to false (the default), this parameter contains all the interfaces requested by the controller. If allow_optional_interfaces was set to false , this parameter may contain none, some or all interfaces requested by the controller, depending on whether the robot exposes them. Please refer to the code examples in the class description. |
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 239 of file multi_interface_controller.h.
virtual bool controller_interface::MultiInterfaceController< T1, T2, T3, T4 >::init | ( | hardware_interface::RobotHW * | , |
ros::NodeHandle & | , | ||
ros::NodeHandle & | |||
) | [inline, virtual] |
Custom controller initialization logic.
In this method resources from different interfaces are claimed, and other non real-time initialization is performed, such as setup of ROS interfaces and resource pre-allocation.
robot_hw | Robot hardware abstraction containing a subset of the entire robot. If MultiInterfaceController was called with allow_optional_interfaces set to false (the default), this parameter contains all the interfaces requested by the controller. If allow_optional_interfaces was set to false , this parameter may contain none, some or all interfaces requested by the controller, depending on whether the robot exposes them. Please refer to the code examples in the class description. |
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. |
Reimplemented in steer_drive_controller::SteerDriveController.
Definition at line 269 of file multi_interface_controller.h.
virtual bool controller_interface::MultiInterfaceController< T1, T2, T3, T4 >::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 a RobotHW that is a subset of the input robot_hw
parameter, containing only the requested hardware interfaces (all or some, depending on the value of allow_optional_interfaces
passed to the constructor).
robot_hw | The robot hardware abstraction. | |
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. | |
[out] | claimed_resources | The resources claimed by this controller. They can belong to multiple hardware interfaces. |
Implements controller_interface::ControllerBase.
Definition at line 297 of file multi_interface_controller.h.
MultiInterfaceController& controller_interface::MultiInterfaceController< T1, T2, T3, T4 >::operator= | ( | const MultiInterfaceController< T1, T2, T3, T4 > & | c | ) | [private] |
static void controller_interface::MultiInterfaceController< T1, T2, T3, T4 >::populateClaimedResources | ( | hardware_interface::RobotHW * | robot_hw, |
std::set< std::string > & | claimed_resources | ||
) | [inline, static, protected] |
Extract all hardware interfaces requested by this controller from robot_hw_in
, and add them also to robot_hw_out
.
[in] | robot_hw_in | Robot hardware abstraction containing the interfaces requested by this controller, and potentially others. |
[out] | claimed_resources | The resources claimed by this controller. They can belong to multiple hardware interfaces. |
Definition at line 398 of file multi_interface_controller.h.
bool controller_interface::MultiInterfaceController< T1, T2, T3, T4 >::allow_optional_interfaces_ [protected] |
Flag to indicate if hardware interfaces are considered optional (i.e. non-required).
Definition at line 412 of file multi_interface_controller.h.
hardware_interface::RobotHW controller_interface::MultiInterfaceController< T1, T2, T3, T4 >::robot_hw_ctrl_ [protected] |
Robot hardware abstraction containing only the subset of interfaces requested by the controller.
Definition at line 409 of file multi_interface_controller.h.