-
Notifications
You must be signed in to change notification settings - Fork 204
/
Copy pathbuffer_core.cpp
1513 lines (1310 loc) · 46.7 KB
/
buffer_core.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
// Copyright 2010, Willow Garage, Inc. All rights reserved.
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions are met:
//
// * Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// * Redistributions in binary form must reproduce the above copyright
// notice, this list of conditions and the following disclaimer in the
// documentation and/or other materials provided with the distribution.
//
// * Neither the name of the Willow Garage nor the names of its
// contributors may be used to endorse or promote products derived from
// this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
// POSSIBILITY OF SUCH DAMAGE.
/** \author Tully Foote */
#include <algorithm>
#include <cassert>
#include <chrono>
#include <map>
#include <memory>
#include <mutex>
#include <string>
#include <utility>
#include <vector>
#include "tf2/buffer_core.h"
#include "tf2/time_cache.h"
#include "tf2/exceptions.h"
#include "console_bridge/console.h"
#include "tf2/LinearMath/Quaternion.h"
#include "tf2/LinearMath/Transform.h"
#include "tf2/LinearMath/Vector3.h"
#include "builtin_interfaces/msg/time.hpp"
#include "geometry_msgs/msg/transform.hpp"
#include "geometry_msgs/msg/transform_stamped.hpp"
namespace tf2
{
namespace
{
// Tolerance for acceptable quaternion normalization
constexpr static double QUATERNION_NORMALIZATION_TOLERANCE = 10e-3;
bool startsWithSlash(const std::string & frame_id)
{
if (frame_id.size() > 0) {
if (frame_id[0] == '/') {
return true;
}
}
return false;
}
std::string stripSlash(const std::string & in)
{
std::string out = in;
if (startsWithSlash(in)) {
out.erase(0, 1);
}
return out;
}
void fillOrWarnMessageForInvalidFrame(
const char * function_name_arg,
const std::string & frame_id,
std::string * error_msg,
const char * rationale)
{
std::string s = "Invalid frame ID \"" + frame_id +
"\" passed to " + function_name_arg + " - " + rationale;
if (error_msg != nullptr) {
*error_msg = s;
} else {
CONSOLE_BRIDGE_logWarn("%s", s.c_str());
}
}
} // anonymous namespace
CompactFrameID BufferCore::validateFrameId(
const char * function_name_arg,
const std::string & frame_id,
std::string * error_msg) const
{
if (frame_id.empty()) {
fillOrWarnMessageForInvalidFrame(
function_name_arg, frame_id, error_msg, "in tf2 frame_ids cannot be empty");
return 0;
}
if (startsWithSlash(frame_id)) {
fillOrWarnMessageForInvalidFrame(
function_name_arg, frame_id, error_msg, "in tf2 frame_ids cannot start with a '/'");
return 0;
}
CompactFrameID id = lookupFrameNumber(frame_id);
if (id == 0) {
fillOrWarnMessageForInvalidFrame(
function_name_arg, frame_id, error_msg, "frame does not exist");
}
return id;
}
CompactFrameID BufferCore::validateFrameId(
const char * function_name_arg,
const std::string & frame_id) const
{
if (frame_id.empty()) {
std::string error_msg = "Invalid argument \"" + frame_id + "\" passed to " + function_name_arg +
" - in tf2 frame_ids cannot be empty";
throw tf2::InvalidArgumentException(error_msg.c_str());
}
if (startsWithSlash(frame_id)) {
std::string error_msg = "Invalid argument \"" + frame_id + "\" passed to " + function_name_arg +
" - in tf2 frame_ids cannot start with a '/'";
throw tf2::InvalidArgumentException(error_msg.c_str());
}
CompactFrameID id = lookupFrameNumber(frame_id);
if (id == 0) {
std::string error_msg = "\"" + frame_id + "\" passed to " + function_name_arg +
" does not exist. ";
throw tf2::LookupException(error_msg.c_str());
}
return id;
}
BufferCore::BufferCore(tf2::Duration cache_time)
: cache_time_(cache_time),
transformable_callbacks_counter_(0),
transformable_requests_counter_(0),
using_dedicated_thread_(false)
{
frameIDs_["NO_PARENT"] = 0;
frames_.push_back(TimeCacheInterfacePtr());
frameIDs_reverse_.push_back("NO_PARENT");
}
BufferCore::~BufferCore() {}
void BufferCore::clear()
{
std::unique_lock<std::mutex> lock(frame_mutex_);
if (frames_.size() > 1) {
for (std::vector<TimeCacheInterfacePtr>::iterator cache_it = frames_.begin() + 1;
cache_it != frames_.end(); ++cache_it)
{
if (*cache_it) {
(*cache_it)->clearList();
}
}
}
}
bool BufferCore::setTransform(
const geometry_msgs::msg::TransformStamped & transform,
const std::string & authority, bool is_static)
{
tf2::Transform tf2_transform(tf2::Quaternion(
transform.transform.rotation.x,
transform.transform.rotation.y,
transform.transform.rotation.z,
transform.transform.rotation.w),
tf2::Vector3(
transform.transform.translation.x,
transform.transform.translation.y,
transform.transform.translation.z));
TimePoint time_point(std::chrono::nanoseconds(transform.header.stamp.nanosec) +
std::chrono::duration_cast<std::chrono::nanoseconds>(
std::chrono::seconds(
transform.header.stamp.sec)));
return setTransformImpl(
tf2_transform, transform.header.frame_id, transform.child_frame_id,
time_point, authority, is_static);
}
bool BufferCore::setTransformImpl(
const tf2::Transform & transform_in, const std::string frame_id,
const std::string child_frame_id, const TimePoint stamp,
const std::string & authority, bool is_static)
{
std::string stripped_frame_id = stripSlash(frame_id);
std::string stripped_child_frame_id = stripSlash(child_frame_id);
bool error_exists = false;
if (stripped_child_frame_id == stripped_frame_id) {
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());
error_exists = true;
}
if (stripped_child_frame_id.empty()) {
CONSOLE_BRIDGE_logError(
"TF_NO_CHILD_FRAME_ID: Ignoring transform from authority \"%s\" because child_frame_id not"
" set ", authority.c_str());
error_exists = true;
}
if (stripped_frame_id.empty()) {
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());
error_exists = true;
}
if (std::isnan(transform_in.getOrigin().x()) || std::isnan(transform_in.getOrigin().y()) ||
std::isnan(transform_in.getOrigin().z()) ||
std::isnan(transform_in.getRotation().x()) || std::isnan(transform_in.getRotation().y()) ||
std::isnan(transform_in.getRotation().z()) || std::isnan(transform_in.getRotation().w()))
{
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)",
stripped_child_frame_id.c_str(), authority.c_str(),
transform_in.getOrigin().x(), transform_in.getOrigin().y(), transform_in.getOrigin().z(),
transform_in.getRotation().x(), transform_in.getRotation().y(),
transform_in.getRotation().z(), transform_in.getRotation().w()
);
error_exists = true;
}
bool valid = std::abs(
(transform_in.getRotation().w() * transform_in.getRotation().w() +
transform_in.getRotation().x() * transform_in.getRotation().x() +
transform_in.getRotation().y() * transform_in.getRotation().y() +
transform_in.getRotation().z() * transform_in.getRotation().z()) - 1.0f) <
QUATERNION_NORMALIZATION_TOLERANCE;
if (!valid) {
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)",
stripped_child_frame_id.c_str(), authority.c_str(),
transform_in.getRotation().x(), transform_in.getRotation().y(),
transform_in.getRotation().z(), transform_in.getRotation().w());
error_exists = true;
}
if (error_exists) {
return false;
}
{
std::unique_lock<std::mutex> lock(frame_mutex_);
CompactFrameID frame_number = lookupOrInsertFrameNumber(stripped_child_frame_id);
TimeCacheInterfacePtr frame = getFrame(frame_number);
if (frame == nullptr) {
frame = allocateFrame(frame_number, is_static);
} else {
// Overwrite TimeCacheInterface type with a current input
const TimeCache * time_cache_ptr = dynamic_cast<TimeCache *>(frame.get());
const StaticCache * static_cache_ptr = dynamic_cast<StaticCache *>(frame.get());
if (time_cache_ptr && is_static) {
frame = allocateFrame(frame_number, is_static);
} else if (static_cache_ptr && !is_static) {
frame = allocateFrame(frame_number, is_static);
}
}
if (frame->insertData(
TransformStorage(
stamp, transform_in.getRotation(),
transform_in.getOrigin(), lookupOrInsertFrameNumber(stripped_frame_id), frame_number)))
{
frame_authority_[frame_number] = authority;
} else {
std::string stamp_str = displayTimePoint(stamp);
CONSOLE_BRIDGE_logWarn(
"TF_OLD_DATA ignoring data from the past for frame %s at time %s according to authority"
" %s\nPossible reasons are listed at http://wiki.ros.org/tf/Errors%%20explained",
stripped_child_frame_id.c_str(), stamp_str.c_str(), authority.c_str());
return false;
}
}
testTransformableRequests();
return true;
}
// This method expects that the caller is holding frame_mutex_
TimeCacheInterfacePtr BufferCore::allocateFrame(CompactFrameID cfid, bool is_static)
{
if (is_static) {
frames_[cfid] = std::make_shared<StaticCache>();
} else {
frames_[cfid] = std::make_shared<TimeCache>(cache_time_);
}
return frames_[cfid];
}
enum WalkEnding
{
Identity,
TargetParentOfSource,
SourceParentOfTarget,
FullPath,
};
template<typename F>
tf2::TF2Error BufferCore::walkToTopParent(
F & f, TimePoint time, CompactFrameID target_id,
CompactFrameID source_id, std::string * error_string, std::vector<CompactFrameID>
* frame_chain) const
{
if (frame_chain) {
frame_chain->clear();
}
// Short circuit if zero length transform to allow lookups on non existant links
if (source_id == target_id) {
f.finalize(Identity, time);
return tf2::TF2Error::TF2_NO_ERROR;
}
// If getting the latest get the latest common time
if (time == TimePointZero) {
tf2::TF2Error retval = getLatestCommonTime(target_id, source_id, time, error_string);
if (retval != tf2::TF2Error::TF2_NO_ERROR) {
return retval;
}
}
// Walk the tree to its root from the source frame, accumulating the transform
CompactFrameID frame = source_id;
CompactFrameID top_parent = frame;
uint32_t depth = 0;
std::string extrapolation_error_string;
bool extrapolation_might_have_occurred = false;
while (frame != 0) {
TimeCacheInterfacePtr cache = getFrame(frame);
if (frame_chain) {
frame_chain->push_back(frame);
}
if (!cache) {
// There will be no cache for the very root of the tree
top_parent = frame;
break;
}
CompactFrameID parent = f.gather(cache, time, &extrapolation_error_string);
if (parent == 0) {
// Just break out here... there may still be a path from source -> target
top_parent = frame;
extrapolation_might_have_occurred = true;
break;
}
// Early out... target frame is a direct parent of the source frame
if (frame == target_id) {
f.finalize(TargetParentOfSource, time);
return tf2::TF2Error::TF2_NO_ERROR;
}
f.accum(true);
top_parent = frame;
frame = parent;
++depth;
if (depth > MAX_GRAPH_DEPTH) {
if (error_string) {
std::stringstream ss;
ss << "The tf tree is invalid because it contains a loop." << std::endl <<
allFramesAsStringNoLock() << std::endl;
*error_string = ss.str();
}
return tf2::TF2Error::TF2_LOOKUP_ERROR;
}
}
// Now walk to the top parent from the target frame, accumulating its transform
frame = target_id;
depth = 0;
std::vector<CompactFrameID> reverse_frame_chain;
while (frame != top_parent) {
TimeCacheInterfacePtr cache = getFrame(frame);
if (frame_chain) {
reverse_frame_chain.push_back(frame);
}
if (!cache) {
break;
}
CompactFrameID parent = f.gather(cache, time, error_string);
if (parent == 0) {
if (error_string) {
std::stringstream ss;
ss << *error_string << ", when looking up transform from frame [" << lookupFrameString(
source_id) << "] to frame [" << lookupFrameString(target_id) << "]";
*error_string = ss.str();
}
return tf2::TF2Error::TF2_EXTRAPOLATION_ERROR;
}
// Early out... source frame is a direct parent of the target frame
if (frame == source_id) {
f.finalize(SourceParentOfTarget, time);
if (frame_chain) {
frame_chain->swap(reverse_frame_chain);
}
return tf2::TF2Error::TF2_NO_ERROR;
}
f.accum(false);
frame = parent;
++depth;
if (depth > MAX_GRAPH_DEPTH) {
if (error_string) {
std::stringstream ss;
ss << "The tf tree is invalid because it contains a loop." << std::endl <<
allFramesAsStringNoLock() << std::endl;
*error_string = ss.str();
}
return tf2::TF2Error::TF2_LOOKUP_ERROR;
}
}
if (frame != top_parent) {
if (extrapolation_might_have_occurred) {
if (error_string) {
std::stringstream ss;
ss << extrapolation_error_string << ", when looking up transform from frame [" <<
lookupFrameString(source_id) << "] to frame [" << lookupFrameString(target_id) << "]";
*error_string = ss.str();
}
return tf2::TF2Error::TF2_EXTRAPOLATION_ERROR;
}
createConnectivityErrorString(source_id, target_id, error_string);
return tf2::TF2Error::TF2_CONNECTIVITY_ERROR;
}
f.finalize(FullPath, time);
if (frame_chain) {
// Pruning: Compare the chains starting at the parent (end) until they differ
size_t m = reverse_frame_chain.size();
size_t n = frame_chain->size();
while (m > 0u && n > 0u) {
--m;
--n;
if ((*frame_chain)[n] != reverse_frame_chain[m]) {
break;
}
}
// Erase all duplicate items from frame_chain
if (n > 0u) {
frame_chain->erase(frame_chain->begin() + (n - 1u), frame_chain->end());
}
if (m < reverse_frame_chain.size()) {
size_t i = m + 1uL;
while (i > 0u) {
--i;
frame_chain->push_back(reverse_frame_chain[i]);
}
}
}
return tf2::TF2Error::TF2_NO_ERROR;
}
struct TransformAccum
{
TransformAccum()
: source_to_top_quat(0.0, 0.0, 0.0, 1.0),
source_to_top_vec(0.0, 0.0, 0.0),
target_to_top_quat(0.0, 0.0, 0.0, 1.0),
target_to_top_vec(0.0, 0.0, 0.0),
result_quat(0.0, 0.0, 0.0, 1.0),
result_vec(0.0, 0.0, 0.0)
{
}
CompactFrameID gather(TimeCacheInterfacePtr cache, TimePoint time, std::string * error_string)
{
if (!cache->getData(time, st, error_string)) {
return 0;
}
return st.frame_id_;
}
void accum(bool source)
{
if (source) {
source_to_top_vec = quatRotate(st.rotation_, source_to_top_vec) + st.translation_;
source_to_top_quat = st.rotation_ * source_to_top_quat;
} else {
target_to_top_vec = quatRotate(st.rotation_, target_to_top_vec) + st.translation_;
target_to_top_quat = st.rotation_ * target_to_top_quat;
}
}
void finalize(WalkEnding end, TimePoint _time)
{
switch (end) {
case Identity:
break;
case TargetParentOfSource:
result_vec = source_to_top_vec;
result_quat = source_to_top_quat;
break;
case SourceParentOfTarget:
{
tf2::Quaternion inv_target_quat = target_to_top_quat.inverse();
tf2::Vector3 inv_target_vec = quatRotate(inv_target_quat, -target_to_top_vec);
result_vec = inv_target_vec;
result_quat = inv_target_quat;
break;
}
case FullPath:
{
tf2::Quaternion inv_target_quat = target_to_top_quat.inverse();
tf2::Vector3 inv_target_vec = quatRotate(inv_target_quat, -target_to_top_vec);
result_vec = quatRotate(inv_target_quat, source_to_top_vec) + inv_target_vec;
result_quat = inv_target_quat * source_to_top_quat;
}
break;
}
time = _time;
}
TransformStorage st;
TimePoint time;
tf2::Quaternion source_to_top_quat;
tf2::Vector3 source_to_top_vec;
tf2::Quaternion target_to_top_quat;
tf2::Vector3 target_to_top_vec;
tf2::Quaternion result_quat;
tf2::Vector3 result_vec;
};
geometry_msgs::msg::TransformStamped
BufferCore::lookupTransform(
const std::string & target_frame, const std::string & source_frame,
const TimePoint & time) const
{
tf2::Transform transform;
TimePoint time_out;
lookupTransformImpl(target_frame, source_frame, time, transform, time_out);
geometry_msgs::msg::TransformStamped msg;
msg.transform.translation.x = transform.getOrigin().x();
msg.transform.translation.y = transform.getOrigin().y();
msg.transform.translation.z = transform.getOrigin().z();
msg.transform.rotation.x = transform.getRotation().x();
msg.transform.rotation.y = transform.getRotation().y();
msg.transform.rotation.z = transform.getRotation().z();
msg.transform.rotation.w = transform.getRotation().w();
std::chrono::nanoseconds ns = std::chrono::duration_cast<std::chrono::nanoseconds>(
time_out.time_since_epoch());
std::chrono::seconds s = std::chrono::duration_cast<std::chrono::seconds>(
time_out.time_since_epoch());
msg.header.stamp.sec = static_cast<int32_t>(s.count());
msg.header.stamp.nanosec = static_cast<uint32_t>(ns.count() % 1000000000ull);
msg.header.frame_id = target_frame;
msg.child_frame_id = source_frame;
return msg;
}
geometry_msgs::msg::TransformStamped
BufferCore::lookupTransform(
const std::string & target_frame, const TimePoint & target_time,
const std::string & source_frame, const TimePoint & source_time,
const std::string & fixed_frame) const
{
tf2::Transform transform;
TimePoint time_out;
lookupTransformImpl(
target_frame, target_time, source_frame, source_time,
fixed_frame, transform, time_out);
geometry_msgs::msg::TransformStamped msg;
msg.transform.translation.x = transform.getOrigin().x();
msg.transform.translation.y = transform.getOrigin().y();
msg.transform.translation.z = transform.getOrigin().z();
msg.transform.rotation.x = transform.getRotation().x();
msg.transform.rotation.y = transform.getRotation().y();
msg.transform.rotation.z = transform.getRotation().z();
msg.transform.rotation.w = transform.getRotation().w();
std::chrono::nanoseconds ns = std::chrono::duration_cast<std::chrono::nanoseconds>(
time_out.time_since_epoch());
std::chrono::seconds s = std::chrono::duration_cast<std::chrono::seconds>(
time_out.time_since_epoch());
msg.header.stamp.sec = static_cast<int32_t>(s.count());
msg.header.stamp.nanosec = static_cast<uint32_t>(ns.count() % 1000000000ull);
msg.header.frame_id = target_frame;
msg.child_frame_id = source_frame;
return msg;
}
void BufferCore::lookupTransformImpl(
const std::string & target_frame,
const std::string & source_frame,
const TimePoint & time, tf2::Transform & transform,
TimePoint & time_out) const
{
std::unique_lock<std::mutex> lock(frame_mutex_);
if (target_frame == source_frame) {
transform.setIdentity();
if (time == TimePointZero) {
CompactFrameID target_id = lookupFrameNumber(target_frame);
TimeCacheInterfacePtr cache = getFrame(target_id);
if (cache) {
time_out = cache->getLatestTimestamp();
} else {
time_out = time;
}
} else {
time_out = time;
}
return;
}
// Identity case does not need to be validated
CompactFrameID target_id = validateFrameId("lookupTransform argument target_frame", target_frame);
CompactFrameID source_id = validateFrameId("lookupTransform argument source_frame", source_frame);
std::string error_string;
TransformAccum accum;
tf2::TF2Error retval = walkToTopParent(accum, time, target_id, source_id, &error_string, nullptr);
if (retval != tf2::TF2Error::TF2_NO_ERROR) {
switch (retval) {
case tf2::TF2Error::TF2_CONNECTIVITY_ERROR:
throw ConnectivityException(error_string);
case tf2::TF2Error::TF2_EXTRAPOLATION_ERROR:
throw ExtrapolationException(error_string);
case tf2::TF2Error::TF2_LOOKUP_ERROR:
throw LookupException(error_string);
default:
CONSOLE_BRIDGE_logError("Unknown error code: %d", retval);
assert(0);
}
}
time_out = accum.time;
transform.setOrigin(accum.result_vec);
transform.setRotation(accum.result_quat);
}
void BufferCore::lookupTransformImpl(
const std::string & target_frame,
const TimePoint & target_time,
const std::string & source_frame,
const TimePoint & source_time,
const std::string & fixed_frame, tf2::Transform & transform,
TimePoint & time_out) const
{
validateFrameId("lookupTransform argument target_frame", target_frame);
validateFrameId("lookupTransform argument source_frame", source_frame);
validateFrameId("lookupTransform argument fixed_frame", fixed_frame);
tf2::Transform tf1, tf2;
lookupTransformImpl(fixed_frame, source_frame, source_time, tf1, time_out);
lookupTransformImpl(target_frame, fixed_frame, target_time, tf2, time_out);
transform = tf2 * tf1;
}
struct CanTransformAccum
{
CompactFrameID gather(TimeCacheInterfacePtr cache, TimePoint time, std::string * error_string)
{
return cache->getParent(time, error_string);
}
void accum(bool source)
{
(void)source;
}
void finalize(WalkEnding end, TimePoint _time)
{
(void)end;
(void)_time;
}
TransformStorage st;
};
bool BufferCore::canTransformInternal(
CompactFrameID target_id, CompactFrameID source_id,
const TimePoint & time, std::string * error_msg) const
{
std::unique_lock<std::mutex> lock(frame_mutex_);
if (target_id == 0 || source_id == 0) {
if (error_msg) {
*error_msg = "Source or target frame is not yet defined";
}
return false;
}
if (target_id == source_id) {
return true;
}
CanTransformAccum accum;
if (walkToTopParent(
accum, time, target_id, source_id,
error_msg, nullptr) == tf2::TF2Error::TF2_NO_ERROR)
{
return true;
}
return false;
}
bool BufferCore::canTransform(
const std::string & target_frame, const std::string & source_frame,
const TimePoint & time, std::string * error_msg) const
{
// Short circuit if target_frame == source_frame
if (target_frame == source_frame) {
return true;
}
CompactFrameID target_id = validateFrameId(
"canTransform argument target_frame", target_frame, error_msg);
if (target_id == 0) {
return false;
}
CompactFrameID source_id = validateFrameId(
"canTransform argument source_frame", source_frame, error_msg);
if (source_id == 0) {
return false;
}
return canTransformInternal(target_id, source_id, time, error_msg);
}
bool BufferCore::canTransform(
const std::string & target_frame, const TimePoint & target_time,
const std::string & source_frame, const TimePoint & source_time,
const std::string & fixed_frame, std::string * error_msg) const
{
CompactFrameID target_id = validateFrameId(
"canTransform argument target_frame", target_frame, error_msg);
if (target_id == 0) {
return false;
}
CompactFrameID source_id = validateFrameId(
"canTransform argument source_frame", source_frame, error_msg);
if (source_id == 0) {
return false;
}
CompactFrameID fixed_id = validateFrameId(
"canTransform argument fixed_frame", fixed_frame, error_msg);
if (fixed_id == 0) {
return false;
}
return
canTransformInternal(target_id, fixed_id, target_time, error_msg) &&
canTransformInternal(fixed_id, source_id, source_time, error_msg);
}
tf2::TimeCacheInterfacePtr BufferCore::getFrame(CompactFrameID frame_id) const
{
if (frame_id >= frames_.size()) {
return TimeCacheInterfacePtr();
} else {
return frames_[frame_id];
}
}
CompactFrameID BufferCore::lookupFrameNumber(const std::string & frameid_str) const
{
CompactFrameID retval;
M_StringToCompactFrameID::const_iterator map_it = frameIDs_.find(frameid_str);
if (map_it == frameIDs_.end()) {
retval = CompactFrameID(0);
} else {
retval = map_it->second;
}
return retval;
}
CompactFrameID BufferCore::lookupOrInsertFrameNumber(const std::string & frameid_str)
{
CompactFrameID retval = 0;
M_StringToCompactFrameID::iterator map_it = frameIDs_.find(frameid_str);
if (map_it == frameIDs_.end()) {
retval = CompactFrameID(frames_.size());
// Just a place holder for iteration
frames_.push_back(TimeCacheInterfacePtr());
frameIDs_[frameid_str] = retval;
frameIDs_reverse_.push_back(frameid_str);
} else {
retval = frameIDs_[frameid_str];
}
return retval;
}
const std::string & BufferCore::lookupFrameString(CompactFrameID frame_id_num) const
{
if (frame_id_num >= frameIDs_reverse_.size()) {
std::stringstream ss;
ss << "Reverse lookup of frame id " << frame_id_num << " failed!";
throw tf2::LookupException(ss.str());
} else {
return frameIDs_reverse_[frame_id_num];
}
}
void BufferCore::createConnectivityErrorString(
CompactFrameID source_frame,
CompactFrameID target_frame, std::string * out) const
{
if (!out) {
return;
}
*out = std::string(
"Could not find a connection between '" + lookupFrameString(target_frame) + "' and '" +
lookupFrameString(source_frame) + "' because they are not part of the same tree." +
"Tf has two or more unconnected trees.");
}
std::vector<std::string> BufferCore::getAllFrameNames() const
{
std::vector<std::string> frames;
_getFrameStrings(frames);
return frames;
}
std::string BufferCore::allFramesAsString() const
{
std::unique_lock<std::mutex> lock(frame_mutex_);
return this->allFramesAsStringNoLock();
}
std::string BufferCore::allFramesAsStringNoLock() const
{
std::stringstream mstream;
TransformStorage temp;
// regular transforms
for (size_t counter = 1; counter < frames_.size(); counter++) {
TimeCacheInterfacePtr frame_ptr = getFrame(static_cast<CompactFrameID>(counter));
if (frame_ptr == nullptr) {
continue;
}
CompactFrameID frame_id_num;
if (frame_ptr->getData(TimePointZero, temp)) {
frame_id_num = temp.frame_id_;
} else {
frame_id_num = 0;
}
mstream << "Frame " << frameIDs_reverse_[counter] << " exists with parent " <<
frameIDs_reverse_[frame_id_num] << "." << std::endl;
}
return mstream.str();
}
struct TimeAndFrameIDFrameComparator
{
explicit TimeAndFrameIDFrameComparator(CompactFrameID id)
: id(id)
{}
bool operator()(const P_TimeAndFrameID & rhs) const
{
return rhs.second == id;
}
CompactFrameID id;
};
tf2::TF2Error BufferCore::getLatestCommonTime(
CompactFrameID target_id, CompactFrameID source_id,
TimePoint & time, std::string * error_string) const
{
// Error if one of the frames don't exist.
if (source_id == 0 || target_id == 0) {return tf2::TF2Error::TF2_LOOKUP_ERROR;}
if (source_id == target_id) {
TimeCacheInterfacePtr cache = getFrame(source_id);
// Set time to latest timestamp of frameid in case of target and source frame id are the same
if (cache) {
time = cache->getLatestTimestamp();
} else {
time = TimePointZero;
}
return tf2::TF2Error::TF2_NO_ERROR;
}
std::vector<P_TimeAndFrameID> lct_cache;
// Walk the tree to its root from the source frame, accumulating the list of parent/time as
// well as the latest time in the target is a direct parent
CompactFrameID frame = source_id;
uint32_t depth = 0;
TimePoint common_time = TimePoint::max();
while (frame != 0) {
TimeCacheInterfacePtr cache = getFrame(frame);
if (!cache) {
// There will be no cache for the very root of the tree
break;
}
P_TimeAndFrameID latest = cache->getLatestTimeAndParent();
if (latest.second == 0) {
// Just break out here... there may still be a path from source -> target
break;
}
if (latest.first != TimePointZero) {
common_time = std::min(latest.first, common_time);
}
lct_cache.push_back(latest);
frame = latest.second;
// Early out... target frame is a direct parent of the source frame
if (frame == target_id) {
time = common_time;
if (time == TimePoint::max()) {
time = TimePointZero;
}
return tf2::TF2Error::TF2_NO_ERROR;
}
++depth;
if (depth > MAX_GRAPH_DEPTH) {
if (error_string) {
std::stringstream ss;
ss << "The tf tree is invalid because it contains a loop." << std::endl <<
allFramesAsStringNoLock() << std::endl;
*error_string = ss.str();
}
return tf2::TF2Error::TF2_LOOKUP_ERROR;
}
}
// Now walk to the top parent from the target frame, accumulating the latest time and looking
// for a common parent
frame = target_id;
depth = 0;
common_time = TimePoint::max();
CompactFrameID common_parent = 0;
while (true) {
TimeCacheInterfacePtr cache = getFrame(frame);
if (!cache) {
break;
}
P_TimeAndFrameID latest = cache->getLatestTimeAndParent();
if (latest.second == 0) {
break;
}
if (latest.first != TimePointZero) {
common_time = std::min(latest.first, common_time);
}