31 #ifndef IMU_SENSOR_CONTROLLER_IMU_SENSOR_CONTROLLER_H 32 #define IMU_SENSOR_CONTROLLER_IMU_SENSOR_CONTROLLER_H 37 #include <sensor_msgs/Imu.h> 39 #include <boost/shared_ptr.hpp> 56 std::vector<hardware_interface::ImuSensorHandle>
sensors_;
virtual void update(const ros::Time &time, const ros::Duration &)
virtual void stopping(const ros::Time &)
boost::shared_ptr< realtime_tools::RealtimePublisher< sensor_msgs::Imu > > RtPublisherPtr
virtual bool init(hardware_interface::ImuSensorInterface *hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh)
std::vector< RtPublisherPtr > realtime_pubs_
std::vector< hardware_interface::ImuSensorHandle > sensors_
virtual void starting(const ros::Time &time)
std::vector< ros::Time > last_publish_times_