vrpn_client_ros.cpp
Go to the documentation of this file.
1 
33 
37 
38 #include <vector>
39 #include <unordered_set>
40 #include <algorithm>
41 
42 namespace
43 {
44  std::unordered_set<std::string> name_blacklist_({"VRPN Control"});
45 }
46 
47 namespace vrpn_client_ros
48 {
49 
53  bool isInvalidFirstCharInName(const char c)
54  {
55  return ! ( isalpha(c) || c == '/' || c == '~' );
56  }
57 
58  bool isInvalidSubsequentCharInName(const char c)
59  {
60  return ! ( isalnum(c) || c == '/' || c == '_' );
61  }
62 
63  VrpnTrackerRos::VrpnTrackerRos(std::string tracker_name, ConnectionPtr connection, ros::NodeHandle nh)
64  {
65  tracker_remote_ = std::make_shared<vrpn_Tracker_Remote>(tracker_name.c_str(), connection.get());
66 
67  std::string clean_name = tracker_name;
68 
69  if (clean_name.size() > 0)
70  {
71  int start_subsequent = 1;
72  if (isInvalidFirstCharInName(clean_name[0]))
73  {
74  clean_name = clean_name.substr(1);
75  start_subsequent = 0;
76  }
77 
78  clean_name.erase( std::remove_if( clean_name.begin() + start_subsequent, clean_name.end(), isInvalidSubsequentCharInName ), clean_name.end() );
79  }
80 
81  init(clean_name, nh, false);
82  }
83 
84  VrpnTrackerRos::VrpnTrackerRos(std::string tracker_name, std::string host, ros::NodeHandle nh)
85  {
86  std::string tracker_address;
87  tracker_address = tracker_name + "@" + host;
88  tracker_remote_ = std::make_shared<vrpn_Tracker_Remote>(tracker_address.c_str());
89  init(tracker_name, nh, true);
90  }
91 
92  void VrpnTrackerRos::init(std::string tracker_name, ros::NodeHandle nh, bool create_mainloop_timer)
93  {
94  ROS_INFO_STREAM("Creating new tracker " << tracker_name);
95 
96  tracker_remote_->register_change_handler(this, &VrpnTrackerRos::handle_pose);
97  tracker_remote_->register_change_handler(this, &VrpnTrackerRos::handle_twist);
98  tracker_remote_->register_change_handler(this, &VrpnTrackerRos::handle_accel);
99  tracker_remote_->shutup = true;
100 
101  std::string error;
102  if (!ros::names::validate(tracker_name, error))
103  {
104  ROS_ERROR_STREAM("Invalid tracker name " << tracker_name << ", not creating topics : " << error);
105  return;
106  }
107 
108  this->tracker_name = tracker_name;
109 
110  output_nh_ = ros::NodeHandle(nh, tracker_name);
111 
112  std::string frame_id;
113  nh.param<std::string>("frame_id", frame_id, "world");
114  nh.param<bool>("use_server_time", use_server_time_, false);
115  nh.param<bool>("broadcast_tf", broadcast_tf_, false);
116  nh.param<bool>("process_sensor_id", process_sensor_id_, false);
117 
118  pose_msg_.header.frame_id = twist_msg_.header.frame_id = accel_msg_.header.frame_id = transform_stamped_.header.frame_id = frame_id;
119 
120  if (create_mainloop_timer)
121  {
122  double update_frequency;
123  nh.param<double>("update_frequency", update_frequency, 100.0);
124  mainloop_timer = nh.createTimer(ros::Duration(1 / update_frequency),
125  boost::bind(&VrpnTrackerRos::mainloop, this));
126  }
127  }
128 
130  {
131  ROS_INFO_STREAM("Destroying tracker " << transform_stamped_.child_frame_id);
132  tracker_remote_->unregister_change_handler(this, &VrpnTrackerRos::handle_pose);
133  tracker_remote_->unregister_change_handler(this, &VrpnTrackerRos::handle_twist);
134  tracker_remote_->unregister_change_handler(this, &VrpnTrackerRos::handle_accel);
135  }
136 
138  {
139  tracker_remote_->mainloop();
140  }
141 
142  void VRPN_CALLBACK VrpnTrackerRos::handle_pose(void *userData, const vrpn_TRACKERCB tracker_pose)
143  {
144  VrpnTrackerRos *tracker = static_cast<VrpnTrackerRos *>(userData);
145 
146  ros::Publisher *pose_pub;
147  std::size_t sensor_index(0);
148  ros::NodeHandle nh = tracker->output_nh_;
149 
150  if (tracker->process_sensor_id_)
151  {
152  sensor_index = static_cast<std::size_t>(tracker_pose.sensor);
153  nh = ros::NodeHandle(tracker->output_nh_, std::to_string(tracker_pose.sensor));
154  }
155 
156  if (tracker->pose_pubs_.size() <= sensor_index)
157  {
158  tracker->pose_pubs_.resize(sensor_index + 1);
159  }
160  pose_pub = &(tracker->pose_pubs_[sensor_index]);
161 
162  if (pose_pub->getTopic().empty())
163  {
164  *pose_pub = nh.advertise<geometry_msgs::PoseStamped>("pose", 1);
165  }
166 
167  if (pose_pub->getNumSubscribers() > 0)
168  {
169  if (tracker->use_server_time_)
170  {
171  tracker->pose_msg_.header.stamp.sec = tracker_pose.msg_time.tv_sec;
172  tracker->pose_msg_.header.stamp.nsec = tracker_pose.msg_time.tv_usec * 1000;
173  }
174  else
175  {
176  tracker->pose_msg_.header.stamp = ros::Time::now();
177  }
178 
179  tracker->pose_msg_.pose.position.x = tracker_pose.pos[0];
180  tracker->pose_msg_.pose.position.y = tracker_pose.pos[1];
181  tracker->pose_msg_.pose.position.z = tracker_pose.pos[2];
182 
183  tracker->pose_msg_.pose.orientation.x = tracker_pose.quat[0];
184  tracker->pose_msg_.pose.orientation.y = tracker_pose.quat[1];
185  tracker->pose_msg_.pose.orientation.z = tracker_pose.quat[2];
186  tracker->pose_msg_.pose.orientation.w = tracker_pose.quat[3];
187 
188  pose_pub->publish(tracker->pose_msg_);
189  }
190 
191  if (tracker->broadcast_tf_)
192  {
193  static tf2_ros::TransformBroadcaster tf_broadcaster;
194 
195  if (tracker->use_server_time_)
196  {
197  tracker->transform_stamped_.header.stamp.sec = tracker_pose.msg_time.tv_sec;
198  tracker->transform_stamped_.header.stamp.nsec = tracker_pose.msg_time.tv_usec * 1000;
199  }
200  else
201  {
202  tracker->transform_stamped_.header.stamp = ros::Time::now();
203  }
204 
205  if (tracker->process_sensor_id_)
206  {
207  tracker->transform_stamped_.child_frame_id = tracker->tracker_name + "/" + std::to_string(tracker_pose.sensor);
208  }
209  else
210  {
211  tracker->transform_stamped_.child_frame_id = tracker->tracker_name;
212  }
213 
214  tracker->transform_stamped_.transform.translation.x = tracker_pose.pos[0];
215  tracker->transform_stamped_.transform.translation.y = tracker_pose.pos[1];
216  tracker->transform_stamped_.transform.translation.z = tracker_pose.pos[2];
217 
218  tracker->transform_stamped_.transform.rotation.x = tracker_pose.quat[0];
219  tracker->transform_stamped_.transform.rotation.y = tracker_pose.quat[1];
220  tracker->transform_stamped_.transform.rotation.z = tracker_pose.quat[2];
221  tracker->transform_stamped_.transform.rotation.w = tracker_pose.quat[3];
222 
223  tf_broadcaster.sendTransform(tracker->transform_stamped_);
224  }
225  }
226 
227  void VRPN_CALLBACK VrpnTrackerRos::handle_twist(void *userData, const vrpn_TRACKERVELCB tracker_twist)
228  {
229  VrpnTrackerRos *tracker = static_cast<VrpnTrackerRos *>(userData);
230 
231  ros::Publisher *twist_pub;
232  std::size_t sensor_index(0);
233  ros::NodeHandle nh = tracker->output_nh_;
234 
235  if (tracker->process_sensor_id_)
236  {
237  sensor_index = static_cast<std::size_t>(tracker_twist.sensor);
238  nh = ros::NodeHandle(tracker->output_nh_, std::to_string(tracker_twist.sensor));
239  }
240 
241  if (tracker->twist_pubs_.size() <= sensor_index)
242  {
243  tracker->twist_pubs_.resize(sensor_index + 1);
244  }
245  twist_pub = &(tracker->twist_pubs_[sensor_index]);
246 
247  if (twist_pub->getTopic().empty())
248  {
249  *twist_pub = nh.advertise<geometry_msgs::TwistStamped>("twist", 1);
250  }
251 
252  if (twist_pub->getNumSubscribers() > 0)
253  {
254  if (tracker->use_server_time_)
255  {
256  tracker->twist_msg_.header.stamp.sec = tracker_twist.msg_time.tv_sec;
257  tracker->twist_msg_.header.stamp.nsec = tracker_twist.msg_time.tv_usec * 1000;
258  }
259  else
260  {
261  tracker->twist_msg_.header.stamp = ros::Time::now();
262  }
263 
264  tracker->twist_msg_.twist.linear.x = tracker_twist.vel[0];
265  tracker->twist_msg_.twist.linear.y = tracker_twist.vel[1];
266  tracker->twist_msg_.twist.linear.z = tracker_twist.vel[2];
267 
268  double roll, pitch, yaw;
269  tf2::Matrix3x3 rot_mat(
270  tf2::Quaternion(tracker_twist.vel_quat[0], tracker_twist.vel_quat[1], tracker_twist.vel_quat[2],
271  tracker_twist.vel_quat[3]));
272  rot_mat.getRPY(roll, pitch, yaw);
273 
274  tracker->twist_msg_.twist.angular.x = roll;
275  tracker->twist_msg_.twist.angular.y = pitch;
276  tracker->twist_msg_.twist.angular.z = yaw;
277 
278  twist_pub->publish(tracker->twist_msg_);
279  }
280  }
281 
282  void VRPN_CALLBACK VrpnTrackerRos::handle_accel(void *userData, const vrpn_TRACKERACCCB tracker_accel)
283  {
284  VrpnTrackerRos *tracker = static_cast<VrpnTrackerRos *>(userData);
285 
286  ros::Publisher *accel_pub;
287  std::size_t sensor_index(0);
288  ros::NodeHandle nh = tracker->output_nh_;
289 
290  if (tracker->process_sensor_id_)
291  {
292  sensor_index = static_cast<std::size_t>(tracker_accel.sensor);
293  nh = ros::NodeHandle(tracker->output_nh_, std::to_string(tracker_accel.sensor));
294  }
295 
296  if (tracker->accel_pubs_.size() <= sensor_index)
297  {
298  tracker->accel_pubs_.resize(sensor_index + 1);
299  }
300  accel_pub = &(tracker->accel_pubs_[sensor_index]);
301 
302  if (accel_pub->getTopic().empty())
303  {
304  *accel_pub = nh.advertise<geometry_msgs::TwistStamped>("accel", 1);
305  }
306 
307  if (accel_pub->getNumSubscribers() > 0)
308  {
309  if (tracker->use_server_time_)
310  {
311  tracker->accel_msg_.header.stamp.sec = tracker_accel.msg_time.tv_sec;
312  tracker->accel_msg_.header.stamp.nsec = tracker_accel.msg_time.tv_usec * 1000;
313  }
314  else
315  {
316  tracker->accel_msg_.header.stamp = ros::Time::now();
317  }
318 
319  tracker->accel_msg_.accel.linear.x = tracker_accel.acc[0];
320  tracker->accel_msg_.accel.linear.y = tracker_accel.acc[1];
321  tracker->accel_msg_.accel.linear.z = tracker_accel.acc[2];
322 
323  double roll, pitch, yaw;
324  tf2::Matrix3x3 rot_mat(
325  tf2::Quaternion(tracker_accel.acc_quat[0], tracker_accel.acc_quat[1], tracker_accel.acc_quat[2],
326  tracker_accel.acc_quat[3]));
327  rot_mat.getRPY(roll, pitch, yaw);
328 
329  tracker->accel_msg_.accel.angular.x = roll;
330  tracker->accel_msg_.accel.angular.y = pitch;
331  tracker->accel_msg_.accel.angular.z = yaw;
332 
333  accel_pub->publish(tracker->accel_msg_);
334  }
335  }
336 
338  {
339  output_nh_ = private_nh;
340 
341  host_ = getHostStringFromParams(private_nh);
342 
343  ROS_INFO_STREAM("Connecting to VRPN server at " << host_);
344  connection_ = std::shared_ptr<vrpn_Connection>(vrpn_get_connection_by_name(host_.c_str()));
345  ROS_INFO("Connection established");
346 
347  double update_frequency;
348  private_nh.param<double>("update_frequency", update_frequency, 100.0);
349  mainloop_timer = nh.createTimer(ros::Duration(1 / update_frequency), boost::bind(&VrpnClientRos::mainloop, this));
350 
351  double refresh_tracker_frequency;
352  private_nh.param<double>("refresh_tracker_frequency", refresh_tracker_frequency, 0.0);
353 
354  if (refresh_tracker_frequency > 0.0)
355  {
356  refresh_tracker_timer_ = nh.createTimer(ros::Duration(1 / refresh_tracker_frequency),
357  boost::bind(&VrpnClientRos::updateTrackers, this));
358  }
359 
360  std::vector<std::string> param_tracker_names_;
361  if (private_nh.getParam("trackers", param_tracker_names_))
362  {
363  for (std::vector<std::string>::iterator it = param_tracker_names_.begin();
364  it != param_tracker_names_.end(); ++it)
365  {
366  trackers_.insert(std::make_pair(*it, std::make_shared<VrpnTrackerRos>(*it, connection_, output_nh_)));
367  }
368  }
369  }
370 
372  {
373  std::stringstream host_stream;
374  std::string server;
375  int port;
376 
377  host_nh.param<std::string>("server", server, "localhost");
378  host_stream << server;
379 
380  if (host_nh.getParam("port", port))
381  {
382  host_stream << ":" << port;
383  }
384  return host_stream.str();
385  }
386 
388  {
389  connection_->mainloop();
390  if (!connection_->doing_okay())
391  {
392  ROS_WARN("VRPN connection is not 'doing okay'");
393  }
394  for (TrackerMap::iterator it = trackers_.begin(); it != trackers_.end(); ++it)
395  {
396  it->second->mainloop();
397  }
398  }
399 
401  {
402  int i = 0;
403  while (connection_->sender_name(i) != NULL)
404  {
405  if (trackers_.count(connection_->sender_name(i)) == 0 && name_blacklist_.count(connection_->sender_name(i)) == 0)
406  {
407  ROS_INFO_STREAM("Found new sender: " << connection_->sender_name(i));
408  trackers_.insert(std::make_pair(connection_->sender_name(i),
409  std::make_shared<VrpnTrackerRos>(connection_->sender_name(i), connection_,
410  output_nh_)));
411  }
412  i++;
413  }
414  }
415 } // namespace vrpn_client_ros
geometry_msgs::AccelStamped accel_msg_
void getRPY(tf2Scalar &roll, tf2Scalar &pitch, tf2Scalar &yaw, unsigned int solution_number=1) const
geometry_msgs::PoseStamped pose_msg_
void publish(const boost::shared_ptr< M > &message) const
std::vector< ros::Publisher > twist_pubs_
VrpnTrackerRos(std::string tracker_name, ConnectionPtr connection, ros::NodeHandle nh)
ROSCPP_DECL bool validate(const std::string &name, std::string &error)
static std::string getHostStringFromParams(ros::NodeHandle host_nh)
static void VRPN_CALLBACK handle_twist(void *userData, const vrpn_TRACKERVELCB tracker_twist)
#define ROS_WARN(...)
std::vector< ros::Publisher > pose_pubs_
void init(std::string tracker_name, ros::NodeHandle nh, bool create_mainloop_timer)
#define ROS_INFO(...)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
VrpnClientRos(ros::NodeHandle nh, ros::NodeHandle private_nh)
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void sendTransform(const geometry_msgs::TransformStamped &transform)
bool isInvalidFirstCharInName(const char c)
geometry_msgs::TwistStamped twist_msg_
std::shared_ptr< vrpn_Connection > ConnectionPtr
std::vector< ros::Publisher > accel_pubs_
geometry_msgs::TransformStamped transform_stamped_
uint32_t getNumSubscribers() const
bool isInvalidSubsequentCharInName(const char c)
#define ROS_INFO_STREAM(args)
bool getParam(const std::string &key, std::string &s) const
static Time now()
static void VRPN_CALLBACK handle_accel(void *userData, const vrpn_TRACKERACCCB tracker_accel)
std::string getTopic() const
#define ROS_ERROR_STREAM(args)
static void VRPN_CALLBACK handle_pose(void *userData, const vrpn_TRACKERCB tracker_pose)


vrpn_client_ros
Author(s): Paul Bovbel
autogenerated on Sat Jun 8 2019 04:44:59