42 const std::vector<std::string>& sensor_names = hw->
getNames();
43 for (
unsigned i=0; i<sensor_names.size(); i++)
44 ROS_DEBUG(
"Got sensor %s", sensor_names[i].c_str());
48 ROS_ERROR(
"Parameter 'publish_rate' not set");
52 for (
unsigned i=0; i<sensor_names.size(); i++){
virtual void update(const ros::Time &time, const ros::Duration &)
std::vector< RtPublisherPtr > realtime_pubs_
virtual bool init(hardware_interface::ForceTorqueSensorInterface *hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh)
std::vector< hardware_interface::ForceTorqueSensorHandle > sensors_
virtual void stopping(const ros::Time &)
std::vector< ros::Time > last_publish_times_
ForceTorqueSensorHandle getHandle(const std::string &name)
virtual void starting(const ros::Time &time)
bool getParam(const std::string &key, std::string &s) const
std::vector< std::string > getNames() const
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)