sr_tactile_sensor_publisher.hpp
Go to the documentation of this file.
00001 
00011 #pragma once
00012 
00013 #include <sr_hardware_interface/tactile_sensors.hpp>
00014 #include <sr_robot_msgs/ShadowPST.h>
00015 #include <realtime_tools/realtime_publisher.h>
00016 #include <ros/ros.h>
00017 #include <vector>
00018 #include <string>
00019 
00020 namespace controller
00021 {
00022 
00023 class SrTactileSensorPublisher
00024 {
00025 public:
00026   SrTactileSensorPublisher(std::vector<tactiles::AllTactileData>* sensors, double publish_rate,
00027                            ros::NodeHandle nh_prefix, std::string prefix);
00028   virtual ~SrTactileSensorPublisher() {}
00029   virtual void init(const ros::Time& time) {}
00030   virtual void update(const ros::Time& time, const ros::Duration& period) {}
00031 
00032 protected:
00033   std::vector<tactiles::AllTactileData>* sensors_;
00034   ros::Time last_publish_time_;
00035   double publish_rate_;
00036   ros::NodeHandle nh_prefix_;
00037   std::string prefix_;
00038 };
00039 
00040 }  // namespace controller
00041 
00042 /* For the emacs weenies in the crowd.
00043 Local Variables:
00044    c-basic-offset: 2
00045 End:
00046 */


sr_tactile_sensor_controller
Author(s): Guillaume Walck
autogenerated on Mon Jul 1 2019 20:06:36