YARP
Yet Another Robot Platform
transformServer.cpp
Go to the documentation of this file.
1 /*
2  * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT)
3  * SPDX-License-Identifier: LGPL-2.1-or-later
4  */
5 
6 // example: yarpdev --device transformServer --ROS::enable_ros_publisher 0 --ROS::enable_ros_subscriber 0
7 
8 #define _USE_MATH_DEFINES
9 #include <cmath>
10 
11 #include "transformServer.h"
12 #include <sstream>
13 #include <limits>
15 #include <yarp/os/Log.h>
16 #include <yarp/os/LogComponent.h>
17 #include <yarp/os/LogStream.h>
18 #include <mutex>
19 #include <cstdlib>
20 
21 using namespace yarp::sig;
22 using namespace yarp::math;
23 using namespace yarp::dev;
24 using namespace yarp::os;
25 
26 
27 namespace {
28 YARP_LOG_COMPONENT(TRANSFORMSERVER, "yarp.device.transformServer")
29 }
30 
31 
37 {
38  std::lock_guard<std::mutex> lock(m_mutex);
39  if (id >= 0 && (size_t)id < m_transforms.size())
40  {
41  m_transforms.erase(m_transforms.begin() + id);
42  return true;
43  }
44  return false;
45 }
46 
48 {
49  std::lock_guard<std::mutex> lock(m_mutex);
50  for (auto& m_transform : m_transforms)
51  {
52  //@@@ this linear search requires optimization!
53  if (m_transform.dst_frame_id == t.dst_frame_id && m_transform.src_frame_id == t.src_frame_id)
54  {
55  //transform already exists, update it
56  m_transform=t;
57  return true;
58  }
59  }
60 
61  //add a new transform
62  m_transforms.push_back(t);
63  return true;
64 }
65 
66 bool Transforms_server_storage::delete_transform(std::string t1, std::string t2)
67 {
68  std::lock_guard<std::mutex> lock(m_mutex);
69  if (t1=="*" && t2=="*")
70  {
71  m_transforms.clear();
72  return true;
73  }
74  else
75  if (t1=="*")
76  {
77  for (size_t i = 0; i < m_transforms.size(); )
78  {
79  //source frame is jolly, thus delete all frames with destination == t2
80  if (m_transforms[i].dst_frame_id == t2)
81  {
82  m_transforms.erase(m_transforms.begin() + i);
83  i=0; //the erase operation invalidates the iteration, loop restart is required
84  }
85  else
86  {
87  i++;
88  }
89  }
90  return true;
91  }
92  else
93  if (t2=="*")
94  {
95  for (size_t i = 0; i < m_transforms.size(); )
96  {
97  //destination frame is jolly, thus delete all frames with source == t1
98  if (m_transforms[i].src_frame_id == t1)
99  {
100  m_transforms.erase(m_transforms.begin() + i);
101  i=0; //the erase operation invalidates the iteration, loop restart is required
102  }
103  else
104  {
105  i++;
106  }
107  }
108  return true;
109  }
110  else
111  {
112  for (size_t i = 0; i < m_transforms.size(); i++)
113  {
114  if ((m_transforms[i].dst_frame_id == t1 && m_transforms[i].src_frame_id == t2) ||
115  (m_transforms[i].dst_frame_id == t2 && m_transforms[i].src_frame_id == t1) )
116  {
117  m_transforms.erase(m_transforms.begin() + i);
118  return true;
119  }
120  }
121  }
122  return false;
123 }
124 
126 {
127  std::lock_guard<std::mutex> lock(m_mutex);
128  m_transforms.clear();
129 }
130 
136 {
137  m_period = DEFAULT_THREAD_PERIOD;
138  m_enable_publish_ros_tf = false;
139  m_enable_subscribe_ros_tf = false;
140  m_yarp_static_transform_storage = nullptr;
141  m_yarp_timed_transform_storage = nullptr;
142  m_ros_static_transform_storage = nullptr;
143  m_ros_timed_transform_storage = nullptr;
144  m_rosNode = nullptr;
145  m_FrameTransformTimeout = 0.200; //ms
146 }
147 
149 {
150  threadRelease();
151  if (m_yarp_static_transform_storage)
152  {
153  delete m_yarp_static_transform_storage;
154  m_yarp_static_transform_storage = nullptr;
155  }
156  if (m_yarp_timed_transform_storage)
157  {
158  delete m_yarp_timed_transform_storage;
159  m_yarp_timed_transform_storage = nullptr;
160  }
161  if (m_ros_timed_transform_storage)
162  {
163  delete m_ros_timed_transform_storage;
164  m_ros_timed_transform_storage = nullptr;
165  }
166  if (m_ros_static_transform_storage)
167  {
168  delete m_ros_static_transform_storage;
169  m_ros_static_transform_storage = nullptr;
170  }
171 }
172 
173 void TransformServer::list_response(yarp::os::Bottle& out)
174 {
175  std::vector<Transforms_server_storage*> storages;
176  std::vector<std::string> storageDescription;
177  storages.push_back(m_ros_timed_transform_storage);
178  storageDescription.emplace_back("ros timed transforms");
179 
180  storages.push_back(m_ros_static_transform_storage);
181  storageDescription.emplace_back("ros static transforms");
182 
183  storages.push_back(m_yarp_timed_transform_storage);
184  storageDescription.emplace_back("yarp timed transforms");
185 
186  storages.push_back(m_yarp_static_transform_storage);
187  storageDescription.emplace_back("yarp static transforms");
188 
189  if (storages[0]->size() == 0 &&
190  storages[1]->size() == 0 &&
191  storages[2]->size() == 0 &&
192  storages[3]->size() == 0)
193  {
194  out.addString("no transforms found");
195  return;
196  }
197 
198  for(size_t s = 0; s < storages.size(); s++ )
199  {
200  if(!storages[s])
201  {
202  continue;
203  }
204 
205  std::string text_to_print = storageDescription[s] + std::string("(") +std::to_string(storages[s]->size())+ std::string("): ");
206  out.addString(text_to_print);
207 
208  for(size_t i = 0; i < storages[s]->size(); i++)
209  {
210  out.addString((*storages[s])[i].toString());
211  }
212 
213  }
214 }
215 
216 std::string TransformServer::get_matrix_as_text(Transforms_server_storage* storage, int i)
217 {
218  if (m_show_transforms_in_diagram== show_transforms_in_diagram_t::do_not_show)
219  {
220  return "";
221  }
222  else if (m_show_transforms_in_diagram== show_transforms_in_diagram_t::show_quaternion)
223  {
224  return std::string(",label=\" ") + (*storage)[i].toString(FrameTransform::display_transform_mode_t::rotation_as_quaternion) + "\"";
225  }
226  else if (m_show_transforms_in_diagram == show_transforms_in_diagram_t::show_matrix)
227  {
228  return std::string(",label=\" ") + (*storage)[i].toString(FrameTransform::display_transform_mode_t::rotation_as_matrix) + "\"";
229  }
230  else if (m_show_transforms_in_diagram == show_transforms_in_diagram_t::show_rpy)
231  {
232  return std::string(",label=\" ") + (*storage)[i].toString(FrameTransform::display_transform_mode_t::rotation_as_rpy) + "\"";
233  }
234 
235  yCError(TRANSFORMSERVER) << "get_matrix_as_text() invalid option";
236  return "";
237  /*
238  //this is a test to use Latek display
239  std::string s = "\\begin{ bmatrix } \
240  1 & 2 & 3\\ \
241  a & b & c \
242  \\end{ bmatrix }";
243  */
244 }
245 
246 bool TransformServer::generate_view()
247 {
248  std::string dot_string = "digraph G { ";
249  for (size_t i = 0; i < m_ros_timed_transform_storage->size(); i++)
250  {
251  std::string edge_text = get_matrix_as_text(m_ros_timed_transform_storage, i);
252  std::string trf_text = (*m_ros_timed_transform_storage)[i].src_frame_id + "->" +
253  (*m_ros_timed_transform_storage)[i].dst_frame_id + " " +
254  "[color = black]";
255  dot_string += trf_text + '\n';
256  }
257  for (size_t i = 0; i < m_ros_static_transform_storage->size(); i++)
258  {
259  std::string edge_text = get_matrix_as_text(m_ros_static_transform_storage,i);
260  std::string trf_text = (*m_ros_static_transform_storage)[i].src_frame_id + "->" +
261  (*m_ros_static_transform_storage)[i].dst_frame_id + " " +
262  "[color = black, style=dashed "+ edge_text + "]";
263  dot_string += trf_text + '\n';
264  }
265  for (size_t i = 0; i < m_yarp_timed_transform_storage->size(); i++)
266  {
267  std::string edge_text = get_matrix_as_text(m_yarp_timed_transform_storage, i);
268  std::string trf_text = (*m_yarp_timed_transform_storage)[i].src_frame_id + "->" +
269  (*m_yarp_timed_transform_storage)[i].dst_frame_id + " " +
270  "[color = blue "+ edge_text + "]";
271  dot_string += trf_text + '\n';
272  }
273  for (size_t i = 0; i < m_yarp_static_transform_storage->size(); i++)
274  {
275  std::string edge_text = get_matrix_as_text(m_yarp_static_transform_storage, i);
276  std::string trf_text = (*m_yarp_static_transform_storage)[i].src_frame_id + "->" +
277  (*m_yarp_static_transform_storage)[i].dst_frame_id + " " +
278  "[color = blue, style=dashed " + edge_text + "]";
279  dot_string += trf_text + '\n';
280  }
281 
282  std::string legend = "\n\
283  rankdir=LR\n\
284  node[shape=plaintext]\n\
285  subgraph cluster_01 {\n\
286  label = \"Legend\";\n\
287  key[label=<<table border=\"0\" cellpadding=\"2\" cellspacing=\"0\" cellborder=\"0\">\n\
288  <tr><td align=\"right\" port=\"i1\">YARP timed transform</td></tr>\n\
289  <tr><td align=\"right\" port=\"i2\">YARP static transform</td></tr>\n\
290  <tr><td align=\"right\" port=\"i3\">ROS timed transform</td></tr>\n\
291  <tr><td align=\"right\" port=\"i4\">ROS static transform</td></tr>\n\
292  </table>>]\n\
293  key2[label=<<table border=\"0\" cellpadding=\"2\" cellspacing=\"0\" cellborder=\"0\">\n\
294  <tr><td port = \"i1\">&nbsp;</td></tr>\n\
295  <tr><td port = \"i2\">&nbsp;</td></tr>\n\
296  <tr><td port = \"i3\">&nbsp;</td></tr>\n\
297  <tr><td port = \"i4\">&nbsp;</td></tr>\n\
298  </table>>]\n\
299  key:i1:e -> key2:i1:w [color = blue]\n\
300  key:i2:e -> key2:i2:w [color = blue, style=dashed]\n\
301  key:i3:e -> key2:i3:w [color = black]\n\
302  key:i4:e -> key2:i4:w [color = black, style=dashed]\n\
303  } }";
304 
305  std::string command_string = "printf '"+dot_string+ legend + "' | dot -Tpdf > frames.pdf";
306 #if defined (__linux__)
307  int ret = std::system("dot -V");
308  if (ret != 0)
309  {
310  yCError(TRANSFORMSERVER) << "dot executable not found. Please install graphviz.";
311  return false;
312  }
313 
314  yCDebug(TRANSFORMSERVER) << "Command string is:" << command_string;
315  ret = std::system(command_string.c_str());
316  if (ret != 0)
317  {
318  yCError(TRANSFORMSERVER) << "The following command failed to execute:" << command_string;
319  return false;
320  }
321 #else
322  yCError(TRANSFORMSERVER) << "Not yet implemented. Available only Linux";
323  return false;
324 #endif
325  return true;
326 }
327 
328 bool TransformServer::read(yarp::os::ConnectionReader& connection)
329 {
330  std::lock_guard<std::mutex> lock(m_mutex);
331  yarp::os::Bottle in;
332  yarp::os::Bottle out;
333  bool ok = in.read(connection);
334  if (!ok) {
335  return false;
336  }
337 
338  std::string request = in.get(0).asString();
339 
340  // parse in, prepare out
341  int code = in.get(0).asVocab32();
342  bool ret = false;
343  if (code == VOCAB_ITRANSFORM)
344  {
345  int cmd = in.get(1).asVocab32();
346  if (cmd == VOCAB_TRANSFORM_SET)
347  {
348  if (in.size() != 12)
349  {
350  yCError(TRANSFORMSERVER) << "read(): Protocol error";
351  out.clear();
353  }
354  else
355  {
357  t.src_frame_id = in.get(2).asString();
358  t.dst_frame_id = in.get(3).asString();
359  double duration = in.get(4).asFloat64();
360  t.translation.tX = in.get(5).asFloat64();
361  t.translation.tY = in.get(6).asFloat64();
362  t.translation.tZ = in.get(7).asFloat64();
363  t.rotation.w() = in.get(8).asFloat64();
364  t.rotation.x() = in.get(9).asFloat64();
365  t.rotation.y() = in.get(10).asFloat64();
366  t.rotation.z() = in.get(11).asFloat64();
367  t.timestamp = yarp::os::Time::now();
368 
369  if (duration > 0)
370  {
371  ret = m_yarp_timed_transform_storage->set_transform(t);
372  }
373  else
374  {
375  ret = m_yarp_static_transform_storage->set_transform(t);
376  }
377 
378  if (ret == true)
379  {
380  out.clear();
381  out.addVocab32(VOCAB_OK);
382  }
383  else
384  {
385  out.clear();
387  yCError(TRANSFORMSERVER) << "read(): Something strange happened";
388  }
389  }
390  }
391  else if (cmd == VOCAB_TRANSFORM_DELETE_ALL)
392  {
393  m_yarp_timed_transform_storage->clear();
394  m_yarp_static_transform_storage->clear();
395  m_ros_timed_transform_storage->clear();
396  m_ros_static_transform_storage->clear();
397  out.clear();
398  out.addVocab32(VOCAB_OK);
399  }
400  else if (cmd == VOCAB_TRANSFORM_DELETE)
401  {
402  std::string frame1 = in.get(2).asString();
403  std::string frame2 = in.get(3).asString();
404  bool ret1 = m_yarp_timed_transform_storage->delete_transform(frame1, frame2);
405  if (ret1 == true)
406  {
407  out.clear();
408  out.addVocab32(VOCAB_OK);
409  }
410  else
411  {
412  bool ret2 = m_yarp_static_transform_storage->delete_transform(frame1, frame2);
413  if (ret2 == true)
414  {
415  out.clear();
416  out.addVocab32(VOCAB_OK);
417  }
418  }
419 
420  }
421  else
422  {
423  yCError(TRANSFORMSERVER, "Invalid vocab received");
424  out.clear();
425  out.addVocab32(VOCAB_ERR);
426  }
427  }
428  else if(request == "help")
429  {
430  out.addVocab32("many");
431  out.addString("'list': get all transforms stored");
432  out.addString("'delete_all': delete all transforms");
433  out.addString("'set_static_transform_rad <src> <dst> <x> <y> <z> <roll> <pitch> <yaw>': create a static transform (angles in radians)");
434  out.addString("'set_static_transform_deg <src> <dst> <x> <y> <z> <roll> <pitch> <yaw>': create a static transform (angles in degrees)");
435  out.addString("'delete_static_transform <src> <dst>': delete a static transform");
436  out.addString("'generate_view <option>': generate a frames.pdf file showing the transform tree diagram.");
437  out.addString(" The following values are valid for option (default=none)");
438  out.addString(" 'show_rpy': show roation as rpy angles");
439  out.addString(" 'show_quaterion:'show rotation as a quaternion");
440  out.addString(" 'show_matrix:'show rotationa as a 3x3 rotation matrix");
441  }
442  else if (request == "set_static_transform_rad" ||
443  request == "set_static_transform_deg")
444  {
446  t.src_frame_id = in.get(1).asString();
447  t.dst_frame_id = in.get(2).asString();
448  t.translation.tX = in.get(3).asFloat64();
449  t.translation.tY = in.get(4).asFloat64();
450  t.translation.tZ = in.get(5).asFloat64();
451  if (request == "set_static_transform_rad")
452  { t.rotFromRPY(in.get(6).asFloat64(), in.get(7).asFloat64(), in.get(8).asFloat64());}
453  else if (request == "set_static_transform_deg")
454  { t.rotFromRPY(in.get(6).asFloat64() * 180 / M_PI, in.get(7).asFloat64() * 180 / M_PI, in.get(8).asFloat64() * 180 / M_PI);}
455  t.timestamp = yarp::os::Time::now();
456  ret = m_yarp_static_transform_storage->set_transform(t);
457  if (ret == true)
458  {
459  yCInfo(TRANSFORMSERVER) << "set_static_transform done";
460  out.addString("set_static_transform done");
461  }
462  else
463  {
464  yCError(TRANSFORMSERVER) << "read(): something strange happened";
465  }
466  }
467  else if(request == "delete_all")
468  {
469  m_yarp_timed_transform_storage->clear();
470  m_yarp_static_transform_storage->clear();
471  m_ros_timed_transform_storage->clear();
472  m_ros_static_transform_storage->clear();
473  yCInfo(TRANSFORMSERVER) << "delete_all done";
474  out.addString("delete_all done");
475  }
476  else if (request == "list")
477  {
478  out.addVocab32("many");
479  list_response(out);
480  }
481  else if (request == "generate_view")
482  {
483  m_show_transforms_in_diagram = show_transforms_in_diagram_t::do_not_show;
484  if (in.get(1).asString() == "show_quaternion") {
485  m_show_transforms_in_diagram = show_transforms_in_diagram_t::show_quaternion;
486  } else if (in.get(1).asString() == "show_matrix") {
487  m_show_transforms_in_diagram = show_transforms_in_diagram_t::show_matrix;
488  } else if (in.get(1).asString() == "show_rpy") {
489  m_show_transforms_in_diagram = show_transforms_in_diagram_t::show_rpy;
490  }
491  generate_view();
492  out.addString("ok");
493  }
494  else if (request == "delete_static_transform")
495  {
496  std::string src = in.get(1).asString();
497  std::string dst = in.get(2).asString();
498  m_yarp_static_transform_storage->delete_transform(src,dst);
499  m_ros_static_transform_storage->delete_transform(src,dst);
500  out.addString("delete_static_transform done");
501  }
502  else
503  {
504  yCError(TRANSFORMSERVER, "Invalid vocab received");
505  out.clear();
506  out.addVocab32(VOCAB_ERR);
507  }
508 
509  yarp::os::ConnectionWriter *returnToSender = connection.getWriter();
510  if (returnToSender != nullptr)
511  {
512  out.write(*returnToSender);
513  }
514  else
515  {
516  yCError(TRANSFORMSERVER) << "Invalid return to sender";
517  }
518  return true;
519 }
520 
522 {
523  //open rpc port
524  if (!m_rpcPort.open(m_rpcPortName))
525  {
526  yCError(TRANSFORMSERVER, "Failed to open port %s", m_rpcPortName.c_str());
527  return false;
528  }
529  m_rpcPort.setReader(*this);
530 
531  // open data port
532  if (!m_streamingPort.open(m_streamingPortName))
533  {
534  yCError(TRANSFORMSERVER, "Failed to open port %s", m_streamingPortName.c_str());
535  return false;
536  }
537 
538  //open ros publisher (if requested)
539  if (m_enable_publish_ros_tf)
540  {
541  if (m_rosNode == nullptr)
542  {
543  m_rosNode = new yarp::os::Node(ROSNODENAME);
544  }
545  if (!m_rosPublisherPort_tf_timed.topic(ROSTOPICNAME_TF))
546  {
547  yCError(TRANSFORMSERVER) << "Unable to publish data on " << ROSTOPICNAME_TF << " topic, check your yarp-ROS network configuration";
548  return false;
549  }
550  if (!m_rosPublisherPort_tf_static.topic(ROSTOPICNAME_TF_STATIC))
551  {
552  yCError(TRANSFORMSERVER) << "Unable to publish data on " << ROSTOPICNAME_TF_STATIC << " topic, check your yarp-ROS network configuration";
553  return false;
554  }
555  }
556 
557  //open ros subscriber(if requested)
558  if (m_enable_subscribe_ros_tf)
559  {
560  if (m_rosNode == nullptr)
561  {
562  m_rosNode = new yarp::os::Node(ROSNODENAME);
563  }
564  if (!m_rosSubscriberPort_tf_timed.topic(ROSTOPICNAME_TF))
565  {
566  yCError(TRANSFORMSERVER) << "Unable to subscribe to " << ROSTOPICNAME_TF << " topic, check your yarp-ROS network configuration";
567  return false;
568  }
569  m_rosSubscriberPort_tf_timed.setStrict();
570  if (!m_rosSubscriberPort_tf_static.topic(ROSTOPICNAME_TF_STATIC))
571  {
572  yCError(TRANSFORMSERVER) << "Unable to subscribe to " << ROSTOPICNAME_TF_STATIC << " topic, check your yarp-ROS network configuration";
573  return false;
574  }
575  m_rosSubscriberPort_tf_static.setStrict();
576  }
577 
578  m_yarp_static_transform_storage = new Transforms_server_storage();
579  m_yarp_timed_transform_storage = new Transforms_server_storage();
580 
581  m_ros_static_transform_storage = new Transforms_server_storage();
582  m_ros_timed_transform_storage = new Transforms_server_storage();
583 
584  yCInfo(TRANSFORMSERVER) << "Transform server started";
585  return true;
586 }
587 
588 bool TransformServer::parseStartingTf(yarp::os::Searchable &config)
589 {
590 
591  if (config.check("USER_TF"))
592  {
593  Bottle all_transforms_group = config.findGroup("USER_TF").tail();
594  yCDebug(TRANSFORMSERVER) << all_transforms_group.toString();
595 
596  for (size_t i = 0; i < all_transforms_group.size(); i++)
597  {
599 
600  Bottle* b = all_transforms_group.get(i).asList();
601  if(!b)
602  {
603  yCError(TRANSFORMSERVER) << "No entries in USER_TF group";
604  return false;
605  }
606 
607  if(b->size() == 18)
608  {
609  bool r(true);
610  Matrix m(4, 4);
611 
612  for(int i = 0; i < 16; i++)
613  {
614  if(!b->get(i).isFloat64())
615  {
616  yCError(TRANSFORMSERVER) << "transformServer: element " << i << " is not a double.";
617  r = false;
618  }
619  else
620  {
621  m.data()[i] = b->get(i).asFloat64();
622  }
623  }
624 
625  if(!b->get(16).isString() || !b->get(17).isString())
626  {
627  r = false;
628  }
629 
630  if(!r)
631  {
632  yCError(TRANSFORMSERVER) << "transformServer: param not correct.. for the 4x4 matrix mode" <<
633  "you must provide 18 parameter. the matrix, the source frame(string) and the destination frame(string)";
634  return false;
635  }
636 
637  t.fromMatrix(m);
638  t.src_frame_id = b->get(16).asString();
639  t.dst_frame_id = b->get(17).asString();
640  }
641  else if( b->size() == 8 &&
642  b->get(0).isFloat64() &&
643  b->get(1).isFloat64() &&
644  b->get(2).isFloat64() &&
645  b->get(3).isFloat64() &&
646  b->get(4).isFloat64() &&
647  b->get(5).isFloat64() &&
648  b->get(6).isString() &&
649  b->get(7).isString())
650  {
651  t.translation.set(b->get(0).asFloat64(), b->get(1).asFloat64(), b->get(2).asFloat64());
652  t.rotFromRPY(b->get(3).asFloat64(), b->get(4).asFloat64(), b->get(5).asFloat64());
653  t.src_frame_id = b->get(6).asString();
654  t.dst_frame_id = b->get(7).asString();
655  }
656  else
657  {
658  yCError(TRANSFORMSERVER) << "transformServer: param not correct.. a tf requires 8 param in the format:" <<
659  "x(dbl) y(dbl) z(dbl) r(dbl) p(dbl) y(dbl) src(str) dst(str)";
660  return false;
661  }
662 
663  if(m_yarp_static_transform_storage->set_transform(t))
664  {
665  yCInfo(TRANSFORMSERVER) << "Transform from" << t.src_frame_id << "to" << t.dst_frame_id << "successfully set";
666  }
667  else
668  {
669  yCInfo(TRANSFORMSERVER) << "Unbale to set transform from " << t.src_frame_id << "to" << t.dst_frame_id;
670  }
671  }
672  return true;
673  }
674  else
675  {
676  yCInfo(TRANSFORMSERVER) << "No starting tf found";
677  }
678  return true;
679 }
680 
682 {
683  yCWarning(TRANSFORMSERVER) << "The 'transformServer' device is deprecated in favour of 'frameTransformServer'.";
684  yCWarning(TRANSFORMSERVER) << "The old device is no longer supported, and it will be deprecated in YARP 3.6 and removed in YARP 4.";
685  yCWarning(TRANSFORMSERVER) << "Please update your scripts.";
686 
687  Property params;
688  params.fromString(config.toString());
689 
690  if (!config.check("period"))
691  {
692  m_period = 0.01;
693  }
694  else
695  {
696  m_period = config.find("period").asInt32() / 1000.0;
697  yCInfo(TRANSFORMSERVER) << "Thread period set to:" << m_period;
698  }
699 
700  if (config.check("transforms_lifetime"))
701  {
702  m_FrameTransformTimeout = config.find("transforms_lifetime").asFloat64();
703  yCInfo(TRANSFORMSERVER) << "transforms_lifetime set to:" << m_FrameTransformTimeout;
704  }
705 
706  std::string name;
707  if (!config.check("name"))
708  {
709  name = "transformServer";
710  }
711  else
712  {
713  name = config.find("name").asString();
714  }
715  m_streamingPortName = "/"+ name + "/transforms:o";
716  m_rpcPortName = "/" + name + "/rpc";
717 
718  //ROS configuration
719  if (!config.check("ROS"))
720  {
721  yCError(TRANSFORMSERVER) << "Missing ROS group";
722  return false;
723  }
724  Bottle ROS_config = config.findGroup("ROS");
725  if (ROS_config.check("enable_ros_publisher") == false)
726  {
727  yCError(TRANSFORMSERVER) << "Missing 'enable_ros_publisher' in ROS group";
728  return false;
729  }
730  if (ROS_config.find("enable_ros_publisher").asInt32() == 1 || ROS_config.find("enable_ros_publisher").asString() == "true")
731  {
732  m_enable_publish_ros_tf = true;
733  yCInfo(TRANSFORMSERVER) << "Enabled ROS publisher";
734  }
735  if (ROS_config.check("enable_ros_subscriber") == false)
736  {
737  yCError(TRANSFORMSERVER) << "Missing 'enable_ros_subscriber' in ROS group";
738  return false;
739  }
740  if (ROS_config.find("enable_ros_subscriber").asInt32() == 1 || ROS_config.find("enable_ros_subscriber").asString() == "true")
741  {
742  m_enable_subscribe_ros_tf = true;
743  yCInfo(TRANSFORMSERVER) << "Enabled ROS subscriber";
744  }
745 
746  this->start();
747 
749  parseStartingTf(config);
750 
751  return true;
752 }
753 
755 {
756  m_streamingPort.interrupt();
757  m_streamingPort.close();
758  m_rpcPort.interrupt();
759  m_rpcPort.close();
760  if (m_enable_publish_ros_tf)
761  {
762  m_rosPublisherPort_tf_timed.interrupt();
763  m_rosPublisherPort_tf_timed.close();
764  }
765  if (m_enable_subscribe_ros_tf)
766  {
767  m_rosSubscriberPort_tf_timed.interrupt();
768  m_rosSubscriberPort_tf_timed.close();
769  }
770  if (m_enable_publish_ros_tf)
771  {
772  m_rosPublisherPort_tf_static.interrupt();
773  m_rosPublisherPort_tf_static.close();
774  }
775  if (m_enable_subscribe_ros_tf)
776  {
777  m_rosSubscriberPort_tf_static.interrupt();
778  m_rosSubscriberPort_tf_static.close();
779  }
780  if (m_rosNode)
781  {
782  m_rosNode->interrupt();
783  delete m_rosNode;
784  m_rosNode = nullptr;
785  }
786 }
787 
789 {
790  std::lock_guard<std::mutex> lock(m_mutex);
791  if (true)
792  {
793  double current_time = yarp::os::Time::now();
794 
795  //timeout check for yarp timed transforms.
796  bool repeat_check;
797  do
798  {
799  repeat_check = false;
800  size_t tfVecSize_timed_yarp = m_yarp_timed_transform_storage->size();
801  for (size_t i = 0; i < tfVecSize_timed_yarp; i++)
802  {
803  if (current_time - (*m_yarp_timed_transform_storage)[i].timestamp > m_FrameTransformTimeout)
804  {
805  m_yarp_timed_transform_storage->delete_transform(i);
806  repeat_check = true;
807  break;
808  }
809  }
810  }
811  while (repeat_check);
812 
813  //timeout check for ROS timed transforms.
814  do
815  {
816  repeat_check = false;
817  size_t tfVecSize_timed_ros = m_ros_timed_transform_storage->size();
818  for (size_t i = 0; i < tfVecSize_timed_ros; i++)
819  {
820  if (current_time - (*m_ros_timed_transform_storage)[i].timestamp > m_FrameTransformTimeout)
821  {
822  m_ros_timed_transform_storage->delete_transform(i);
823  repeat_check = true;
824  break;
825  }
826  }
827  } while (repeat_check);
828 
829  //ros subscriber
830  if (m_enable_subscribe_ros_tf)
831  {
832  yarp::rosmsg::tf2_msgs::TFMessage* rosInData_timed = nullptr;
833  do
834  {
835  rosInData_timed = m_rosSubscriberPort_tf_timed.read(false);
836  if (rosInData_timed != nullptr)
837  {
838  std::vector <yarp::rosmsg::geometry_msgs::TransformStamped> tfs = rosInData_timed->transforms;
839  size_t tfs_size = tfs.size();
840  for (size_t i = 0; i < tfs_size; i++)
841  {
843  t.translation.tX = tfs[i].transform.translation.x;
844  t.translation.tY = tfs[i].transform.translation.y;
845  t.translation.tZ = tfs[i].transform.translation.z;
846  t.rotation.x() = tfs[i].transform.rotation.x;
847  t.rotation.y() = tfs[i].transform.rotation.y;
848  t.rotation.z() = tfs[i].transform.rotation.z;
849  t.rotation.w() = tfs[i].transform.rotation.w;
850  t.src_frame_id = tfs[i].header.frame_id;
851  t.dst_frame_id = tfs[i].child_frame_id;
852  //@@@ should we use yarp or ROS timestamps?
853  t.timestamp = yarp::os::Time::now();
854  //t.timestamp = tfs[i].header.stamp.sec; //@@@this needs some revising
855  (*m_ros_timed_transform_storage).set_transform(t);
856  }
857  }
858  } while (rosInData_timed != nullptr);
859 
860  yarp::rosmsg::tf2_msgs::TFMessage* rosInData_static = nullptr;
861  do
862  {
863  rosInData_static = m_rosSubscriberPort_tf_static.read(false);
864  if (rosInData_static != nullptr)
865  {
866  std::vector <yarp::rosmsg::geometry_msgs::TransformStamped> tfs = rosInData_static->transforms;
867  size_t tfs_size = tfs.size();
868  for (size_t i = 0; i < tfs_size; i++)
869  {
871  t.translation.tX = tfs[i].transform.translation.x;
872  t.translation.tY = tfs[i].transform.translation.y;
873  t.translation.tZ = tfs[i].transform.translation.z;
874  t.rotation.x() = tfs[i].transform.rotation.x;
875  t.rotation.y() = tfs[i].transform.rotation.y;
876  t.rotation.z() = tfs[i].transform.rotation.z;
877  t.rotation.w() = tfs[i].transform.rotation.w;
878  t.src_frame_id = tfs[i].header.frame_id;
879  t.dst_frame_id = tfs[i].child_frame_id;
880  //@@@ should we use yarp or ROS timestamps?
881  t.timestamp = yarp::os::Time::now();
882  //t.timestamp = tfs[i].header.stamp; //@@@ is this ok?
883  (*m_ros_static_transform_storage).set_transform(t);
884  }
885  }
886  } while (rosInData_static != nullptr);
887  }
888 
889  //yarp streaming port
890  m_lastStateStamp.update();
891  size_t tfVecSize_static_yarp = m_yarp_static_transform_storage->size();
892  size_t tfVecSize_timed_yarp = m_yarp_timed_transform_storage->size();
893  size_t tfVecSize_static_ros = m_ros_static_transform_storage->size();
894  size_t tfVecSize_timed_ros = m_ros_timed_transform_storage->size();
895 #if 0
896  yCDebug(TRANSFORMSERVER) << "yarp size" << tfVecSize_yarp << "ros_size" << tfVecSize_ros;
897 #endif
898  yarp::os::Bottle& b = m_streamingPort.prepare();
899  b.clear();
900 
901  for (size_t i = 0; i < tfVecSize_static_yarp; i++)
902  {
903  yarp::os::Bottle& transform = b.addList();
904  transform.addString((*m_yarp_static_transform_storage)[i].src_frame_id);
905  transform.addString((*m_yarp_static_transform_storage)[i].dst_frame_id);
906  transform.addFloat64((*m_yarp_static_transform_storage)[i].timestamp);
907 
908  transform.addFloat64((*m_yarp_static_transform_storage)[i].translation.tX);
909  transform.addFloat64((*m_yarp_static_transform_storage)[i].translation.tY);
910  transform.addFloat64((*m_yarp_static_transform_storage)[i].translation.tZ);
911 
912  transform.addFloat64((*m_yarp_static_transform_storage)[i].rotation.w());
913  transform.addFloat64((*m_yarp_static_transform_storage)[i].rotation.x());
914  transform.addFloat64((*m_yarp_static_transform_storage)[i].rotation.y());
915  transform.addFloat64((*m_yarp_static_transform_storage)[i].rotation.z());
916  }
917  for (size_t i = 0; i < tfVecSize_timed_yarp; i++)
918  {
919  yarp::os::Bottle& transform = b.addList();
920  transform.addString((*m_yarp_timed_transform_storage)[i].src_frame_id);
921  transform.addString((*m_yarp_timed_transform_storage)[i].dst_frame_id);
922  transform.addFloat64((*m_yarp_timed_transform_storage)[i].timestamp);
923 
924  transform.addFloat64((*m_yarp_timed_transform_storage)[i].translation.tX);
925  transform.addFloat64((*m_yarp_timed_transform_storage)[i].translation.tY);
926  transform.addFloat64((*m_yarp_timed_transform_storage)[i].translation.tZ);
927 
928  transform.addFloat64((*m_yarp_timed_transform_storage)[i].rotation.w());
929  transform.addFloat64((*m_yarp_timed_transform_storage)[i].rotation.x());
930  transform.addFloat64((*m_yarp_timed_transform_storage)[i].rotation.y());
931  transform.addFloat64((*m_yarp_timed_transform_storage)[i].rotation.z());
932  }
933  for (size_t i = 0; i < tfVecSize_timed_ros; i++)
934  {
935  yarp::os::Bottle& transform = b.addList();
936  transform.addString((*m_ros_timed_transform_storage)[i].src_frame_id);
937  transform.addString((*m_ros_timed_transform_storage)[i].dst_frame_id);
938  transform.addFloat64((*m_ros_timed_transform_storage)[i].timestamp);
939 
940  transform.addFloat64((*m_ros_timed_transform_storage)[i].translation.tX);
941  transform.addFloat64((*m_ros_timed_transform_storage)[i].translation.tY);
942  transform.addFloat64((*m_ros_timed_transform_storage)[i].translation.tZ);
943 
944  transform.addFloat64((*m_ros_timed_transform_storage)[i].rotation.w());
945  transform.addFloat64((*m_ros_timed_transform_storage)[i].rotation.x());
946  transform.addFloat64((*m_ros_timed_transform_storage)[i].rotation.y());
947  transform.addFloat64((*m_ros_timed_transform_storage)[i].rotation.z());
948  }
949  for (size_t i = 0; i < tfVecSize_static_ros; i++)
950  {
951  yarp::os::Bottle& transform = b.addList();
952  transform.addString((*m_ros_static_transform_storage)[i].src_frame_id);
953  transform.addString((*m_ros_static_transform_storage)[i].dst_frame_id);
954  transform.addFloat64((*m_ros_static_transform_storage)[i].timestamp);
955 
956  transform.addFloat64((*m_ros_static_transform_storage)[i].translation.tX);
957  transform.addFloat64((*m_ros_static_transform_storage)[i].translation.tY);
958  transform.addFloat64((*m_ros_static_transform_storage)[i].translation.tZ);
959 
960  transform.addFloat64((*m_ros_static_transform_storage)[i].rotation.w());
961  transform.addFloat64((*m_ros_static_transform_storage)[i].rotation.x());
962  transform.addFloat64((*m_ros_static_transform_storage)[i].rotation.y());
963  transform.addFloat64((*m_ros_static_transform_storage)[i].rotation.z());
964  }
965 
966  m_streamingPort.setEnvelope(m_lastStateStamp);
967  m_streamingPort.write();
968 
969  //ros publisher
970  if (m_enable_publish_ros_tf)
971  {
972  static int rosMsgCounter = 0;
973  yarp::rosmsg::tf2_msgs::TFMessage& rosOutData_timed = m_rosPublisherPort_tf_timed.prepare();
975  rosOutData_timed.transforms.clear();
976  for (size_t i = 0; i < tfVecSize_timed_yarp; i++)
977  {
978  transform_timed.child_frame_id = (*m_yarp_timed_transform_storage)[i].dst_frame_id;
979  transform_timed.header.frame_id = (*m_yarp_timed_transform_storage)[i].src_frame_id;
980  transform_timed.header.seq = rosMsgCounter;
981  transform_timed.header.stamp = (*m_yarp_timed_transform_storage)[i].timestamp;
982  transform_timed.transform.rotation.x = (*m_yarp_timed_transform_storage)[i].rotation.x();
983  transform_timed.transform.rotation.y = (*m_yarp_timed_transform_storage)[i].rotation.y();
984  transform_timed.transform.rotation.z = (*m_yarp_timed_transform_storage)[i].rotation.z();
985  transform_timed.transform.rotation.w = (*m_yarp_timed_transform_storage)[i].rotation.w();
986  transform_timed.transform.translation.x = (*m_yarp_timed_transform_storage)[i].translation.tX;
987  transform_timed.transform.translation.y = (*m_yarp_timed_transform_storage)[i].translation.tY;
988  transform_timed.transform.translation.z = (*m_yarp_timed_transform_storage)[i].translation.tZ;
989 
990  rosOutData_timed.transforms.push_back(transform_timed);
991  }
992  m_rosPublisherPort_tf_timed.write();
993 
994  yarp::rosmsg::tf2_msgs::TFMessage& rosOutData_static = m_rosPublisherPort_tf_static.prepare();
996  rosOutData_static.transforms.clear();
997  for (size_t i = 0; i < tfVecSize_static_yarp; i++)
998  {
999  transform_static.child_frame_id = (*m_yarp_static_transform_storage)[i].dst_frame_id;
1000  transform_static.header.frame_id = (*m_yarp_static_transform_storage)[i].src_frame_id;
1001  transform_static.header.seq = rosMsgCounter;
1002  transform_static.header.stamp = yarp::os::Time::now(); //@@@check timestamp of static transform?
1003  transform_static.transform.rotation.x = (*m_yarp_static_transform_storage)[i].rotation.x();
1004  transform_static.transform.rotation.y = (*m_yarp_static_transform_storage)[i].rotation.y();
1005  transform_static.transform.rotation.z = (*m_yarp_static_transform_storage)[i].rotation.z();
1006  transform_static.transform.rotation.w = (*m_yarp_static_transform_storage)[i].rotation.w();
1007  transform_static.transform.translation.x = (*m_yarp_static_transform_storage)[i].translation.tX;
1008  transform_static.transform.translation.y = (*m_yarp_static_transform_storage)[i].translation.tY;
1009  transform_static.transform.translation.z = (*m_yarp_static_transform_storage)[i].translation.tZ;
1010 
1011  rosOutData_static.transforms.push_back(transform_static);
1012  }
1013  m_rosPublisherPort_tf_static.write();
1014 
1015  rosMsgCounter++;
1016  }
1017 
1018  }
1019  else
1020  {
1021  yCError(TRANSFORMSERVER, "Returned error");
1022  }
1023 }
1024 
1026 {
1027  yCTrace(TRANSFORMSERVER, "Close");
1028  if (PeriodicThread::isRunning())
1029  {
1030  PeriodicThread::stop();
1031  }
1032 
1033  return true;
1034 }
define control board standard interfaces
float t
#define ROSNODENAME
#define ROSTOPICNAME_TF
#define ROSTOPICNAME_TF_STATIC
constexpr yarp::conf::vocab32_t VOCAB_OK
Definition: GenericVocabs.h:15
constexpr yarp::conf::vocab32_t VOCAB_FAILED
Definition: GenericVocabs.h:16
constexpr yarp::conf::vocab32_t VOCAB_ERR
Definition: GenericVocabs.h:17
constexpr yarp::conf::vocab32_t VOCAB_TRANSFORM_DELETE
constexpr yarp::conf::vocab32_t VOCAB_TRANSFORM_SET
constexpr yarp::conf::vocab32_t VOCAB_TRANSFORM_DELETE_ALL
constexpr yarp::conf::vocab32_t VOCAB_ITRANSFORM
bool ret
constexpr double DEFAULT_THREAD_PERIOD
bool threadInit() override
Initialization method.
void run() override
Loop function.
bool open(yarp::os::Searchable &params) override
Open the DeviceDriver.
bool close() override
Close the DeviceDriver.
void threadRelease() override
Release method.
TransformServer()
TransformServer.
bool delete_transform(int id)
Transforms storage.
bool set_transform(const yarp::math::FrameTransform &t)
bool open(const std::string &name) override
Start port operation, with a specific name, with automatically-chosen network parameters.
void setReader(PortReader &reader) override
Set an external reader for port data.
void close() override
Stop port activity.
void interrupt() override
Interrupt any current reads or writes attached to the port.
A simple collection of objects that can be described and transmitted in a portable way.
Definition: Bottle.h:74
void addVocab32(yarp::conf::vocab32_t x)
Places a vocabulary item in the bottle, at the end of the list.
Definition: Bottle.cpp:164
Bottle & addList()
Places an empty nested list in the bottle, at the end of the list.
Definition: Bottle.cpp:182
size_type size() const
Gets the number of elements in the bottle.
Definition: Bottle.cpp:251
bool read(ConnectionReader &reader) override
Set the bottle's value based on input from a network connection.
Definition: Bottle.cpp:240
void addFloat64(yarp::conf::float64_t x)
Places a 64-bit floating point number in the bottle, at the end of the list.
Definition: Bottle.cpp:158
Value & get(size_type index) const
Reads a Value v from a certain part of the list.
Definition: Bottle.cpp:246
bool check(const std::string &key) const override
Check if there exists a property of the given name.
Definition: Bottle.cpp:277
Bottle tail() const
Get all but the first element of a bottle.
Definition: Bottle.cpp:388
void clear()
Empties the bottle of any objects it contains.
Definition: Bottle.cpp:121
bool write(ConnectionWriter &writer) const override
Output a representation of the bottle to a network connection.
Definition: Bottle.cpp:230
void addString(const char *str)
Places a string in the bottle, at the end of the list.
Definition: Bottle.cpp:170
std::string toString() const override
Gives a human-readable textual representation of the bottle.
Definition: Bottle.cpp:211
Value & find(const std::string &key) const override
Gets a value corresponding to a given keyword.
Definition: Bottle.cpp:287
void close() override
Stop port activity.
bool setEnvelope(PortWriter &envelope) override
Set an envelope (e.g., a timestamp) to the next message which will be sent.
bool open(const std::string &name) override
Start port operation, with a specific name, with automatically-chosen network parameters.
void interrupt() override
Interrupt any current reads or writes attached to the port.
void write(bool forceStrict=false)
Write the current object being returned by BufferedPort::prepare.
T & prepare()
Access the object which will be transmitted by the next call to yarp::os::BufferedPort::write.
An interface for reading from a network connection.
virtual ConnectionWriter * getWriter()=0
Gets a way to reply to the message, if possible.
An interface for writing to a network connection.
The Node class.
Definition: Node.h:24
void interrupt()
interrupt delegates the call to the Node port interrupt.
Definition: Node.cpp:597
An abstraction for a periodic thread.
bool start()
Call this to start the thread.
A class for storing options and configuration information.
Definition: Property.h:34
void fromString(const std::string &txt, bool wipe=true)
Interprets a string as a list of properties.
Definition: Property.cpp:1063
void close() override
Stop port activity.
Definition: Publisher.h:85
bool topic(const std::string &name)
Set topic to publish to.
Definition: Publisher.h:64
T & prepare()
Access the object which will be transmitted by the next call to yarp::os::Publisher::write.
Definition: Publisher.h:124
void interrupt() override
Interrupt any current reads or writes attached to the port.
Definition: Publisher.h:91
void write(bool forceStrict=false)
Write the current object being returned by Publisher::prepare.
Definition: Publisher.h:149
A base class for nested structures that can be searched.
Definition: Searchable.h:66
virtual Value & find(const std::string &key) const =0
Gets a value corresponding to a given keyword.
virtual bool check(const std::string &key) const =0
Check if there exists a property of the given name.
virtual std::string toString() const =0
Return a standard text representation of the content of the object.
virtual Bottle & findGroup(const std::string &key) const =0
Gets a list corresponding to a given keyword.
void update()
Set the timestamp to the current time, and increment the sequence number (wrapping to 0 if the sequen...
Definition: Stamp.cpp:124
void close() override
Stop port activity.
Definition: Subscriber.h:84
T * read(bool shouldWait=true)
Read a message from the port.
Definition: Subscriber.h:114
void setStrict(bool strict=true)
Definition: Subscriber.h:151
bool topic(const std::string &name)
Set topic to subscribe to.
Definition: Subscriber.h:63
void interrupt() override
Interrupt any current reads or writes attached to the port.
Definition: Subscriber.h:90
virtual yarp::conf::float64_t asFloat64() const
Get 64-bit floating point value.
Definition: Value.cpp:222
virtual bool isString() const
Checks if value is a string.
Definition: Value.cpp:156
virtual yarp::conf::vocab32_t asVocab32() const
Get vocabulary identifier as an integer.
Definition: Value.cpp:228
virtual std::int32_t asInt32() const
Get 32-bit integer value.
Definition: Value.cpp:204
virtual Bottle * asList() const
Get list value.
Definition: Value.cpp:240
virtual bool isFloat64() const
Checks if value is a 64-bit floating point number.
Definition: Value.cpp:150
virtual std::string asString() const
Get string value.
Definition: Value.cpp:234
yarp::rosmsg::geometry_msgs::Transform transform
yarp::rosmsg::geometry_msgs::Quaternion rotation
Definition: Transform.h:35
yarp::rosmsg::geometry_msgs::Vector3 translation
Definition: Transform.h:34
yarp::conf::float64_t y
Definition: Vector3.h:38
yarp::conf::float64_t z
Definition: Vector3.h:39
yarp::conf::float64_t x
Definition: Vector3.h:37
yarp::rosmsg::TickTime stamp
Definition: Header.h:45
std::vector< yarp::rosmsg::geometry_msgs::TransformStamped > transforms
Definition: TFMessage.h:30
A class for a Matrix.
Definition: Matrix.h:43
#define M_PI
std::string toString(const T &value)
convert an arbitrary type to string.
#define yCInfo(component,...)
Definition: LogComponent.h:132
#define yCError(component,...)
Definition: LogComponent.h:154
#define yCTrace(component,...)
Definition: LogComponent.h:85
#define yCWarning(component,...)
Definition: LogComponent.h:143
#define yCDebug(component,...)
Definition: LogComponent.h:109
#define YARP_LOG_COMPONENT(name,...)
Definition: LogComponent.h:77
std::string to_string(IntegerType x)
Definition: numeric.h:115
An interface for the device drivers.
double now()
Return the current time in seconds, relative to an arbitrary starting point.
Definition: Time.cpp:121
void delay(double seconds)
Wait for a certain number of seconds.
Definition: Time.cpp:111
An interface to the operating system, including Port based communication.
Signal processing.
Definition: Image.h:22