66 const std::list<hardware_interface::ControllerInfo>& stop_list)
69 if (!start_list.empty() || !stop_list.empty())
71 for (
const auto& controller : start_list)
73 if (controller.claimed_resources.empty())
87 const std::list<hardware_interface::ControllerInfo>& stop_list)
90 if (!start_list.empty() || !stop_list.empty())
92 for (
const auto& controller : start_list)
94 if (controller.claimed_resources.empty())
void registerInterface(T *iface)
bool init(ros::NodeHandle &root_nh, ros::NodeHandle &robot_hw_nh) override
void write(const ros::Time &time, const ros::Duration &period) override
void doSwitch(const std::list< hardware_interface::ControllerInfo > &start_list, const std::list< hardware_interface::ControllerInfo > &stop_list) override
void read(const ros::Time &time, const ros::Duration &period) override
void registerHandle(const ForceTorqueSensorHandle &handle)
hardware_interface::ForceTorqueSensorInterface ft_sensor_interface_
bool prepareSwitch(const std::list< hardware_interface::ControllerInfo > &start_list, const std::list< hardware_interface::ControllerInfo > &stop_list) override
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
hardware_interface::HardwareInterface a_plain_hw_interface_