-
Notifications
You must be signed in to change notification settings - Fork 207
/
Copy pathbuffer_core.h
528 lines (454 loc) · 20.8 KB
/
buffer_core.h
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
// Copyright 2008, 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 {copyright_holder} 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 */
#ifndef TF2__BUFFER_CORE_H_
#define TF2__BUFFER_CORE_H_
#include <algorithm>
#include <chrono>
#include <cmath>
#include <functional>
#include <map>
#include <memory>
#include <mutex>
#include <string>
#include <unordered_map>
#include <utility>
#include <vector>
#include "LinearMath/Transform.h"
#include "geometry_msgs/msg/transform_stamped.hpp"
#include "geometry_msgs/msg/velocity_stamped.hpp"
#include "rcutils/logging_macros.h"
#include "tf2/buffer_core_interface.h"
#include "tf2/exceptions.h"
#include "tf2/transform_storage.h"
#include "tf2/visibility_control.h"
namespace tf2
{
typedef std::pair<TimePoint, CompactFrameID> P_TimeAndFrameID;
typedef uint64_t TransformableRequestHandle;
class TimeCacheInterface;
using TimeCacheInterfacePtr = std::shared_ptr<TimeCacheInterface>;
enum TransformableResult
{
TransformAvailable,
TransformFailure,
};
//!< The default amount of time to cache data in seconds
static constexpr Duration BUFFER_CORE_DEFAULT_CACHE_TIME = std::chrono::seconds(10);
/** \brief A Class which provides coordinate transforms between any two frames in a system.
*
* This class provides a simple interface to allow recording and lookup of
* relationships between arbitrary frames of the system.
*
* libTF assumes that there is a tree of coordinate frame transforms which define the relationship between all coordinate frames.
* For example your typical robot would have a transform from global to real world. And then from base to hand, and from base to head.
* But Base to Hand really is composed of base to shoulder to elbow to wrist to hand.
* libTF is designed to take care of all the intermediate steps for you.
*
* Internal Representation
* libTF will store frames with the parameters necessary for generating the transform into that frame from it's parent and a reference to the parent frame.
* Frames are designated using an std::string
* 0 is a frame without a parent (the top of a tree)
* The positions of frames over time must be pushed in.
*
* All function calls which pass frame ids can potentially throw the exception tf::LookupException
*/
class BufferCore : public BufferCoreInterface
{
public:
/************* Constants ***********************/
//!< Maximum graph search depth (deeper graphs will be assumed to have loops)
TF2_PUBLIC
static const uint32_t MAX_GRAPH_DEPTH = 1000UL;
/** Constructor
* \param cache_time How long to keep a history of transforms in nanoseconds
*
*/
TF2_PUBLIC
explicit BufferCore(tf2::Duration cache_time = BUFFER_CORE_DEFAULT_CACHE_TIME);
TF2_PUBLIC
virtual ~BufferCore(void);
/** \brief Clear all data */
TF2_PUBLIC
void clear() override;
/** \brief Add transform information to the tf data structure
* \param transform The transform to store
* \param authority The source of the information for this transform
* \param is_static Record this transform as a static transform. It will be good across all time. (This cannot be changed after the first call.)
* \return True unless an error occured
*/
TF2_PUBLIC
bool setTransform(
const geometry_msgs::msg::TransformStamped & transform,
const std::string & authority, bool is_static = false);
/*********** Accessors *************/
/**
* \brief Get the transform between two frames by frame ID.
* \param target_frame The frame to which data should be transformed.
* \param source_frame The frame where the data originated.
* \param time The time at which the value of the transform is desired (0 will get the latest).
* \return The transform between the frames.
*
* Possible exceptions tf2::LookupException, tf2::ConnectivityException,
* tf2::ExtrapolationException, tf2::InvalidArgumentException
*/
TF2_PUBLIC
virtual tf2::Stamped<tf2::Transform>
lookupTransformTf2(
const std::string & target_frame,
const std::string & source_frame,
const tf2::TimePoint & time) const override;
/** \brief Get the transform between two frames by frame ID.
* \param target_frame The frame to which data should be transformed
* \param source_frame The frame where the data originated
* \param time The time at which the value of the transform is desired. (0 will get the latest)
* \return The transform between the frames as a ROS type.
*
* Possible exceptions tf2::LookupException, tf2::ConnectivityException,
* tf2::ExtrapolationException, tf2::InvalidArgumentException
*/
TF2_PUBLIC
geometry_msgs::msg::TransformStamped
lookupTransform(
const std::string & target_frame, const std::string & source_frame,
const TimePoint & time) const override;
/**
* \brief Get the transform between two frames by frame ID assuming fixed frame.
* \param target_frame The frame to which data should be transformed.
* \param target_time The time to which the data should be transformed (0 will get the latest).
* \param source_frame The frame where the data originated.
* \param source_time The time at which the source_frame should be evaluated
* (0 will get the latest).
* \param fixed_frame The frame in which to assume the transform is constant in time.
* \return The transform between the frames.
*
* Possible exceptions tf2::LookupException, tf2::ConnectivityException,
* tf2::ExtrapolationException, tf2::InvalidArgumentException
*/
TF2_PUBLIC
virtual tf2::Stamped<tf2::Transform>
lookupTransformTf2(
const std::string & target_frame,
const tf2::TimePoint & target_time,
const std::string & source_frame,
const tf2::TimePoint & source_time,
const std::string & fixed_frame) const override;
/** \brief Get the transform between two frames by frame ID assuming fixed frame.
* \param target_frame The frame to which data should be transformed
* \param target_time The time to which the data should be transformed. (0 will get the latest)
* \param source_frame The frame where the data originated
* \param source_time The time at which the source_frame should be evaluated. (0 will get the latest)
* \param fixed_frame The frame in which to assume the transform is constant in time.
* \return The transform between the frames as a ROS type.
*
* Possible exceptions tf2::LookupException, tf2::ConnectivityException,
* tf2::ExtrapolationException, tf2::InvalidArgumentException
*/
TF2_PUBLIC
geometry_msgs::msg::TransformStamped
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 override;
TF2_PUBLIC
tf2::Stamped<std::pair<tf2::Vector3, tf2::Vector3>> lookupVelocityTf2(
const std::string & tracking_frame, const std::string & observation_frame,
const TimePoint & time, const tf2::Duration & averaging_interval) const;
TF2_PUBLIC
geometry_msgs::msg::VelocityStamped lookupVelocity(
const std::string & tracking_frame, const std::string & observation_frame,
const TimePoint & time, const tf2::Duration & averaging_interval) const;
/** \brief Lookup the velocity of the moving_frame in the reference_frame
* \param reference_frame The frame in which to track
* \param moving_frame The frame to track
* \param time The time at which to get the velocity
* \param duration The period over which to average
* \param velocity The velocity output
*
* Possible exceptions TransformReference::LookupException, TransformReference::ConnectivityException,
* TransformReference::MaxDepthException
*/
TF2_PUBLIC
tf2::Stamped<std::pair<tf2::Vector3, tf2::Vector3>> lookupVelocityTf2(
const std::string & tracking_frame, const std::string & observation_frame,
const std::string & reference_frame, const tf2::Vector3 & reference_point,
const std::string & reference_point_frame,
const TimePoint & time, const tf2::Duration & duration) const;
/** \brief Lookup the velocity of the moving_frame in the reference_frame
* \param reference_frame The frame in which to track
* \param moving_frame The frame to track
* \param time The time at which to get the velocity
* \param duration The period over which to average
* \param velocity The velocity output
*
* Possible exceptions TransformReference::LookupException, TransformReference::ConnectivityException,
* TransformReference::MaxDepthException
*/
TF2_PUBLIC
geometry_msgs::msg::VelocityStamped lookupVelocity(
const std::string & tracking_frame, const std::string & observation_frame,
const std::string & reference_frame, const tf2::Vector3 & reference_point,
const std::string & reference_point_frame,
const TimePoint & time, const tf2::Duration & duration) const;
/** \brief Test if a transform is possible
* \param target_frame The frame into which to transform
* \param source_frame The frame from which to transform
* \param time The time at which to transform
* \param error_msg A pointer to a string which will be filled with why the transform failed, if not nullptr
* \return True if the transform is possible, false otherwise
*/
TF2_PUBLIC
bool canTransform(
const std::string & target_frame, const std::string & source_frame,
const TimePoint & time, std::string * error_msg = nullptr) const override;
/** \brief Test if a transform is possible
* \param target_frame The frame into which to transform
* \param target_time The time into which to transform
* \param source_frame The frame from which to transform
* \param source_time The time from which to transform
* \param fixed_frame The frame in which to treat the transform as constant in time
* \param error_msg A pointer to a string which will be filled with why the transform failed, if not nullptr
* \return True if the transform is possible, false otherwise
*/
TF2_PUBLIC
bool 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 = nullptr) const override;
/** \brief Get all frames that exist in the system.
*/
TF2_PUBLIC
std::vector<std::string> getAllFrameNames() const override;
/** \brief A way to see what frames have been cached in yaml format
* Useful for debugging tools
*/
TF2_PUBLIC
std::string allFramesAsYAML(TimePoint current_time) const;
/** Backwards compatibility for #84
*/
TF2_PUBLIC
std::string allFramesAsYAML() const;
/** \brief A way to see what frames have been cached
* Useful for debugging
*/
TF2_PUBLIC
std::string allFramesAsString() const;
using TransformableCallback = std::function<
void (TransformableRequestHandle request_handle, const std::string & target_frame,
const std::string & source_frame,
TimePoint time, TransformableResult result)>;
/// \brief Internal use only
TF2_PUBLIC
TransformableRequestHandle addTransformableRequest(
const TransformableCallback & cb,
const std::string & target_frame,
const std::string & source_frame,
TimePoint time);
/// \brief Internal use only
TF2_PUBLIC
void cancelTransformableRequest(TransformableRequestHandle handle);
// Tell the buffer that there are multiple threads servicing it.
// This is useful for derived classes to know if they can block or not.
TF2_PUBLIC
void setUsingDedicatedThread(bool value) {using_dedicated_thread_ = value;}
// Get the state of using_dedicated_thread_
TF2_PUBLIC
bool isUsingDedicatedThread() const {return using_dedicated_thread_;}
/* Backwards compatability section for tf::Transformer you should not use these
*/
/**@brief Check if a frame exists in the tree
* @param frame_id_str The frame id in question */
TF2_PUBLIC
bool _frameExists(const std::string & frame_id_str) const;
/**@brief Fill the parent of a frame.
* @param frame_id The frame id of the frame in question
* @param time The timepoint of the frame in question
* @param parent The reference to the string to fill the parent
* Returns true unless "NO_PARENT" */
TF2_PUBLIC
bool _getParent(const std::string & frame_id, TimePoint time, std::string & parent) const;
/** \brief A way to get a std::vector of available frame ids */
TF2_PUBLIC
void _getFrameStrings(std::vector<std::string> & ids) const;
TF2_PUBLIC
CompactFrameID _lookupFrameNumber(const std::string & frameid_str) const
{
return lookupFrameNumber(frameid_str);
}
TF2_PUBLIC
CompactFrameID _lookupOrInsertFrameNumber(const std::string & frameid_str)
{
return lookupOrInsertFrameNumber(frameid_str);
}
TF2_PUBLIC
tf2::TF2Error _getLatestCommonTime(
CompactFrameID target_frame, CompactFrameID source_frame,
TimePoint & time, std::string * error_string) const
{
std::unique_lock<std::mutex> lock(frame_mutex_);
return getLatestCommonTime(target_frame, source_frame, time, error_string);
}
TF2_PUBLIC
CompactFrameID _validateFrameId(
const char * function_name_arg,
const std::string & frame_id) const
{
return validateFrameId(function_name_arg, frame_id);
}
/**@brief Get the duration over which this transformer will cache */
TF2_PUBLIC
tf2::Duration getCacheLength() {return cache_time_;}
/** \brief Backwards compatabilityA way to see what frames have been cached
* Useful for debugging
*/
TF2_PUBLIC
std::string _allFramesAsDot(TimePoint current_time) const;
TF2_PUBLIC
std::string _allFramesAsDot() const;
/** \brief Backwards compatabilityA way to see what frames are in a chain
* Useful for debugging
*/
TF2_PUBLIC
void _chainAsVector(
const std::string & target_frame, TimePoint target_time,
const std::string & source_frame, TimePoint source_time,
const std::string & fixed_frame,
std::vector<std::string> & output) const;
private:
/******************** Internal Storage ****************/
/** \brief The pointers to potential frames that the tree can be made of.
* The frames will be dynamically allocated at run time when set the first time. */
typedef std::vector<TimeCacheInterfacePtr> V_TimeCacheInterface;
V_TimeCacheInterface frames_;
/** \brief A mutex to protect testing and allocating new frames on the above vector. */
mutable std::mutex frame_mutex_;
/** \brief A map from string frame ids to CompactFrameID */
typedef std::unordered_map<std::string, CompactFrameID> M_StringToCompactFrameID;
M_StringToCompactFrameID frameIDs_;
/** \brief A map from CompactFrameID frame_id_numbers to string for debugging and output */
std::vector<std::string> frameIDs_reverse_;
/** \brief A map to lookup the most recent authority for a given frame */
std::map<CompactFrameID, std::string> frame_authority_;
/// How long to cache transform history
tf2::Duration cache_time_;
typedef uint32_t TransformableCallbackHandle;
typedef std::unordered_map<TransformableCallbackHandle,
TransformableCallback> M_TransformableCallback;
M_TransformableCallback transformable_callbacks_;
uint32_t transformable_callbacks_counter_;
std::mutex transformable_callbacks_mutex_;
struct TransformableRequest
{
TimePoint time;
TransformableRequestHandle request_handle;
TransformableCallbackHandle cb_handle;
CompactFrameID target_id;
CompactFrameID source_id;
std::string target_string;
std::string source_string;
};
typedef std::vector<TransformableRequest> V_TransformableRequest;
V_TransformableRequest transformable_requests_;
std::mutex transformable_requests_mutex_;
uint64_t transformable_requests_counter_;
bool using_dedicated_thread_;
/************************* Internal Functions ****************************/
/** \brief A way to see what frames have been cached
* Useful for debugging. Use this call internally.
*/
std::string allFramesAsStringNoLock() const;
bool 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);
void lookupTransformImpl(
const std::string & target_frame, const std::string & source_frame,
const TimePoint & time_in, tf2::Transform & transform, TimePoint & time_out) const;
void 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;
/** \brief An accessor to get a frame.
* \param c_frame_id The frameID of the desired Reference Frame
*/
TimeCacheInterfacePtr getFrame(CompactFrameID c_frame_id) const;
TimeCacheInterfacePtr allocateFrame(CompactFrameID cfid, bool is_static);
/** \brief Validate a frame ID format and look up its CompactFrameID.
* For invalid cases, produce an message.
* \param function_name_arg string to print out in the message,
* the current function and argument name being validated
* \param frame_id name of the tf frame to validate
* \param[out] error_msg if non-nullptr, fill with produced error messaging.
* Otherwise messages are logged as warning.
* \return The CompactFrameID of the frame or 0 if not found.
*/
CompactFrameID validateFrameId(
const char * function_name_arg,
const std::string & frame_id,
std::string * error_msg) const;
/** \brief Validate a frame ID format and look it up its compact ID.
* Raise an exception for invalid cases.
* \param function_name_arg string to print out in the exception,
* the current function and argument name being validated
* \param frame_id name of the tf frame to validate
* \return The CompactFrameID of the existing frame.
* \throws InvalidArgumentException if the frame_id string has an invalid format
* \throws LookupException if frame_id did not exist
*/
CompactFrameID validateFrameId(
const char * function_name_arg,
const std::string & frame_id) const;
/// String to number for frame lookup. Returns 0 if the frame was not found.
CompactFrameID lookupFrameNumber(const std::string & frameid_str) const;
/// String to number for frame lookup with dynamic allocation of new frames
CompactFrameID lookupOrInsertFrameNumber(const std::string & frameid_str);
/// Number to string frame lookup may throw LookupException if number invalid
const std::string & lookupFrameString(CompactFrameID frame_id_num) const;
void createConnectivityErrorString(
CompactFrameID source_frame, CompactFrameID target_frame,
std::string * out) const;
/**@brief Return the latest rostime which is common across the spanning set
* zero if fails to cross */
tf2::TF2Error getLatestCommonTime(
CompactFrameID target_frame, CompactFrameID source_frame,
TimePoint & time, std::string * error_string) const;
/**@brief Traverse the transform tree. If frame_chain is not nullptr, store the traversed frame tree in vector frame_chain.
* */
template<typename F>
tf2::TF2Error walkToTopParent(
F & f, TimePoint time, CompactFrameID target_id,
CompactFrameID source_id, std::string * error_string,
std::vector<CompactFrameID> * frame_chain) const;
void testTransformableRequests();
// Actual implementation to walk the transform tree and find out if a transform exists.
bool canTransformInternal(
CompactFrameID target_id, CompactFrameID source_id,
const TimePoint & time, std::string * error_msg) const;
};
} // namespace tf2
#endif // TF2__BUFFER_CORE_H_