#include <sr_pst_tactile_sensor_publisher.hpp>
Public Member Functions | |
virtual void | init (const ros::Time &time) |
SrPSTTactileSensorPublisher (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) |
Private Types | |
typedef realtime_tools::RealtimePublisher < sr_robot_msgs::ShadowPST > | PSTPublisher |
typedef boost::shared_ptr < PSTPublisher > | PSTPublisherPtr |
Private Attributes | |
PSTPublisherPtr | pst_realtime_pub_ |
Definition at line 24 of file sr_pst_tactile_sensor_publisher.hpp.
typedef realtime_tools::RealtimePublisher<sr_robot_msgs::ShadowPST> controller::SrPSTTactileSensorPublisher::PSTPublisher [private] |
Definition at line 34 of file sr_pst_tactile_sensor_publisher.hpp.
typedef boost::shared_ptr<PSTPublisher > controller::SrPSTTactileSensorPublisher::PSTPublisherPtr [private] |
Definition at line 35 of file sr_pst_tactile_sensor_publisher.hpp.
controller::SrPSTTactileSensorPublisher::SrPSTTactileSensorPublisher | ( | std::vector< tactiles::AllTactileData > * | sensors, |
double | publish_rate, | ||
ros::NodeHandle | nh_prefix, | ||
std::string | prefix | ||
) | [inline] |
Definition at line 27 of file sr_pst_tactile_sensor_publisher.hpp.
void controller::SrPSTTactileSensorPublisher::init | ( | const ros::Time & | time | ) | [virtual] |
Reimplemented from controller::SrTactileSensorPublisher.
Definition at line 17 of file sr_pst_tactile_sensor_publisher.cpp.
void controller::SrPSTTactileSensorPublisher::update | ( | const ros::Time & | time, |
const ros::Duration & | period | ||
) | [virtual] |
Reimplemented from controller::SrTactileSensorPublisher.
Definition at line 29 of file sr_pst_tactile_sensor_publisher.cpp.
Definition at line 36 of file sr_pst_tactile_sensor_publisher.hpp.