buffer_core.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2010, Willow Garage, Inc.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
32 #include "tf2/buffer_core.h"
33 #include "tf2/time_cache.h"
34 #include "tf2/exceptions.h"
35 #include "tf2_msgs/TF2Error.h"
36 
37 #include <assert.h>
38 #include <console_bridge/console.h>
40 #include <boost/foreach.hpp>
41 #include <boost/tuple/tuple.hpp>
42 
43 namespace tf2
44 {
45 
46 // Tolerance for acceptable quaternion normalization
47 static double QUATERNION_NORMALIZATION_TOLERANCE = 10e-3;
48 
50 void transformMsgToTF2(const geometry_msgs::Transform& msg, tf2::Transform& tf2)
51 {tf2 = tf2::Transform(tf2::Quaternion(msg.rotation.x, msg.rotation.y, msg.rotation.z, msg.rotation.w), tf2::Vector3(msg.translation.x, msg.translation.y, msg.translation.z));}
52 
54 void transformTF2ToMsg(const tf2::Transform& tf2, geometry_msgs::Transform& msg)
55 {
56  msg.translation.x = tf2.getOrigin().x();
57  msg.translation.y = tf2.getOrigin().y();
58  msg.translation.z = tf2.getOrigin().z();
59  msg.rotation.x = tf2.getRotation().x();
60  msg.rotation.y = tf2.getRotation().y();
61  msg.rotation.z = tf2.getRotation().z();
62  msg.rotation.w = tf2.getRotation().w();
63 }
64 
66 void transformTF2ToMsg(const tf2::Transform& tf2, geometry_msgs::TransformStamped& msg, ros::Time stamp, const std::string& frame_id, const std::string& child_frame_id)
67 {
68  transformTF2ToMsg(tf2, msg.transform);
69  msg.header.stamp = stamp;
70  msg.header.frame_id = frame_id;
71  msg.child_frame_id = child_frame_id;
72 }
73 
74 void transformTF2ToMsg(const tf2::Quaternion& orient, const tf2::Vector3& pos, geometry_msgs::Transform& msg)
75 {
76  msg.translation.x = pos.x();
77  msg.translation.y = pos.y();
78  msg.translation.z = pos.z();
79  msg.rotation.x = orient.x();
80  msg.rotation.y = orient.y();
81  msg.rotation.z = orient.z();
82  msg.rotation.w = orient.w();
83 }
84 
85 void transformTF2ToMsg(const tf2::Quaternion& orient, const tf2::Vector3& pos, geometry_msgs::TransformStamped& msg, ros::Time stamp, const std::string& frame_id, const std::string& child_frame_id)
86 {
87  transformTF2ToMsg(orient, pos, msg.transform);
88  msg.header.stamp = stamp;
89  msg.header.frame_id = frame_id;
90  msg.child_frame_id = child_frame_id;
91 }
92 
93 void setIdentity(geometry_msgs::Transform& tx)
94 {
95  tx.translation.x = 0;
96  tx.translation.y = 0;
97  tx.translation.z = 0;
98  tx.rotation.x = 0;
99  tx.rotation.y = 0;
100  tx.rotation.z = 0;
101  tx.rotation.w = 1;
102 }
103 
104 bool startsWithSlash(const std::string& frame_id)
105 {
106  if (frame_id.size() > 0)
107  if (frame_id[0] == '/')
108  return true;
109  return false;
110 }
111 
112 std::string stripSlash(const std::string& in)
113 {
114  std::string out = in;
115  if (startsWithSlash(in))
116  out.erase(0,1);
117  return out;
118 }
119 
120 
121 bool BufferCore::warnFrameId(const char* function_name_arg, const std::string& frame_id) const
122 {
123  if (frame_id.size() == 0)
124  {
125  std::stringstream ss;
126  ss << "Invalid argument passed to "<< function_name_arg <<" in tf2 frame_ids cannot be empty";
127  CONSOLE_BRIDGE_logWarn("%s",ss.str().c_str());
128  return true;
129  }
130 
131  if (startsWithSlash(frame_id))
132  {
133  std::stringstream ss;
134  ss << "Invalid argument \"" << frame_id << "\" passed to "<< function_name_arg <<" in tf2 frame_ids cannot start with a '/' like: ";
135  CONSOLE_BRIDGE_logWarn("%s",ss.str().c_str());
136  return true;
137  }
138 
139  return false;
140 }
141 
142 CompactFrameID BufferCore::validateFrameId(const char* function_name_arg, const std::string& frame_id) const
143 {
144  if (frame_id.empty())
145  {
146  std::stringstream ss;
147  ss << "Invalid argument passed to "<< function_name_arg <<" in tf2 frame_ids cannot be empty";
148  throw tf2::InvalidArgumentException(ss.str().c_str());
149  }
150 
151  if (startsWithSlash(frame_id))
152  {
153  std::stringstream ss;
154  ss << "Invalid argument \"" << frame_id << "\" passed to "<< function_name_arg <<" in tf2 frame_ids cannot start with a '/' like: ";
155  throw tf2::InvalidArgumentException(ss.str().c_str());
156  }
157 
158  CompactFrameID id = lookupFrameNumber(frame_id);
159  if (id == 0)
160  {
161  std::stringstream ss;
162  ss << "\"" << frame_id << "\" passed to "<< function_name_arg <<" does not exist. ";
163  throw tf2::LookupException(ss.str().c_str());
164  }
165 
166  return id;
167 }
168 
170 : cache_time_(cache_time)
171 , transformable_callbacks_counter_(0)
172 , transformable_requests_counter_(0)
173 , using_dedicated_thread_(false)
174 {
175  frameIDs_["NO_PARENT"] = 0;
176  frames_.push_back(TimeCacheInterfacePtr());
177  frameIDs_reverse.push_back("NO_PARENT");
178 }
179 
181 {
182 
183 }
184 
186 {
187  //old_tf_.clear();
188 
189 
190  boost::mutex::scoped_lock lock(frame_mutex_);
191  if ( frames_.size() > 1 )
192  {
193  for (std::vector<TimeCacheInterfacePtr>::iterator cache_it = frames_.begin() + 1; cache_it != frames_.end(); ++cache_it)
194  {
195  if (*cache_it)
196  (*cache_it)->clearList();
197  }
198  }
199 
200 }
201 
202 bool BufferCore::setTransform(const geometry_msgs::TransformStamped& transform_in, const std::string& authority, bool is_static)
203 {
204 
206  /* tf::StampedTransform tf_transform;
207  tf::transformStampedMsgToTF(transform_in, tf_transform);
208  if (!old_tf_.setTransform(tf_transform, authority))
209  {
210  printf("Warning old setTransform Failed but was not caught\n");
211  }*/
212 
214  geometry_msgs::TransformStamped stripped = transform_in;
215  stripped.header.frame_id = stripSlash(stripped.header.frame_id);
216  stripped.child_frame_id = stripSlash(stripped.child_frame_id);
217 
218 
219  bool error_exists = false;
220  if (stripped.child_frame_id == stripped.header.frame_id)
221  {
222  CONSOLE_BRIDGE_logError("TF_SELF_TRANSFORM: Ignoring transform from authority \"%s\" with frame_id and child_frame_id \"%s\" because they are the same", authority.c_str(), stripped.child_frame_id.c_str());
223  error_exists = true;
224  }
225 
226  if (stripped.child_frame_id == "")
227  {
228  CONSOLE_BRIDGE_logError("TF_NO_CHILD_FRAME_ID: Ignoring transform from authority \"%s\" because child_frame_id not set ", authority.c_str());
229  error_exists = true;
230  }
231 
232  if (stripped.header.frame_id == "")
233  {
234  CONSOLE_BRIDGE_logError("TF_NO_FRAME_ID: Ignoring transform with child_frame_id \"%s\" from authority \"%s\" because frame_id not set", stripped.child_frame_id.c_str(), authority.c_str());
235  error_exists = true;
236  }
237 
238  if (std::isnan(stripped.transform.translation.x) || std::isnan(stripped.transform.translation.y) || std::isnan(stripped.transform.translation.z)||
239  std::isnan(stripped.transform.rotation.x) || std::isnan(stripped.transform.rotation.y) || std::isnan(stripped.transform.rotation.z) || std::isnan(stripped.transform.rotation.w))
240  {
241  CONSOLE_BRIDGE_logError("TF_NAN_INPUT: Ignoring transform for child_frame_id \"%s\" from authority \"%s\" because of a nan value in the transform (%f %f %f) (%f %f %f %f)",
242  stripped.child_frame_id.c_str(), authority.c_str(),
243  stripped.transform.translation.x, stripped.transform.translation.y, stripped.transform.translation.z,
244  stripped.transform.rotation.x, stripped.transform.rotation.y, stripped.transform.rotation.z, stripped.transform.rotation.w
245  );
246  error_exists = true;
247  }
248 
249  bool valid = std::abs((stripped.transform.rotation.w * stripped.transform.rotation.w
250  + stripped.transform.rotation.x * stripped.transform.rotation.x
251  + stripped.transform.rotation.y * stripped.transform.rotation.y
252  + stripped.transform.rotation.z * stripped.transform.rotation.z) - 1.0f) < QUATERNION_NORMALIZATION_TOLERANCE;
253 
254  if (!valid)
255  {
256  CONSOLE_BRIDGE_logError("TF_DENORMALIZED_QUATERNION: Ignoring transform for child_frame_id \"%s\" from authority \"%s\" because of an invalid quaternion in the transform (%f %f %f %f)",
257  stripped.child_frame_id.c_str(), authority.c_str(),
258  stripped.transform.rotation.x, stripped.transform.rotation.y, stripped.transform.rotation.z, stripped.transform.rotation.w);
259  error_exists = true;
260  }
261 
262  if (error_exists)
263  return false;
264 
265  {
266  boost::mutex::scoped_lock lock(frame_mutex_);
267  CompactFrameID frame_number = lookupOrInsertFrameNumber(stripped.child_frame_id);
268  TimeCacheInterfacePtr frame = getFrame(frame_number);
269  if (frame == NULL)
270  frame = allocateFrame(frame_number, is_static);
271 
272  std::string error_string;
273  if (frame->insertData(TransformStorage(stripped, lookupOrInsertFrameNumber(stripped.header.frame_id), frame_number), &error_string))
274  {
275  frame_authority_[frame_number] = authority;
276  }
277  else
278  {
279  CONSOLE_BRIDGE_logWarn((error_string+" for frame %s (parent %s) at time %lf according to authority %s").c_str(), stripped.child_frame_id.c_str(), stripped.header.frame_id.c_str(), stripped.header.stamp.toSec(), authority.c_str());
280  return false;
281  }
282  }
283 
285 
286  return true;
287 }
288 
290 {
291  TimeCacheInterfacePtr frame_ptr = frames_[cfid];
292  if (is_static) {
294  } else {
296  }
297 
298  return frames_[cfid];
299 }
300 
302 {
307 };
308 
309 // TODO for Jade: Merge walkToTopParent functions; this is now a stub to preserve ABI
310 template<typename F>
311 int BufferCore::walkToTopParent(F& f, ros::Time time, CompactFrameID target_id, CompactFrameID source_id, std::string* error_string) const
312 {
313  return walkToTopParent(f, time, target_id, source_id, error_string, NULL);
314 }
315 
316 template<typename F>
318  CompactFrameID source_id, std::string* error_string, std::vector<CompactFrameID>
319  *frame_chain) const
320 {
321  if (frame_chain)
322  frame_chain->clear();
323 
324  // Short circuit if zero length transform to allow lookups on non existant links
325  if (source_id == target_id)
326  {
327  f.finalize(Identity, time);
328  return tf2_msgs::TF2Error::NO_ERROR;
329  }
330 
331  //If getting the latest get the latest common time
332  if (time == ros::Time())
333  {
334  int retval = getLatestCommonTime(target_id, source_id, time, error_string);
335  if (retval != tf2_msgs::TF2Error::NO_ERROR)
336  {
337  return retval;
338  }
339  }
340 
341  // Walk the tree to its root from the source frame, accumulating the transform
342  CompactFrameID frame = source_id;
343  CompactFrameID top_parent = frame;
344  uint32_t depth = 0;
345 
346  std::string extrapolation_error_string;
347  bool extrapolation_might_have_occurred = false;
348 
349  while (frame != 0)
350  {
351  TimeCacheInterfacePtr cache = getFrame(frame);
352  if (frame_chain)
353  frame_chain->push_back(frame);
354 
355  if (!cache)
356  {
357  // There will be no cache for the very root of the tree
358  top_parent = frame;
359  break;
360  }
361 
362  CompactFrameID parent = f.gather(cache, time, error_string ? &extrapolation_error_string : NULL);
363  if (parent == 0)
364  {
365  // Just break out here... there may still be a path from source -> target
366  top_parent = frame;
367  extrapolation_might_have_occurred = true;
368  break;
369  }
370 
371  // Early out... target frame is a direct parent of the source frame
372  if (frame == target_id)
373  {
374  f.finalize(TargetParentOfSource, time);
375  return tf2_msgs::TF2Error::NO_ERROR;
376  }
377 
378  f.accum(true);
379 
380  top_parent = frame;
381  frame = parent;
382 
383  ++depth;
384  if (depth > MAX_GRAPH_DEPTH)
385  {
386  if (error_string)
387  {
388  std::stringstream ss;
389  ss << "The tf tree is invalid because it contains a loop." << std::endl
390  << allFramesAsStringNoLock() << std::endl;
391  *error_string = ss.str();
392  }
393  return tf2_msgs::TF2Error::LOOKUP_ERROR;
394  }
395  }
396 
397  // Now walk to the top parent from the target frame, accumulating its transform
398  frame = target_id;
399  depth = 0;
400  std::vector<CompactFrameID> reverse_frame_chain;
401 
402  while (frame != top_parent)
403  {
404  TimeCacheInterfacePtr cache = getFrame(frame);
405  if (frame_chain)
406  reverse_frame_chain.push_back(frame);
407 
408  if (!cache)
409  {
410  break;
411  }
412 
413  CompactFrameID parent = f.gather(cache, time, error_string);
414  if (parent == 0)
415  {
416  if (error_string)
417  {
418  // optimize performance by not using stringstream
419  char str[1000];
420  snprintf(str, sizeof(str), "%s, when looking up transform from frame [%s] to frame [%s]", error_string->c_str(), lookupFrameString(source_id).c_str(), lookupFrameString(target_id).c_str());
421  *error_string = str;
422  }
423 
424  return tf2_msgs::TF2Error::EXTRAPOLATION_ERROR;
425  }
426 
427  // Early out... source frame is a direct parent of the target frame
428  if (frame == source_id)
429  {
430  f.finalize(SourceParentOfTarget, time);
431  if (frame_chain)
432  {
433  // Use the walk we just did
434  frame_chain->swap(reverse_frame_chain);
435  // Reverse it before returning because this is the reverse walk.
436  std::reverse(frame_chain->begin(), frame_chain->end());
437  }
438  return tf2_msgs::TF2Error::NO_ERROR;
439  }
440 
441  f.accum(false);
442 
443  frame = parent;
444 
445  ++depth;
446  if (depth > MAX_GRAPH_DEPTH)
447  {
448  if (error_string)
449  {
450  std::stringstream ss;
451  ss << "The tf tree is invalid because it contains a loop." << std::endl
452  << allFramesAsStringNoLock() << std::endl;
453  *error_string = ss.str();
454  }
455  return tf2_msgs::TF2Error::LOOKUP_ERROR;
456  }
457  }
458 
459  if (frame != top_parent)
460  {
461  if (extrapolation_might_have_occurred)
462  {
463  if (error_string)
464  {
465  // optimize performance by not using stringstream
466  char str[1000];
467  snprintf(str, sizeof(str), "%s, when looking up transform from frame [%s] to frame [%s]", extrapolation_error_string.c_str(), lookupFrameString(source_id).c_str(), lookupFrameString(target_id).c_str());
468  *error_string = str;
469  }
470 
471  return tf2_msgs::TF2Error::EXTRAPOLATION_ERROR;
472 
473  }
474 
475  createConnectivityErrorString(source_id, target_id, error_string);
476  return tf2_msgs::TF2Error::CONNECTIVITY_ERROR;
477  }
478  else if (frame_chain){
479  // append top_parent to reverse_frame_chain for easier matching/trimming
480  reverse_frame_chain.push_back(frame);
481  }
482 
483  f.finalize(FullPath, time);
484  if (frame_chain)
485  {
486  // Pruning: Compare the chains starting at the parent (end) until they differ
487  int m = reverse_frame_chain.size()-1;
488  int n = frame_chain->size()-1;
489  for (; m >= 0 && n >= 0; --m, --n)
490  {
491  if ((*frame_chain)[n] != reverse_frame_chain[m])
492  {
493  break;
494  }
495  }
496  // Erase all duplicate items from frame_chain
497  if (n > 0)
498  {
499  // N is offset by 1 and leave the common parent for this result
500  frame_chain->erase(frame_chain->begin() + (n + 2), frame_chain->end());
501  }
502  if (m < reverse_frame_chain.size())
503  {
504  for (int i = m; i >= 0; --i)
505  {
506  frame_chain->push_back(reverse_frame_chain[i]);
507  }
508  }
509  }
510 
511  return tf2_msgs::TF2Error::NO_ERROR;
512 }
513 
514 
515 
517 {
519  : source_to_top_quat(0.0, 0.0, 0.0, 1.0)
520  , source_to_top_vec(0.0, 0.0, 0.0)
521  , target_to_top_quat(0.0, 0.0, 0.0, 1.0)
522  , target_to_top_vec(0.0, 0.0, 0.0)
523  , result_quat(0.0, 0.0, 0.0, 1.0)
524  , result_vec(0.0, 0.0, 0.0)
525  {
526  }
527 
528  CompactFrameID gather(TimeCacheInterfacePtr cache, ros::Time time, std::string* error_string)
529  {
530  if (!cache->getData(time, st, error_string))
531  {
532  return 0;
533  }
534 
535  return st.frame_id_;
536  }
537 
538  void accum(bool source)
539  {
540  if (source)
541  {
544  }
545  else
546  {
549  }
550  }
551 
552  void finalize(WalkEnding end, ros::Time _time)
553  {
554  switch (end)
555  {
556  case Identity:
557  break;
561  break;
563  {
564  tf2::Quaternion inv_target_quat = target_to_top_quat.inverse();
565  tf2::Vector3 inv_target_vec = quatRotate(inv_target_quat, -target_to_top_vec);
566  result_vec = inv_target_vec;
567  result_quat = inv_target_quat;
568  break;
569  }
570  case FullPath:
571  {
572  tf2::Quaternion inv_target_quat = target_to_top_quat.inverse();
573  tf2::Vector3 inv_target_vec = quatRotate(inv_target_quat, -target_to_top_vec);
574 
575  result_vec = quatRotate(inv_target_quat, source_to_top_vec) + inv_target_vec;
576  result_quat = inv_target_quat * source_to_top_quat;
577  }
578  break;
579  };
580 
581  time = _time;
582  }
583 
587  tf2::Vector3 source_to_top_vec;
589  tf2::Vector3 target_to_top_vec;
590 
592  tf2::Vector3 result_vec;
593 };
594 
595 geometry_msgs::TransformStamped BufferCore::lookupTransform(const std::string& target_frame,
596  const std::string& source_frame,
597  const ros::Time& time) const
598 {
599  boost::mutex::scoped_lock lock(frame_mutex_);
600 
601  if (target_frame == source_frame) {
602  geometry_msgs::TransformStamped identity;
603  identity.header.frame_id = target_frame;
604  identity.child_frame_id = source_frame;
605  identity.transform.rotation.w = 1;
606 
607  if (time == ros::Time())
608  {
609  CompactFrameID target_id = lookupFrameNumber(target_frame);
610  TimeCacheInterfacePtr cache = getFrame(target_id);
611  if (cache)
612  identity.header.stamp = cache->getLatestTimestamp();
613  else
614  identity.header.stamp = time;
615  }
616  else
617  identity.header.stamp = time;
618 
619  return identity;
620  }
621 
622  //Identify case does not need to be validated above
623  CompactFrameID target_id = validateFrameId("lookupTransform argument target_frame", target_frame);
624  CompactFrameID source_id = validateFrameId("lookupTransform argument source_frame", source_frame);
625 
626  std::string error_string;
627  TransformAccum accum;
628  int retval = walkToTopParent(accum, time, target_id, source_id, &error_string);
629  if (retval != tf2_msgs::TF2Error::NO_ERROR)
630  {
631  switch (retval)
632  {
633  case tf2_msgs::TF2Error::CONNECTIVITY_ERROR:
634  throw ConnectivityException(error_string);
635  case tf2_msgs::TF2Error::EXTRAPOLATION_ERROR:
636  throw ExtrapolationException(error_string);
637  case tf2_msgs::TF2Error::LOOKUP_ERROR:
638  throw LookupException(error_string);
639  default:
640  CONSOLE_BRIDGE_logError("Unknown error code: %d", retval);
641  assert(0);
642  }
643  }
644 
645  geometry_msgs::TransformStamped output_transform;
646  transformTF2ToMsg(accum.result_quat, accum.result_vec, output_transform, accum.time, target_frame, source_frame);
647  return output_transform;
648 }
649 
650 
651 geometry_msgs::TransformStamped BufferCore::lookupTransform(const std::string& target_frame,
652  const ros::Time& target_time,
653  const std::string& source_frame,
654  const ros::Time& source_time,
655  const std::string& fixed_frame) const
656 {
657  validateFrameId("lookupTransform argument target_frame", target_frame);
658  validateFrameId("lookupTransform argument source_frame", source_frame);
659  validateFrameId("lookupTransform argument fixed_frame", fixed_frame);
660 
661  geometry_msgs::TransformStamped output;
662  geometry_msgs::TransformStamped temp1 = lookupTransform(fixed_frame, source_frame, source_time);
663  geometry_msgs::TransformStamped temp2 = lookupTransform(target_frame, fixed_frame, target_time);
664 
665  tf2::Transform tf1, tf2;
666  transformMsgToTF2(temp1.transform, tf1);
667  transformMsgToTF2(temp2.transform, tf2);
668  transformTF2ToMsg(tf2*tf1, output.transform);
669  output.header.stamp = temp2.header.stamp;
670  output.header.frame_id = target_frame;
671  output.child_frame_id = source_frame;
672  return output;
673 }
674 
675 
676 
677 /*
678 geometry_msgs::Twist BufferCore::lookupTwist(const std::string& tracking_frame,
679  const std::string& observation_frame,
680  const ros::Time& time,
681  const ros::Duration& averaging_interval) const
682 {
683  try
684  {
685  geometry_msgs::Twist t;
686  old_tf_.lookupTwist(tracking_frame, observation_frame,
687  time, averaging_interval, t);
688  return t;
689  }
690  catch (tf::LookupException& ex)
691  {
692  throw tf2::LookupException(ex.what());
693  }
694  catch (tf::ConnectivityException& ex)
695  {
696  throw tf2::ConnectivityException(ex.what());
697  }
698  catch (tf::ExtrapolationException& ex)
699  {
700  throw tf2::ExtrapolationException(ex.what());
701  }
702  catch (tf::InvalidArgument& ex)
703  {
704  throw tf2::InvalidArgumentException(ex.what());
705  }
706 }
707 
708 geometry_msgs::Twist BufferCore::lookupTwist(const std::string& tracking_frame,
709  const std::string& observation_frame,
710  const std::string& reference_frame,
711  const tf2::Point & reference_point,
712  const std::string& reference_point_frame,
713  const ros::Time& time,
714  const ros::Duration& averaging_interval) const
715 {
716  try{
717  geometry_msgs::Twist t;
718  old_tf_.lookupTwist(tracking_frame, observation_frame, reference_frame, reference_point, reference_point_frame,
719  time, averaging_interval, t);
720  return t;
721  }
722  catch (tf::LookupException& ex)
723  {
724  throw tf2::LookupException(ex.what());
725  }
726  catch (tf::ConnectivityException& ex)
727  {
728  throw tf2::ConnectivityException(ex.what());
729  }
730  catch (tf::ExtrapolationException& ex)
731  {
732  throw tf2::ExtrapolationException(ex.what());
733  }
734  catch (tf::InvalidArgument& ex)
735  {
736  throw tf2::InvalidArgumentException(ex.what());
737  }
738 }
739 */
740 
742 {
743  CompactFrameID gather(TimeCacheInterfacePtr cache, ros::Time time, std::string* error_string)
744  {
745  return cache->getParent(time, error_string);
746  }
747 
748  void accum(bool source)
749  {
750  }
751 
752  void finalize(WalkEnding end, ros::Time _time)
753  {
754  }
755 
757 };
758 
760  const ros::Time& time, std::string* error_msg) const
761 {
762  if (target_id == 0 || source_id == 0)
763  {
764  if (error_msg)
765  {
766  if (target_id == 0)
767  {
768  *error_msg += std::string("target_frame: " + lookupFrameString(target_id ) + " does not exist.");
769  }
770  if (source_id == 0)
771  {
772  if (target_id == 0)
773  {
774  *error_msg += std::string(" ");
775  }
776  *error_msg += std::string("source_frame: " + lookupFrameString(source_id) + " " + lookupFrameString(source_id ) + " does not exist.");
777  }
778  }
779  return false;
780  }
781 
782  if (target_id == source_id)
783  {
784  return true;
785  }
786 
787  CanTransformAccum accum;
788  if (walkToTopParent(accum, time, target_id, source_id, error_msg) == tf2_msgs::TF2Error::NO_ERROR)
789  {
790  return true;
791  }
792 
793  return false;
794 }
795 
797  const ros::Time& time, std::string* error_msg) const
798 {
799  boost::mutex::scoped_lock lock(frame_mutex_);
800  return canTransformNoLock(target_id, source_id, time, error_msg);
801 }
802 
803 bool BufferCore::canTransform(const std::string& target_frame, const std::string& source_frame,
804  const ros::Time& time, std::string* error_msg) const
805 {
806  // Short circuit if target_frame == source_frame
807  if (target_frame == source_frame)
808  return true;
809 
810  if (warnFrameId("canTransform argument target_frame", target_frame))
811  return false;
812  if (warnFrameId("canTransform argument source_frame", source_frame))
813  return false;
814 
815  boost::mutex::scoped_lock lock(frame_mutex_);
816 
817  CompactFrameID target_id = lookupFrameNumber(target_frame);
818  CompactFrameID source_id = lookupFrameNumber(source_frame);
819 
820  if (target_id == 0 || source_id == 0)
821  {
822  if (error_msg)
823  {
824  if (target_id == 0)
825  {
826  *error_msg += std::string("canTransform: target_frame " + target_frame + " does not exist.");
827  }
828  if (source_id == 0)
829  {
830  if (target_id == 0)
831  {
832  *error_msg += std::string(" ");
833  }
834  *error_msg += std::string("canTransform: source_frame " + source_frame + " does not exist.");
835  }
836  }
837  return false;
838  }
839  return canTransformNoLock(target_id, source_id, time, error_msg);
840 }
841 
842 bool BufferCore::canTransform(const std::string& target_frame, const ros::Time& target_time,
843  const std::string& source_frame, const ros::Time& source_time,
844  const std::string& fixed_frame, std::string* error_msg) const
845 {
846  if (warnFrameId("canTransform argument target_frame", target_frame))
847  return false;
848  if (warnFrameId("canTransform argument source_frame", source_frame))
849  return false;
850  if (warnFrameId("canTransform argument fixed_frame", fixed_frame))
851  return false;
852 
853  boost::mutex::scoped_lock lock(frame_mutex_);
854  CompactFrameID target_id = lookupFrameNumber(target_frame);
855  CompactFrameID source_id = lookupFrameNumber(source_frame);
856  CompactFrameID fixed_id = lookupFrameNumber(fixed_frame);
857 
858  if (target_id == 0 || source_id == 0 || fixed_id == 0)
859  {
860  if (error_msg)
861  {
862  if (target_id == 0)
863  {
864  *error_msg += std::string("canTransform: target_frame " + target_frame + " does not exist.");
865  }
866  if (source_id == 0)
867  {
868  if (target_id == 0)
869  {
870  *error_msg += std::string(" ");
871  }
872  *error_msg += std::string("canTransform: source_frame " + source_frame + " does not exist.");
873  }
874  if (fixed_id == 0)
875  {
876  if (target_id == 0 || source_id == 0)
877  {
878  *error_msg += std::string(" ");
879  }
880  *error_msg += std::string("fixed_frame: " + fixed_frame + "does not exist.");
881  }
882  }
883  return false;
884  }
885  return canTransformNoLock(target_id, fixed_id, target_time, error_msg) && canTransformNoLock(fixed_id, source_id, source_time, error_msg);
886 }
887 
888 
890 {
891  if (frame_id >= frames_.size())
892  return TimeCacheInterfacePtr();
893  else
894  {
895  return frames_[frame_id];
896  }
897 }
898 
899 CompactFrameID BufferCore::lookupFrameNumber(const std::string& frameid_str) const
900 {
901  CompactFrameID retval;
902  M_StringToCompactFrameID::const_iterator map_it = frameIDs_.find(frameid_str);
903  if (map_it == frameIDs_.end())
904  {
905  retval = CompactFrameID(0);
906  }
907  else
908  retval = map_it->second;
909  return retval;
910 }
911 
913 {
914  CompactFrameID retval = 0;
915  M_StringToCompactFrameID::iterator map_it = frameIDs_.find(frameid_str);
916  if (map_it == frameIDs_.end())
917  {
918  retval = CompactFrameID(frames_.size());
919  frames_.push_back(TimeCacheInterfacePtr());//Just a place holder for iteration
920  frameIDs_[frameid_str] = retval;
921  frameIDs_reverse.push_back(frameid_str);
922  }
923  else
924  retval = frameIDs_[frameid_str];
925 
926  return retval;
927 }
928 
929 const std::string& BufferCore::lookupFrameString(CompactFrameID frame_id_num) const
930 {
931  if (frame_id_num >= frameIDs_reverse.size())
932  {
933  std::stringstream ss;
934  ss << "Reverse lookup of frame id " << frame_id_num << " failed!";
935  throw tf2::LookupException(ss.str());
936  }
937  else
938  return frameIDs_reverse[frame_id_num];
939 }
940 
941 void BufferCore::createConnectivityErrorString(CompactFrameID source_frame, CompactFrameID target_frame, std::string* out) const
942 {
943  if (!out)
944  {
945  return;
946  }
947  *out = std::string("Could not find a connection between '"+lookupFrameString(target_frame)+"' and '"+
948  lookupFrameString(source_frame)+"' because they are not part of the same tree."+
949  "Tf has two or more unconnected trees.");
950 }
951 
952 std::string BufferCore::allFramesAsString() const
953 {
954  boost::mutex::scoped_lock lock(frame_mutex_);
955  return this->allFramesAsStringNoLock();
956 }
957 
959 {
960  std::stringstream mstream;
961 
962  TransformStorage temp;
963 
964  // for (std::vector< TimeCache*>::iterator it = frames_.begin(); it != frames_.end(); ++it)
965 
967  for (unsigned int counter = 1; counter < frames_.size(); counter ++)
968  {
969  TimeCacheInterfacePtr frame_ptr = getFrame(CompactFrameID(counter));
970  if (frame_ptr == NULL)
971  continue;
972  CompactFrameID frame_id_num;
973  if( frame_ptr->getData(ros::Time(), temp))
974  frame_id_num = temp.frame_id_;
975  else
976  {
977  frame_id_num = 0;
978  }
979  mstream << "Frame "<< frameIDs_reverse[counter] << " exists with parent " << frameIDs_reverse[frame_id_num] << "." <<std::endl;
980  }
981 
982  return mstream.str();
983 }
984 
986 {
988  : id(id)
989  {}
990 
991  bool operator()(const P_TimeAndFrameID& rhs) const
992  {
993  return rhs.second == id;
994  }
995 
997 };
998 
999 int BufferCore::getLatestCommonTime(CompactFrameID target_id, CompactFrameID source_id, ros::Time & time, std::string * error_string) const
1000 {
1001  // Error if one of the frames don't exist.
1002  if (source_id == 0 || target_id == 0) return tf2_msgs::TF2Error::LOOKUP_ERROR;
1003 
1004  if (source_id == target_id)
1005  {
1006  TimeCacheInterfacePtr cache = getFrame(source_id);
1007  //Set time to latest timestamp of frameid in case of target and source frame id are the same
1008  if (cache)
1009  time = cache->getLatestTimestamp();
1010  else
1011  time = ros::Time();
1012  return tf2_msgs::TF2Error::NO_ERROR;
1013  }
1014 
1015  std::vector<P_TimeAndFrameID> lct_cache;
1016 
1017  // Walk the tree to its root from the source frame, accumulating the list of parent/time as well as the latest time
1018  // in the target is a direct parent
1019  CompactFrameID frame = source_id;
1020  P_TimeAndFrameID temp;
1021  uint32_t depth = 0;
1022  ros::Time common_time = ros::TIME_MAX;
1023  while (frame != 0)
1024  {
1025  TimeCacheInterfacePtr cache = getFrame(frame);
1026 
1027  if (!cache)
1028  {
1029  // There will be no cache for the very root of the tree
1030  break;
1031  }
1032 
1033  P_TimeAndFrameID latest = cache->getLatestTimeAndParent();
1034 
1035  if (latest.second == 0)
1036  {
1037  // Just break out here... there may still be a path from source -> target
1038  break;
1039  }
1040 
1041  if (!latest.first.isZero())
1042  {
1043  common_time = std::min(latest.first, common_time);
1044  }
1045 
1046  lct_cache.push_back(latest);
1047 
1048  frame = latest.second;
1049 
1050  // Early out... target frame is a direct parent of the source frame
1051  if (frame == target_id)
1052  {
1053  time = common_time;
1054  if (time == ros::TIME_MAX)
1055  {
1056  time = ros::Time();
1057  }
1058  return tf2_msgs::TF2Error::NO_ERROR;
1059  }
1060 
1061  ++depth;
1062  if (depth > MAX_GRAPH_DEPTH)
1063  {
1064  if (error_string)
1065  {
1066  std::stringstream ss;
1067  ss<<"The tf tree is invalid because it contains a loop." << std::endl
1068  << allFramesAsStringNoLock() << std::endl;
1069  *error_string = ss.str();
1070  }
1071  return tf2_msgs::TF2Error::LOOKUP_ERROR;
1072  }
1073  }
1074 
1075  // Now walk to the top parent from the target frame, accumulating the latest time and looking for a common parent
1076  frame = target_id;
1077  depth = 0;
1078  common_time = ros::TIME_MAX;
1079  CompactFrameID common_parent = 0;
1080  while (true)
1081  {
1082  TimeCacheInterfacePtr cache = getFrame(frame);
1083 
1084  if (!cache)
1085  {
1086  break;
1087  }
1088 
1089  P_TimeAndFrameID latest = cache->getLatestTimeAndParent();
1090 
1091  if (latest.second == 0)
1092  {
1093  break;
1094  }
1095 
1096  if (!latest.first.isZero())
1097  {
1098  common_time = std::min(latest.first, common_time);
1099  }
1100 
1101  std::vector<P_TimeAndFrameID>::iterator it = std::find_if(lct_cache.begin(), lct_cache.end(), TimeAndFrameIDFrameComparator(latest.second));
1102  if (it != lct_cache.end()) // found a common parent
1103  {
1104  common_parent = it->second;
1105  break;
1106  }
1107 
1108  frame = latest.second;
1109 
1110  // Early out... source frame is a direct parent of the target frame
1111  if (frame == source_id)
1112  {
1113  time = common_time;
1114  if (time == ros::TIME_MAX)
1115  {
1116  time = ros::Time();
1117  }
1118  return tf2_msgs::TF2Error::NO_ERROR;
1119  }
1120 
1121  ++depth;
1122  if (depth > MAX_GRAPH_DEPTH)
1123  {
1124  if (error_string)
1125  {
1126  std::stringstream ss;
1127  ss<<"The tf tree is invalid because it contains a loop." << std::endl
1128  << allFramesAsStringNoLock() << std::endl;
1129  *error_string = ss.str();
1130  }
1131  return tf2_msgs::TF2Error::LOOKUP_ERROR;
1132  }
1133  }
1134 
1135  if (common_parent == 0)
1136  {
1137  createConnectivityErrorString(source_id, target_id, error_string);
1138  return tf2_msgs::TF2Error::CONNECTIVITY_ERROR;
1139  }
1140 
1141  // Loop through the source -> root list until we hit the common parent
1142  {
1143  std::vector<P_TimeAndFrameID>::iterator it = lct_cache.begin();
1144  std::vector<P_TimeAndFrameID>::iterator end = lct_cache.end();
1145  for (; it != end; ++it)
1146  {
1147  if (!it->first.isZero())
1148  {
1149  common_time = std::min(common_time, it->first);
1150  }
1151 
1152  if (it->second == common_parent)
1153  {
1154  break;
1155  }
1156  }
1157  }
1158 
1159  if (common_time == ros::TIME_MAX)
1160  {
1161  common_time = ros::Time();
1162  }
1163 
1164  time = common_time;
1165  return tf2_msgs::TF2Error::NO_ERROR;
1166 }
1167 
1168 std::string BufferCore::allFramesAsYAML(double current_time) const
1169 {
1170  std::stringstream mstream;
1171  boost::mutex::scoped_lock lock(frame_mutex_);
1172 
1173  TransformStorage temp;
1174 
1175  if (frames_.size() ==1)
1176  mstream <<"{}";
1177 
1178  mstream.precision(3);
1179  mstream.setf(std::ios::fixed,std::ios::floatfield);
1180 
1181  // for (std::vector< TimeCache*>::iterator it = frames_.begin(); it != frames_.end(); ++it)
1182  for (unsigned int counter = 1; counter < frames_.size(); counter ++)//one referenced for 0 is no frame
1183  {
1184  CompactFrameID cfid = CompactFrameID(counter);
1185  CompactFrameID frame_id_num;
1186  TimeCacheInterfacePtr cache = getFrame(cfid);
1187  if (!cache)
1188  {
1189  continue;
1190  }
1191 
1192  if(!cache->getData(ros::Time(), temp))
1193  {
1194  continue;
1195  }
1196 
1197  frame_id_num = temp.frame_id_;
1198 
1199  std::string authority = "no recorded authority";
1200  std::map<CompactFrameID, std::string>::const_iterator it = frame_authority_.find(cfid);
1201  if (it != frame_authority_.end()) {
1202  authority = it->second;
1203  }
1204 
1205  double rate = cache->getListLength() / std::max((cache->getLatestTimestamp().toSec() -
1206  cache->getOldestTimestamp().toSec() ), 0.0001);
1207 
1208  mstream << std::fixed; //fixed point notation
1209  mstream.precision(3); //3 decimal places
1210  mstream << frameIDs_reverse[cfid] << ": " << std::endl;
1211  mstream << " parent: '" << frameIDs_reverse[frame_id_num] << "'" << std::endl;
1212  mstream << " broadcaster: '" << authority << "'" << std::endl;
1213  mstream << " rate: " << rate << std::endl;
1214  mstream << " most_recent_transform: " << (cache->getLatestTimestamp()).toSec() << std::endl;
1215  mstream << " oldest_transform: " << (cache->getOldestTimestamp()).toSec() << std::endl;
1216  if ( current_time > 0 ) {
1217  mstream << " transform_delay: " << current_time - cache->getLatestTimestamp().toSec() << std::endl;
1218  }
1219  mstream << " buffer_length: " << (cache->getLatestTimestamp() - cache->getOldestTimestamp()).toSec() << std::endl;
1220  }
1221 
1222  return mstream.str();
1223 }
1224 
1225 std::string BufferCore::allFramesAsYAML() const
1226 {
1227  return this->allFramesAsYAML(0.0);
1228 }
1229 
1231 {
1232  boost::mutex::scoped_lock lock(transformable_callbacks_mutex_);
1234  while (!transformable_callbacks_.insert(std::make_pair(handle, cb)).second)
1235  {
1237  }
1238 
1239  return handle;
1240 }
1241 
1243 {
1245  : handle_(handle)
1246  {}
1247 
1249  {
1250  return req.cb_handle == handle_;
1251  }
1252 
1254 };
1255 
1257 {
1258  {
1259  boost::mutex::scoped_lock lock(transformable_callbacks_mutex_);
1260  transformable_callbacks_.erase(handle);
1261  }
1262 
1263  {
1264  boost::mutex::scoped_lock lock(transformable_requests_mutex_);
1265  auto it = std::remove_if(transformable_requests_.begin(), transformable_requests_.end(), RemoveRequestByCallback(handle));
1266  if (it != transformable_requests_.end())
1267  {
1269  }
1270  }
1271 }
1272 
1273 TransformableRequestHandle BufferCore::addTransformableRequest(TransformableCallbackHandle handle, const std::string& target_frame, const std::string& source_frame, ros::Time time)
1274 {
1275  // shortcut if target == source
1276  if (target_frame == source_frame)
1277  {
1278  return 0;
1279  }
1280 
1282  req.target_id = lookupFrameNumber(target_frame);
1283  req.source_id = lookupFrameNumber(source_frame);
1284 
1285  // First check if the request is already transformable. If it is, return immediately
1286  if (canTransformInternal(req.target_id, req.source_id, time, 0))
1287  {
1288  return 0;
1289  }
1290 
1291  // Might not be transformable at all, ever (if it's too far in the past)
1292  if (req.target_id && req.source_id)
1293  {
1294  ros::Time latest_time;
1295  // TODO: This is incorrect, but better than nothing. Really we want the latest time for
1296  // any of the frames
1297  getLatestCommonTime(req.target_id, req.source_id, latest_time, 0);
1298  if (!latest_time.isZero() && time + cache_time_ < latest_time)
1299  {
1300  return 0xffffffffffffffffULL;
1301  }
1302  }
1303 
1304  req.cb_handle = handle;
1305  req.time = time;
1307  if (req.request_handle == 0 || req.request_handle == 0xffffffffffffffffULL)
1308  {
1309  req.request_handle = 1;
1310  }
1311 
1312  if (req.target_id == 0)
1313  {
1314  req.target_string = target_frame;
1315  }
1316 
1317  if (req.source_id == 0)
1318  {
1319  req.source_string = source_frame;
1320  }
1321 
1322  boost::mutex::scoped_lock lock(transformable_requests_mutex_);
1323  transformable_requests_.push_back(req);
1324 
1325  return req.request_handle;
1326 }
1327 
1329 {
1331  : handle_(handle)
1332  {}
1333 
1335  {
1336  return req.request_handle == handle_;
1337  }
1338 
1340 };
1341 
1343 {
1344  boost::mutex::scoped_lock lock(transformable_requests_mutex_);
1345  auto it = std::remove_if(transformable_requests_.begin(), transformable_requests_.end(), RemoveRequestByID(handle));
1346  if (it != transformable_requests_.end())
1347  {
1349  }
1350 }
1351 
1352 
1353 
1354 // backwards compability for tf methods
1355 boost::signals2::connection BufferCore::_addTransformsChangedListener(boost::function<void(void)> callback)
1356 {
1357  boost::mutex::scoped_lock lock(transformable_requests_mutex_);
1358  return _transforms_changed_.connect(callback);
1359 }
1360 
1361 void BufferCore::_removeTransformsChangedListener(boost::signals2::connection c)
1362 {
1363  boost::mutex::scoped_lock lock(transformable_requests_mutex_);
1364  c.disconnect();
1365 }
1366 
1367 
1368 bool BufferCore::_frameExists(const std::string& frame_id_str) const
1369 {
1370  boost::mutex::scoped_lock lock(frame_mutex_);
1371  return frameIDs_.count(frame_id_str);
1372 }
1373 
1374 bool BufferCore::_getParent(const std::string& frame_id, ros::Time time, std::string& parent) const
1375 {
1376 
1377  boost::mutex::scoped_lock lock(frame_mutex_);
1378  CompactFrameID frame_number = lookupFrameNumber(frame_id);
1379  TimeCacheInterfacePtr frame = getFrame(frame_number);
1380 
1381  if (! frame)
1382  return false;
1383 
1384  CompactFrameID parent_id = frame->getParent(time, NULL);
1385  if (parent_id == 0)
1386  return false;
1387 
1388  parent = lookupFrameString(parent_id);
1389  return true;
1390 };
1391 
1392 void BufferCore::_getFrameStrings(std::vector<std::string> & vec) const
1393 {
1394  vec.clear();
1395 
1396  boost::mutex::scoped_lock lock(frame_mutex_);
1397 
1398  TransformStorage temp;
1399 
1400  // for (std::vector< TimeCache*>::iterator it = frames_.begin(); it != frames_.end(); ++it)
1401  for (unsigned int counter = 1; counter < frameIDs_reverse.size(); counter ++)
1402  {
1403  vec.push_back(frameIDs_reverse[counter]);
1404  }
1405  return;
1406 }
1407 
1408 
1409 
1410 
1412 {
1413  boost::mutex::scoped_lock lock(transformable_requests_mutex_);
1414  V_TransformableRequest::iterator it = transformable_requests_.begin();
1415 
1416  typedef boost::tuple<TransformableCallback&, TransformableRequestHandle, std::string,
1417  std::string, ros::Time&, TransformableResult&> TransformableTuple;
1418  std::vector<TransformableTuple> transformables;
1419 
1420  for (; it != transformable_requests_.end();)
1421  {
1422  TransformableRequest& req = *it;
1423 
1424  // One or both of the frames may not have existed when the request was originally made.
1425  if (req.target_id == 0)
1426  {
1428  }
1429 
1430  if (req.source_id == 0)
1431  {
1433  }
1434 
1435  ros::Time latest_time;
1436  bool do_cb = false;
1438  // TODO: This is incorrect, but better than nothing. Really we want the latest time for
1439  // any of the frames
1440  getLatestCommonTime(req.target_id, req.source_id, latest_time, 0);
1441  if (!latest_time.isZero() && req.time + cache_time_ < latest_time)
1442  {
1443  do_cb = true;
1444  result = TransformFailure;
1445  }
1446  else if (canTransformInternal(req.target_id, req.source_id, req.time, 0))
1447  {
1448  do_cb = true;
1449  result = TransformAvailable;
1450  }
1451 
1452  if (do_cb)
1453  {
1454  {
1455  boost::mutex::scoped_lock lock2(transformable_callbacks_mutex_);
1456  M_TransformableCallback::iterator it = transformable_callbacks_.find(req.cb_handle);
1457  if (it != transformable_callbacks_.end())
1458  {
1459  transformables.push_back(boost::make_tuple(boost::ref(it->second),
1460  req.request_handle,
1463  boost::ref(req.time),
1464  boost::ref(result)));
1465  }
1466  }
1467 
1468  if (transformable_requests_.size() > 1)
1469  {
1471  }
1472 
1474  }
1475  else
1476  {
1477  ++it;
1478  }
1479  }
1480 
1481  // unlock before allowing possible user callbacks to avoid potential deadlock (#91)
1482  lock.unlock();
1483 
1484  BOOST_FOREACH (TransformableTuple tt, transformables)
1485  {
1486  tt.get<0>()(tt.get<1>(), tt.get<2>(), tt.get<3>(), tt.get<4>(), tt.get<5>());
1487  }
1488 
1489  // Backwards compatability callback for tf
1491 }
1492 
1493 
1494 std::string BufferCore::_allFramesAsDot(double current_time) const
1495 {
1496  std::stringstream mstream;
1497  mstream << "digraph G {" << std::endl;
1498  boost::mutex::scoped_lock lock(frame_mutex_);
1499 
1500  TransformStorage temp;
1501 
1502  if (frames_.size() == 1) {
1503  mstream <<"\"no tf data recieved\"";
1504  }
1505  mstream.precision(3);
1506  mstream.setf(std::ios::fixed,std::ios::floatfield);
1507 
1508  for (unsigned int counter = 1; counter < frames_.size(); counter ++) // one referenced for 0 is no frame
1509  {
1510  unsigned int frame_id_num;
1511  TimeCacheInterfacePtr counter_frame = getFrame(counter);
1512  if (!counter_frame) {
1513  continue;
1514  }
1515  if(!counter_frame->getData(ros::Time(), temp)) {
1516  continue;
1517  } else {
1518  frame_id_num = temp.frame_id_;
1519  }
1520  std::string authority = "no recorded authority";
1521  std::map<unsigned int, std::string>::const_iterator it = frame_authority_.find(counter);
1522  if (it != frame_authority_.end())
1523  authority = it->second;
1524 
1525  double rate = counter_frame->getListLength() / std::max((counter_frame->getLatestTimestamp().toSec() -
1526  counter_frame->getOldestTimestamp().toSec()), 0.0001);
1527 
1528  mstream << std::fixed; //fixed point notation
1529  mstream.precision(3); //3 decimal places
1530  mstream << "\"" << frameIDs_reverse[frame_id_num] << "\"" << " -> "
1531  << "\"" << frameIDs_reverse[counter] << "\"" << "[label=\""
1532  //<< "Time: " << current_time.toSec() << "\\n"
1533  << "Broadcaster: " << authority << "\\n"
1534  << "Average rate: " << rate << " Hz\\n"
1535  << "Most recent transform: " << (counter_frame->getLatestTimestamp()).toSec() <<" ";
1536  if (current_time > 0)
1537  mstream << "( "<< current_time - counter_frame->getLatestTimestamp().toSec() << " sec old)";
1538  mstream << "\\n"
1539  // << "(time: " << getFrame(counter)->getLatestTimestamp().toSec() << ")\\n"
1540  // << "Oldest transform: " << (current_time - getFrame(counter)->getOldestTimestamp()).toSec() << " sec old \\n"
1541  // << "(time: " << (getFrame(counter)->getOldestTimestamp()).toSec() << ")\\n"
1542  << "Buffer length: " << (counter_frame->getLatestTimestamp()-counter_frame->getOldestTimestamp()).toSec() << " sec\\n"
1543  <<"\"];" <<std::endl;
1544  }
1545 
1546  for (unsigned int counter = 1; counter < frames_.size(); counter ++)//one referenced for 0 is no frame
1547  {
1548  unsigned int frame_id_num;
1549  TimeCacheInterfacePtr counter_frame = getFrame(counter);
1550  if (!counter_frame) {
1551  if (current_time > 0) {
1552  mstream << "edge [style=invis];" <<std::endl;
1553  mstream << " subgraph cluster_legend { style=bold; color=black; label =\"view_frames Result\";\n"
1554  << "\"Recorded at time: " << current_time << "\"[ shape=plaintext ] ;\n "
1555  << "}" << "->" << "\"" << frameIDs_reverse[counter] << "\";" << std::endl;
1556  }
1557  continue;
1558  }
1559  if (counter_frame->getData(ros::Time(), temp)) {
1560  frame_id_num = temp.frame_id_;
1561  } else {
1562  frame_id_num = 0;
1563  }
1564 
1565  if(frameIDs_reverse[frame_id_num]=="NO_PARENT")
1566  {
1567  mstream << "edge [style=invis];" <<std::endl;
1568  mstream << " subgraph cluster_legend { style=bold; color=black; label =\"view_frames Result\";\n";
1569  if (current_time > 0)
1570  mstream << "\"Recorded at time: " << current_time << "\"[ shape=plaintext ] ;\n ";
1571  mstream << "}" << "->" << "\"" << frameIDs_reverse[counter] << "\";" << std::endl;
1572  }
1573  }
1574  mstream << "}";
1575  return mstream.str();
1576 }
1577 
1578 std::string BufferCore::_allFramesAsDot() const
1579 {
1580  return _allFramesAsDot(0.0);
1581 }
1582 
1583 void BufferCore::_chainAsVector(const std::string & target_frame, ros::Time target_time, const std::string & source_frame, ros::Time source_time, const std::string& fixed_frame, std::vector<std::string>& output) const
1584 {
1585  std::string error_string;
1586 
1587  output.clear(); //empty vector
1588 
1589  std::stringstream mstream;
1590  boost::mutex::scoped_lock lock(frame_mutex_);
1591 
1592  TransformAccum accum;
1593 
1594  // Get source frame/time using getFrame
1595  CompactFrameID source_id = lookupFrameNumber(source_frame);
1596  CompactFrameID fixed_id = lookupFrameNumber(fixed_frame);
1597  CompactFrameID target_id = lookupFrameNumber(target_frame);
1598 
1599  std::vector<CompactFrameID> source_frame_chain;
1600  int retval = walkToTopParent(accum, source_time, fixed_id, source_id, &error_string, &source_frame_chain);
1601 
1602  if (retval != tf2_msgs::TF2Error::NO_ERROR)
1603  {
1604  switch (retval)
1605  {
1606  case tf2_msgs::TF2Error::CONNECTIVITY_ERROR:
1607  throw ConnectivityException(error_string);
1608  case tf2_msgs::TF2Error::EXTRAPOLATION_ERROR:
1609  throw ExtrapolationException(error_string);
1610  case tf2_msgs::TF2Error::LOOKUP_ERROR:
1611  throw LookupException(error_string);
1612  default:
1613  CONSOLE_BRIDGE_logError("Unknown error code: %d", retval);
1614  assert(0);
1615  }
1616  }
1617 
1618  std::vector<CompactFrameID> target_frame_chain;
1619  retval = walkToTopParent(accum, target_time, target_id, fixed_id, &error_string, &target_frame_chain);
1620 
1621  if (retval != tf2_msgs::TF2Error::NO_ERROR)
1622  {
1623  switch (retval)
1624  {
1625  case tf2_msgs::TF2Error::CONNECTIVITY_ERROR:
1626  throw ConnectivityException(error_string);
1627  case tf2_msgs::TF2Error::EXTRAPOLATION_ERROR:
1628  throw ExtrapolationException(error_string);
1629  case tf2_msgs::TF2Error::LOOKUP_ERROR:
1630  throw LookupException(error_string);
1631  default:
1632  CONSOLE_BRIDGE_logError("Unknown error code: %d", retval);
1633  assert(0);
1634  }
1635  }
1636  // If the two chains overlap clear the overlap
1637  if (source_frame_chain.size() > 0 && target_frame_chain.size() > 0 &&
1638  source_frame_chain.back() == target_frame_chain.front())
1639  {
1640  source_frame_chain.pop_back();
1641  }
1642  // Join the two walks
1643  for (unsigned int i = 0; i < target_frame_chain.size(); ++i)
1644  {
1645  source_frame_chain.push_back(target_frame_chain[i]);
1646  }
1647 
1648 
1649  // Write each element of source_frame_chain as string
1650  for (unsigned int i = 0; i < source_frame_chain.size(); ++i)
1651  {
1652  output.push_back(lookupFrameString(source_frame_chain[i]));
1653  }
1654 }
1655 
1656 int TestBufferCore::_walkToTopParent(BufferCore& buffer, ros::Time time, CompactFrameID target_id, CompactFrameID source_id, std::string* error_string, std::vector<CompactFrameID> *frame_chain) const
1657 {
1658  TransformAccum accum;
1659  return buffer.walkToTopParent(accum, time, target_id, source_id, error_string, frame_chain);
1660 }
1661 
1662 } // namespace tf2
tf2::BufferCore::transformable_requests_counter_
uint64_t transformable_requests_counter_
Definition: buffer_core.h:356
tf2::TimeAndFrameIDFrameComparator::TimeAndFrameIDFrameComparator
TimeAndFrameIDFrameComparator(CompactFrameID id)
Definition: buffer_core.cpp:987
exceptions.h
tf2::TransformAccum::target_to_top_quat
tf2::Quaternion target_to_top_quat
Definition: buffer_core.cpp:588
tf2::BufferCore::getLatestCommonTime
int getLatestCommonTime(CompactFrameID target_frame, CompactFrameID source_frame, ros::Time &time, std::string *error_string) const
Return the latest rostime which is common across the spanning set zero if fails to cross.
Definition: buffer_core.cpp:999
tf2::transformTF2ToMsg
void transformTF2ToMsg(const tf2::Transform &tf2, geometry_msgs::Transform &msg)
convert Transform to Transform msg
Definition: buffer_core.cpp:54
tf2::BufferCore::lookupTransform
geometry_msgs::TransformStamped lookupTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time) const
Get the transform between two frames by frame ID.
Definition: buffer_core.cpp:595
tf2::TimeAndFrameIDFrameComparator::id
CompactFrameID id
Definition: buffer_core.cpp:996
tf2::BufferCore::testTransformableRequests
void testTransformableRequests()
Definition: buffer_core.cpp:1411
tf2::BufferCore::_transforms_changed_
TransformsChangedSignal _transforms_changed_
Signal which is fired whenever new transform data has arrived, from the thread the data arrived in.
Definition: buffer_core.h:364
tf2::BufferCore::warnFrameId
bool warnFrameId(const char *function_name_arg, const std::string &frame_id) const
Definition: buffer_core.cpp:121
boost::shared_ptr
tf2::BufferCore::TransformableRequest::target_id
CompactFrameID target_id
Definition: buffer_core.h:348
tf2::TransformAccum::gather
CompactFrameID gather(TimeCacheInterfacePtr cache, ros::Time time, std::string *error_string)
Definition: buffer_core.cpp:528
tf2::BufferCore::TransformableCallback
boost::function< void(TransformableRequestHandle request_handle, const std::string &target_frame, const std::string &source_frame, ros::Time time, TransformableResult result)> TransformableCallback
Definition: buffer_core.h:227
tf2::TargetParentOfSource
@ TargetParentOfSource
Definition: buffer_core.cpp:304
tf2::TimeCacheInterfacePtr
boost::shared_ptr< TimeCacheInterface > TimeCacheInterfacePtr
Definition: buffer_core.h:61
tf2::TransformAccum::finalize
void finalize(WalkEnding end, ros::Time _time)
Definition: buffer_core.cpp:552
tf2::BufferCore::allocateFrame
TimeCacheInterfacePtr allocateFrame(CompactFrameID cfid, bool is_static)
Definition: buffer_core.cpp:289
tf2::BufferCore::TransformableRequest::request_handle
TransformableRequestHandle request_handle
Definition: buffer_core.h:346
tf2::BufferCore::addTransformableCallback
TransformableCallbackHandle addTransformableCallback(const TransformableCallback &cb)
Internal use only.
Definition: buffer_core.cpp:1230
buffer_core.h
tf2::BufferCore::TransformableRequest::cb_handle
TransformableCallbackHandle cb_handle
Definition: buffer_core.h:347
tf2::BufferCore::allFramesAsStringNoLock
std::string allFramesAsStringNoLock() const
A way to see what frames have been cached Useful for debugging. Use this call internally.
Definition: buffer_core.cpp:958
tf2::BufferCore::~BufferCore
virtual ~BufferCore(void)
Definition: buffer_core.cpp:180
tf2::BufferCore::setTransform
bool setTransform(const geometry_msgs::TransformStamped &transform, const std::string &authority, bool is_static=false)
Add transform information to the tf data structure.
Definition: buffer_core.cpp:202
CONSOLE_BRIDGE_logError
#define CONSOLE_BRIDGE_logError(fmt,...)
tf2::BufferCore::getFrame
TimeCacheInterfacePtr getFrame(CompactFrameID c_frame_id) const
An accessor to get a frame, which will throw an exception if the frame is no there.
Definition: buffer_core.cpp:889
tf2::BufferCore::_addTransformsChangedListener
boost::signals2::connection _addTransformsChangedListener(boost::function< void(void)> callback)
Add a callback that happens when a new transform has arrived.
Definition: buffer_core.cpp:1355
tf2::BufferCore::MAX_GRAPH_DEPTH
static const uint32_t MAX_GRAPH_DEPTH
Maximum graph search depth (deeper graphs will be assumed to have loops)
Definition: buffer_core.h:93
Transform.h
tf2::BufferCore::transformable_requests_mutex_
boost::mutex transformable_requests_mutex_
Definition: buffer_core.h:355
tf2::BufferCore::allFramesAsYAML
std::string allFramesAsYAML() const
Definition: buffer_core.cpp:1225
tf2::BufferCore::transformable_callbacks_counter_
uint32_t transformable_callbacks_counter_
Definition: buffer_core.h:340
tf2::BufferCore::RemoveRequestByID
Definition: buffer_core.cpp:1328
tf2::BufferCore::_removeTransformsChangedListener
void _removeTransformsChangedListener(boost::signals2::connection c)
Definition: buffer_core.cpp:1361
tf2::CanTransformAccum::st
TransformStorage st
Definition: buffer_core.cpp:756
tf2::CanTransformAccum::finalize
void finalize(WalkEnding end, ros::Time _time)
Definition: buffer_core.cpp:752
tf2::BufferCore::RemoveRequestByCallback
Definition: buffer_core.cpp:1242
tf2::BufferCore::TransformableRequest::time
ros::Time time
Definition: buffer_core.h:345
tf2::BufferCore::walkToTopParent
int walkToTopParent(F &f, ros::Time time, CompactFrameID target_id, CompactFrameID source_id, std::string *error_string) const
Definition: buffer_core.cpp:311
tf2::TimeAndFrameIDFrameComparator::operator()
bool operator()(const P_TimeAndFrameID &rhs) const
Definition: buffer_core.cpp:991
tf2::TransformAccum::time
ros::Time time
Definition: buffer_core.cpp:585
tf2::TimeCache
A class to keep a sorted linked list in time This builds and maintains a list of timestamped data....
Definition: time_cache.h:92
tf2::Identity
@ Identity
Definition: buffer_core.cpp:303
tf2::CompactFrameID
uint32_t CompactFrameID
Definition: transform_storage.h:50
tf2::TransformStorage::rotation_
tf2::Quaternion rotation_
Definition: transform_storage.h:76
tf2::WalkEnding
WalkEnding
Definition: buffer_core.cpp:301
tf2::BufferCore::RemoveRequestByCallback::handle_
TransformableCallbackHandle handle_
Definition: buffer_core.cpp:1253
tf2::BufferCore::RemoveRequestByID::RemoveRequestByID
RemoveRequestByID(TransformableRequestHandle handle)
Definition: buffer_core.cpp:1330
tf2::TransformAccum::accum
void accum(bool source)
Definition: buffer_core.cpp:538
tf2::BufferCore::RemoveRequestByCallback::operator()
bool operator()(const TransformableRequest &req)
Definition: buffer_core.cpp:1248
tf2::TransformStorage
Storage for transforms and their parent.
Definition: transform_storage.h:53
tf2::TransformFailure
@ TransformFailure
Definition: buffer_core.h:67
tf2::BufferCore::allFramesAsString
std::string allFramesAsString() const
A way to see what frames have been cached Useful for debugging.
Definition: buffer_core.cpp:952
tf2::BufferCore::canTransformNoLock
bool canTransformNoLock(CompactFrameID target_id, CompactFrameID source_id, const ros::Time &time, std::string *error_msg) const
Definition: buffer_core.cpp:759
tf2::TransformAccum::st
TransformStorage st
Definition: buffer_core.cpp:584
tf2::BufferCore::frameIDs_reverse
std::vector< std::string > frameIDs_reverse
A map from CompactFrameID frame_id_numbers to string for debugging and output.
Definition: buffer_core.h:330
tf2::BufferCore::_chainAsVector
void _chainAsVector(const std::string &target_frame, ros::Time target_time, const std::string &source_frame, ros::Time source_time, const std::string &fixed_frame, std::vector< std::string > &output) const
Backwards compatabilityA way to see what frames are in a chain Useful for debugging.
Definition: buffer_core.cpp:1583
tf2::startsWithSlash
bool startsWithSlash(const std::string &frame_id)
Definition: buffer_core.cpp:104
tf2::BufferCore::transformable_callbacks_
M_TransformableCallback transformable_callbacks_
Definition: buffer_core.h:339
tf2::BufferCore::_getFrameStrings
void _getFrameStrings(std::vector< std::string > &ids) const
A way to get a std::vector of available frame ids.
Definition: buffer_core.cpp:1392
TimeBase< Time, Duration >::isZero
bool isZero() const
tf2::BufferCore::canTransform
bool canTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, std::string *error_msg=NULL) const
Test if a transform is possible.
Definition: buffer_core.cpp:803
tf2::StaticCache
Definition: time_cache.h:136
tf2::ExtrapolationException
An exception class to notify that the requested value would have required extrapolation beyond curren...
Definition: exceptions.h:79
tf2::TransformableRequestHandle
uint64_t TransformableRequestHandle
Definition: buffer_core.h:59
tf2::BufferCore::clear
void clear()
Clear all data.
Definition: buffer_core.cpp:185
tf2::BufferCore::cache_time_
ros::Duration cache_time_
How long to cache transform history.
Definition: buffer_core.h:336
tf2::BufferCore::frame_mutex_
boost::mutex frame_mutex_
A mutex to protect testing and allocating new frames on the above vector.
Definition: buffer_core.h:324
tf2::Transform
The Transform class supports rigid transforms with only translation and rotation and no scaling/shear...
Definition: Transform.h:32
tf2::SourceParentOfTarget
@ SourceParentOfTarget
Definition: buffer_core.cpp:305
tf2::BufferCore::frameIDs_
M_StringToCompactFrameID frameIDs_
Definition: buffer_core.h:328
tf2::BufferCore::_allFramesAsDot
std::string _allFramesAsDot() const
Definition: buffer_core.cpp:1578
time_cache.h
tf2::TransformStorage::translation_
tf2::Vector3 translation_
Definition: transform_storage.h:77
tf2::TransformAccum::TransformAccum
TransformAccum()
Definition: buffer_core.cpp:518
tf2::BufferCore::_frameExists
bool _frameExists(const std::string &frame_id_str) const
Check if a frame exists in the tree.
Definition: buffer_core.cpp:1368
tf2::TransformStorage::frame_id_
CompactFrameID frame_id_
Definition: transform_storage.h:79
tf2::TimeAndFrameIDFrameComparator
Definition: buffer_core.cpp:985
tf2::TransformAccum::target_to_top_vec
tf2::Vector3 target_to_top_vec
Definition: buffer_core.cpp:589
tf2::LookupException
An exception class to notify of bad frame number.
Definition: exceptions.h:70
tf2::TransformAccum::source_to_top_quat
tf2::Quaternion source_to_top_quat
Definition: buffer_core.cpp:586
tf2::FullPath
@ FullPath
Definition: buffer_core.cpp:306
tf2::BufferCore::cancelTransformableRequest
void cancelTransformableRequest(TransformableRequestHandle handle)
Internal use only.
Definition: buffer_core.cpp:1342
tf2::CanTransformAccum::accum
void accum(bool source)
Definition: buffer_core.cpp:748
tf2::CanTransformAccum::gather
CompactFrameID gather(TimeCacheInterfacePtr cache, ros::Time time, std::string *error_string)
Definition: buffer_core.cpp:743
tf2::ConnectivityException
An exception class to notify of no connection.
Definition: exceptions.h:55
tf2::BufferCore::lookupFrameString
const std::string & lookupFrameString(CompactFrameID frame_id_num) const
Number to string frame lookup may throw LookupException if number invalid.
Definition: buffer_core.cpp:929
tf2::BufferCore::validateFrameId
CompactFrameID validateFrameId(const char *function_name_arg, const std::string &frame_id) const
Definition: buffer_core.cpp:142
tf2::BufferCore::RemoveRequestByID::handle_
TransformableCallbackHandle handle_
Definition: buffer_core.cpp:1339
tf2::BufferCore::TransformableRequest
Definition: buffer_core.h:343
tf2::BufferCore::transformable_requests_
V_TransformableRequest transformable_requests_
Definition: buffer_core.h:354
tf2::BufferCore::frame_authority_
std::map< CompactFrameID, std::string > frame_authority_
A map to lookup the most recent authority for a given frame.
Definition: buffer_core.h:332
ros::TIME_MAX
const ROSTIME_DECL Time TIME_MAX
tf2::P_TimeAndFrameID
std::pair< ros::Time, CompactFrameID > P_TimeAndFrameID
Definition: buffer_core.h:57
tf2::BufferCore::frames_
V_TimeCacheInterface frames_
Definition: buffer_core.h:321
tf2::Quaternion::inverse
Quaternion inverse() const
Return the inverse of this quaternion.
Definition: Quaternion.h:259
ros::Time
tf2::TransformAccum::source_to_top_vec
tf2::Vector3 source_to_top_vec
Definition: buffer_core.cpp:587
tf2::BufferCore
A Class which provides coordinate transforms between any two frames in a system.
Definition: buffer_core.h:88
tf2::TestBufferCore::_walkToTopParent
int _walkToTopParent(BufferCore &buffer, ros::Time time, CompactFrameID target_id, CompactFrameID source_id, std::string *error_string, std::vector< CompactFrameID > *frame_chain) const
Definition: buffer_core.cpp:1656
tf2::TransformAccum
Definition: buffer_core.cpp:516
tf2::quatRotate
TF2SIMD_FORCE_INLINE Vector3 quatRotate(const Quaternion &rotation, const Vector3 &v)
Definition: Quaternion.h:438
tf2::BufferCore::createConnectivityErrorString
void createConnectivityErrorString(CompactFrameID source_frame, CompactFrameID target_frame, std::string *out) const
Definition: buffer_core.cpp:941
tf2::BufferCore::addTransformableRequest
TransformableRequestHandle addTransformableRequest(TransformableCallbackHandle handle, const std::string &target_frame, const std::string &source_frame, ros::Time time)
Internal use only.
Definition: buffer_core.cpp:1273
tf2
Definition: buffer_core.h:54
tf2::BufferCore::lookupOrInsertFrameNumber
CompactFrameID lookupOrInsertFrameNumber(const std::string &frameid_str)
String to number for frame lookup with dynamic allocation of new frames.
Definition: buffer_core.cpp:912
tf2::TransformAccum::result_vec
tf2::Vector3 result_vec
Definition: buffer_core.cpp:592
tf2::QUATERNION_NORMALIZATION_TOLERANCE
static double QUATERNION_NORMALIZATION_TOLERANCE
Definition: buffer_core.cpp:47
tf2::BufferCore::TransformableRequest::source_string
std::string source_string
Definition: buffer_core.h:351
tf2::BufferCore::BufferCore
BufferCore(ros::Duration cache_time_=ros::Duration(DEFAULT_CACHE_TIME))
Definition: buffer_core.cpp:169
tf2::Quaternion
The Quaternion implements quaternion to perform linear algebra rotations in combination with Matrix3x...
Definition: Quaternion.h:30
tf2::BufferCore::TransformableRequest::source_id
CompactFrameID source_id
Definition: buffer_core.h:349
tf2::setIdentity
void setIdentity(geometry_msgs::Transform &tx)
Definition: buffer_core.cpp:93
tf2::transformMsgToTF2
void transformMsgToTF2(const geometry_msgs::Transform &msg, tf2::Transform &tf2)
convert Transform msg to Transform
Definition: buffer_core.cpp:50
tf2::TransformAccum::result_quat
tf2::Quaternion result_quat
Definition: buffer_core.cpp:591
tf2::BufferCore::canTransformInternal
bool canTransformInternal(CompactFrameID target_id, CompactFrameID source_id, const ros::Time &time, std::string *error_msg) const
Definition: buffer_core.cpp:796
tf2::BufferCore::RemoveRequestByID::operator()
bool operator()(const TransformableRequest &req)
Definition: buffer_core.cpp:1334
tf2::BufferCore::removeTransformableCallback
void removeTransformableCallback(TransformableCallbackHandle handle)
Internal use only.
Definition: buffer_core.cpp:1256
tf2::BufferCore::RemoveRequestByCallback::RemoveRequestByCallback
RemoveRequestByCallback(TransformableCallbackHandle handle)
Definition: buffer_core.cpp:1244
tf2::CanTransformAccum
Definition: buffer_core.cpp:741
tf2::BufferCore::transformable_callbacks_mutex_
boost::mutex transformable_callbacks_mutex_
Definition: buffer_core.h:341
tf2::InvalidArgumentException
An exception class to notify that one of the arguments is invalid.
Definition: exceptions.h:90
tf2::BufferCore::lookupFrameNumber
CompactFrameID lookupFrameNumber(const std::string &frameid_str) const
String to number for frame lookup with dynamic allocation of new frames.
Definition: buffer_core.cpp:899
ros::Duration
tf2::TransformableResult
TransformableResult
Definition: buffer_core.h:64
tf2::BufferCore::_getParent
bool _getParent(const std::string &frame_id, ros::Time time, std::string &parent) const
Fill the parent of a frame.
Definition: buffer_core.cpp:1374
tf2::TransformableCallbackHandle
uint32_t TransformableCallbackHandle
Definition: buffer_core.h:58
tf2::BufferCore::TransformableRequest::target_string
std::string target_string
Definition: buffer_core.h:350
tf2::TransformAvailable
@ TransformAvailable
Definition: buffer_core.h:66
tf2::stripSlash
std::string stripSlash(const std::string &in)
Definition: buffer_core.cpp:112


tf2
Author(s): Tully Foote, Eitan Marder-Eppstein, Wim Meeussen
autogenerated on Sun Feb 4 2024 03:18:11