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


tf2
Author(s): Tully Foote, Eitan Marder-Eppstein, Wim Meeussen
autogenerated on Sun May 4 2025 02:16:30