70 const std::list<hardware_interface::ControllerInfo>& stop_list)
73 if (!start_list.empty() || !stop_list.empty())
75 for (std::list<hardware_interface::ControllerInfo>::const_iterator it = start_list.begin(); it != start_list.end(); ++it)
77 if (it->claimed_resources.empty())
91 const std::list<hardware_interface::ControllerInfo>& stop_list)
94 if (!start_list.empty() || !stop_list.empty())
96 for (std::list<hardware_interface::ControllerInfo>::const_iterator it = start_list.begin(); it != start_list.end(); ++it)
98 if (it->claimed_resources.empty())
void registerInterface(T *iface)
void write(const ros::Time &time, const ros::Duration &period)
virtual bool init(ros::NodeHandle &root_nh, ros::NodeHandle &robot_hw_nh)
void registerHandle(const ForceTorqueSensorHandle &handle)
hardware_interface::ForceTorqueSensorInterface ft_sensor_interface_
virtual void doSwitch(const std::list< hardware_interface::ControllerInfo > &start_list, const std::list< hardware_interface::ControllerInfo > &stop_list)
void read(const ros::Time &time, const ros::Duration &period)
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
hardware_interface::HardwareInterface a_plain_hw_interface_
virtual bool prepareSwitch(const std::list< hardware_interface::ControllerInfo > &start_list, const std::list< hardware_interface::ControllerInfo > &stop_list)