sr_pst_tactile_sensor_publisher.cpp
Go to the documentation of this file.
1 
23 
26 
27 namespace controller
28 {
30 {
31  // initialize time
32  last_publish_time_ = time;
33 
34  // realtime publisher
37  pst_realtime_pub_->msg_.pressure.resize(sensors_->size());
38  pst_realtime_pub_->msg_.temperature.resize(sensors_->size());
39 }
40 
42 {
43  bool pst_published = false;
44  // limit rate of publishing
45  if (publish_rate_ > 0.0 && last_publish_time_ + ros::Duration(1.0 / publish_rate_) < time)
46  {
47  // try to publish
48  if (pst_realtime_pub_->trylock())
49  {
50  // we're actually publishing, so increment time
52  pst_published = true;
53  // populate message
54  pst_realtime_pub_->msg_.header.stamp = time;
55  pst_realtime_pub_->msg_.header.frame_id = prefix_+"distal";
56  // data
57  for (unsigned i = 0; i < sensors_->size(); i++)
58  {
59  pst_realtime_pub_->msg_.pressure[i] = sensors_->at(i).pst.pressure;
60  pst_realtime_pub_->msg_.temperature[i] = sensors_->at(i).pst.temperature;
61  }
62  pst_realtime_pub_->unlockAndPublish();
63  }
64  }
65 }
66 } // end namespace controller
67 
68 
69 /* For the emacs weenies in the crowd.
70 Local Variables:
71  c-basic-offset: 2
72 End:
73 */
virtual void update(const ros::Time &time, const ros::Duration &period)
std::vector< tactiles::AllTactileData > * sensors_
derived from ImuSensorController author: Adolfo Rodriguez Tsouroukdissian
Publishes PST tactile state.


sr_tactile_sensor_controller
Author(s): Guillaume Walck
autogenerated on Tue Oct 13 2020 04:02:07