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


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