Go to the documentation of this file.
148 template <
typename... T>
252 ROS_ERROR(
"Cannot initialize this controller because it failed to be constructed");
265 if (!
init(robot_hw_ctrl_p, controller_nh) || !
init(robot_hw_ctrl_p, root_nh, controller_nh))
267 ROS_ERROR(
"Failed to initialize the controller");
272 claimed_resources.clear();
294 return internal::hasInterfaces<T...>(robot_hw);
304 internal::clearClaims<T...>(robot_hw);
318 internal::extractInterfaceResources<T...>(robot_hw_in, robot_hw_out);
332 internal::populateClaimedResources<T...>(robot_hw, claimed_resources);
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 r...
ControllerState state_
The current execution state of the controller.
static void populateClaimedResources(hardware_interface::RobotHW *robot_hw, ClaimedResources &claimed_resources)
Extract all hardware interfaces requested by this controller from robot_hw_in, and add them also to r...
std::vector< hardware_interface::InterfaceResources > ClaimedResources
hardware_interface::RobotHW robot_hw_ctrl_
Abstract Controller Interface.
Controller able to claim resources from multiple hardware interfaces.
virtual bool init(hardware_interface::RobotHW *, ros::NodeHandle &, ros::NodeHandle &)
Custom controller initialization logic.
virtual bool init(hardware_interface::RobotHW *, ros::NodeHandle &)
Custom controller initialization logic.
MultiInterfaceController(bool allow_optional_interfaces=false)
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.
static bool hasRequiredInterfaces(hardware_interface::RobotHW *robot_hw)
Check if robot hardware abstraction contains all required interfaces.
bool allow_optional_interfaces_