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