31 #ifndef FORCE_TORQUE_SENSOR_CONTROLLER_FORCE_TORQUE_SENSOR_CONTROLLER_H 32 #define FORCE_TORQUE_SENSOR_CONTROLLER_FORCE_TORQUE_SENSOR_CONTROLLER_H 37 #include <geometry_msgs/WrenchStamped.h> 39 #include <boost/shared_ptr.hpp> 56 std::vector<hardware_interface::ForceTorqueSensorHandle>
sensors_;
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 &)
ForceTorqueSensorController()
std::vector< ros::Time > last_publish_times_
boost::shared_ptr< realtime_tools::RealtimePublisher< geometry_msgs::WrenchStamped > > RtPublisherPtr
virtual void starting(const ros::Time &time)