#include <sr_biotac_tactile_sensor_publisher.hpp>

Public Member Functions | |
| virtual void | init (const ros::Time &time) | 
| SrBiotacTactileSensorPublisher (std::vector< tactiles::AllTactileData > *sensors, double publish_rate, ros::NodeHandle nh_prefix, std::string prefix) | |
| virtual void | update (const ros::Time &time, const ros::Duration &period) | 
  Public Member Functions inherited from controller::SrTactileSensorPublisher | |
| SrTactileSensorPublisher (std::vector< tactiles::AllTactileData > *sensors, double publish_rate, ros::NodeHandle nh_prefix, std::string prefix) | |
| virtual | ~SrTactileSensorPublisher () | 
Private Types | |
| typedef realtime_tools::RealtimePublisher< sr_robot_msgs::BiotacAll > | BiotacPublisher | 
| typedef boost::shared_ptr< BiotacPublisher > | BiotacPublisherPtr | 
Private Attributes | |
| BiotacPublisherPtr | biotac_realtime_pub_ | 
Additional Inherited Members | |
  Protected Attributes inherited from controller::SrTactileSensorPublisher | |
| ros::Time | last_publish_time_ | 
| ros::NodeHandle | nh_prefix_ | 
| std::string | prefix_ | 
| double | publish_rate_ | 
| std::vector< tactiles::AllTactileData > * | sensors_ | 
Definition at line 36 of file sr_biotac_tactile_sensor_publisher.hpp.
      
  | 
  private | 
Definition at line 46 of file sr_biotac_tactile_sensor_publisher.hpp.
      
  | 
  private | 
Definition at line 47 of file sr_biotac_tactile_sensor_publisher.hpp.
      
  | 
  inline | 
Definition at line 39 of file sr_biotac_tactile_sensor_publisher.hpp.
      
  | 
  virtual | 
Reimplemented from controller::SrTactileSensorPublisher.
Definition at line 31 of file sr_biotac_tactile_sensor_publisher.cpp.
      
  | 
  virtual | 
Reimplemented from controller::SrTactileSensorPublisher.
Definition at line 48 of file sr_biotac_tactile_sensor_publisher.cpp.
      
  | 
  private | 
Definition at line 48 of file sr_biotac_tactile_sensor_publisher.hpp.