|
1 | 1 | /**
|
2 | 2 | \mainpage
|
3 |
| -\htmlinclude manifest.html |
4 | 3 |
|
5 |
| -\b tf2 is the second generation of the tf library. |
| 4 | +``tf2`` is the second generation of the tf library. |
6 | 5 |
|
7 |
| -This library implements the interface defined by tf2::BufferCore. |
| 6 | +This library implements the interface defined by `tf2::BufferCore`. |
8 | 7 |
|
9 | 8 | There is also a Python wrapper with the same API that class this library using CPython bindings.
|
10 | 9 |
|
11 |
| -\section codeapi Code API |
| 10 | +Some tutorials are available at <A HREF="http://docs.ros.org/en/rolling/Tutorials/Intermediate/Tf2/Tf2-Main.html">https://docs.ros.org/</A>. |
12 | 11 |
|
13 |
| -The main interface is through the tf2::BufferCore interface. |
| 12 | +\section architecture Architecture |
14 | 13 |
|
15 |
| -It uses the exceptions in exceptions.h and the Stamped datatype |
16 |
| -in transform_datatypes.h. |
| 14 | +``tf2`` is a transform library designed to provide implementation of interface that keeps track of multiple coordinate frames over time. |
| 15 | +``tf2`` maintains the relationship between coordinate frames in a tree structure buffered in time, and lets the user transform data between any two coordinate frames at any desired point in time. |
| 16 | +The high level goal is to allow developers and users not to have to worry about which coordinate frame any specific data is stored in. |
17 | 17 |
|
18 |
| -\section conversions Conversion Interface |
| 18 | +\subsection main-interface Main Interface |
19 | 19 |
|
20 |
| -tf2 offers a templated conversion interface for external libraries to specify conversions between |
21 |
| -tf2-specific data types and user-defined data types. Various templated functions in tf2_ros use the |
22 |
| -conversion interface to apply transformations from the tf server to these custom datatypes. |
| 20 | +The main interface is through the `tf2::BufferCore` interface. |
| 21 | + |
| 22 | +It uses the exceptions in tf2/exceptions.h and the `tf2::Stamped` datatype in tf2/transform_datatypes.h. |
| 23 | + |
| 24 | +\subsection conversion-interface Conversion Interface |
| 25 | + |
| 26 | +tf2 offers a templated conversion interface for external libraries to specify conversions between ``tf2``-specific data types and user-defined data types. |
| 27 | +Various templated functions in ``tf2_ros`` use the conversion interface to apply transformations from the tf server to these custom datatypes. |
23 | 28 |
|
24 | 29 | The conversion interface is defined in tf2/convert.h.
|
25 | 30 |
|
26 |
| -Some packages that implement this interface: |
| 31 | +\subsection buffer-core-relations Buffer Core: Record and lookup relations between frames |
| 32 | + |
| 33 | +The ``tf2`` library implements the interface defined by `tf2::BufferCore`. |
| 34 | +This class and all classes derived from it are responsible for providing coordinate transforms between any two frames in a system. |
| 35 | +This class provides a simple interface to allow recording and lookup of relationships between arbitrary frames of the system. |
| 36 | + |
| 37 | +``tf2`` assumes that there is a tree of coordinate frame transforms which define the relationship between all coordinate frames. |
| 38 | +After transformation relationships are supplied, query specifiyng target frame, source frame, and time point can be used to obtain required data. |
| 39 | +``tf2`` will take care of all the intermediate transfromation steps for specific queries. |
| 40 | + |
| 41 | +Additionally, ``tf2`` features data interpolation. |
| 42 | +The probability that a specific query would be at the same timestamp of all the frames in the system is very unlikely in an asynchronous system with nanosecond precision. |
| 43 | +Therefore, for any given query it can be expected that data is interpolated. |
| 44 | + |
| 45 | +It should be noted that buffer implicitly limits the maximum cache size of 10s by default as defined by the `tf2::TIMECACHE_DEFAULT_MAX_STORAGE_TIME` and it cannot interpolate outside of the cache history. |
| 46 | +Thus there is a risk of incurring extrapolation limits based on specific system. |
| 47 | + |
| 48 | +\subsubsection buffer-core-methods Buffer Core Methods |
| 49 | + |
| 50 | +The `tf2::BufferCore` class contains useful methods to update the existing tf buffer. |
| 51 | + |
| 52 | +- `tf2::BufferCore::clear` |
| 53 | + |
| 54 | + - This method clears all data in the buffer. |
| 55 | + |
| 56 | +- `tf2::BufferCore::setTransform` |
| 57 | + |
| 58 | + - This method will add `geometry_msgs::msg::TransformStamped` information to the tf data structure. |
| 59 | + |
| 60 | +- `tf2::BufferCore::lookupTransform` |
| 61 | + |
| 62 | + - This method returns the transform between two frames by frame ID. |
| 63 | + - Possible exceptions are `tf2::LookupException`, `tf2::ConnectivityException`, `tf2::ExtrapolationException`, or `tf2::InvalidArgumentException`. |
| 64 | + |
| 65 | +- `tf2::BufferCore::canTransform` |
| 66 | + |
| 67 | + - This method tests if a transform is possible. |
| 68 | + |
| 69 | +- `tf2::BufferCore::getAllFrameNames` |
| 70 | + |
| 71 | + - This method returns all frames that exist in the system. |
| 72 | + |
| 73 | +- `tf2::BufferCore::allFramesAsYAML` |
| 74 | + |
| 75 | + - This method allows to see what frames have been cached in yaml format and is useful for debugging tools. |
| 76 | + |
| 77 | +- `tf2::BufferCore::allFramesAsString` |
| 78 | + |
| 79 | + - This method allows to see what frames have been cached and is useful for debugging. |
| 80 | + |
| 81 | +\subsection supported-datatypes Supported Datatypes |
| 82 | + |
| 83 | +``tf2`` implements templated datatype support. |
| 84 | +This allows the core packages to have minimal dependencies and there be packages which add support for converting to and from different datatypes as well as transforming those data types. |
| 85 | +``tf2`` does have an internal datatypes which are based on bullet's LinearMath library. |
| 86 | +However it's recommended to use a fully supported math datatype which best supports your application. |
| 87 | +``tf2`` conversion methods also support converting between and transforming between multiple different datatypes too. |
| 88 | + |
| 89 | +At it's core ``tf2`` relies on the `tf2::Stamped` data types which can be conveniently correlated to ROS 2 messages which have a `std_msgs::msg::Header`. |
| 90 | + |
| 91 | +\subsubsection data-type-support-packages Data Type Support Packages |
| 92 | + |
| 93 | +These packages provide methods to allow ``tf2`` to work natively with data types of any external library. |
| 94 | +Most are either C++ or Python specific. |
27 | 95 |
|
28 | 96 | - tf2_bullet
|
| 97 | + |
| 98 | + - ``tf2`` methods to work with bullet datatypes natively in C++. |
| 99 | + |
29 | 100 | - tf2_eigen
|
| 101 | + |
| 102 | + - ``tf2`` methods to work with Eigen datatypes natively in C++. |
| 103 | + |
30 | 104 | - tf2_geometry_msgs
|
| 105 | + |
| 106 | + - ``tf2`` methods to work with `geometry_msgs` datatypes natively in C++ or Python. |
| 107 | + |
31 | 108 | - tf2_kdl
|
| 109 | + |
| 110 | + - ``tf2`` methods to work with kdl datatypes natively in C++ or Python. |
| 111 | + |
32 | 112 | - tf2_sensor_msgs
|
33 | 113 |
|
34 |
| -Some tutorials are available at <A HREF="https://docs.ros.org/en/rolling/Tutorials/tf2.html">https://docs.ros.org/</A>. |
| 114 | + - ``tf2`` methods to work with sensor_msgs datatypes natively in C++ or Python. |
| 115 | + |
| 116 | +\subsection coordinate-frame-conventions Coordinate Frame Conventions |
| 117 | + |
| 118 | +An important part of using ``tf2`` is to use standard conventions for coordinate frames. |
| 119 | +There are several sources of conventions for using coordinate frames. |
| 120 | + |
| 121 | +- Units, orientation conventions, chirality, rotation representations, and covariance representations are covered in <a href=https://www.ros.org/reps/rep-0103.html>REP 103</a>. |
| 122 | + |
| 123 | +- Standard names for mobile base coordinate frames are covered in <a href=https://www.ros.org/reps/rep-0105.html>REP 105</a>. |
| 124 | + |
| 125 | +- Standard coordinate frames for Humanoid Robots are in <a href=https://www.ros.org/reps/rep-0120.html>REP 120</a>. |
| 126 | + |
| 127 | +\subsection geometry Geometry |
| 128 | + |
| 129 | +``tf2`` provides basic geometry data types, such as |
| 130 | + |
| 131 | + - `tf2::Vector3` |
| 132 | + |
| 133 | + - `tf2::Matrix3x3` |
| 134 | + |
| 135 | + - `tf2::Quaternion` |
| 136 | + |
| 137 | + - `tf2::Transform` |
| 138 | + |
| 139 | +These data types support linear algebra operations between each other. |
| 140 | + |
| 141 | +\subsection high-level-design High level Design |
| 142 | + |
| 143 | +- A distributed system: |
| 144 | + |
| 145 | + - Purpose: No bottle neck process and all processes are one step away for minimal latency. |
| 146 | + - Implementation: Everything is broadcast and reassembled at end consumer points. |
| 147 | + There can be multiple data sources for tf information. |
| 148 | + Data is not required to be synchronized by using interpolation, so data can arrive out of order. |
| 149 | + |
| 150 | +- Only transform data between coordinate frames at the time of use: |
| 151 | + |
| 152 | + - Purpose: Efficiency, both computational, bandwidth, and simplicity. |
| 153 | + - Implementation: Transform data between given frames only when required. |
| 154 | + |
| 155 | +- Support queries on data which are timestamped at times other than the current time: |
| 156 | + |
| 157 | + - Purpose: Handle data processing lag gracefully. |
| 158 | + - Implementation: Interface class stores all transform data in memory and traverses tree on request. |
| 159 | + |
| 160 | +- Only have to know the name of the coordinate frame to work with data: |
| 161 | + |
| 162 | + - Purpose: Ease of use for users/developers. |
| 163 | + - Implementation: Use string ``frame_ids`` as unique identifiers. |
| 164 | + |
| 165 | +- The system doesn't need to know about the configuration before hand and can handle reconfiguring on the fly: |
| 166 | + |
| 167 | + - Purpose: Generic system for any configuration. |
| 168 | + - Implementation: Use directed tree structure. |
| 169 | + It allows fast traversal (order ``n`` where ``n`` is the depth of the tree) when evaluating a transform. |
| 170 | + It can be reconfigured simply by redefining a link. |
| 171 | + It does not require any structure verification or maintenance of the data structure, except for maintaining a sorted linked list of data for each link. |
| 172 | + |
| 173 | +- Core is ROS agnostic: |
| 174 | + |
| 175 | + - Purpose: Code reuse. |
| 176 | + - Implementation: Core library is C++ class. |
| 177 | + A second class provides ROS interface and instantiates the core library. |
| 178 | + |
| 179 | +- Thread Safe Interface: |
| 180 | + |
| 181 | + - Purpose: Can be used in a multithreaded program. |
| 182 | + - Implementation: Mutexes around data storage for each frame. |
| 183 | + Mutexes around ``frame_id`` lookup map. |
| 184 | + Each are individually locked and unlocked, neither can block the other. |
| 185 | + |
| 186 | +- Native Datatype Interfaces: |
| 187 | + |
| 188 | + - Purpose: Users can interact with ``tf2_ros`` in their native datatypes, the conversion is handled implicitly by the library. |
| 189 | + - Implementation: There is a `tf2::convert` templated method that converts from type A to type B using the geometry_msgs types as the common factor. |
| 190 | + |
| 191 | + And as long as any datatype provides the methods ``msgType toMsg(datatype)`` and ``fromMsg(msgType, datatype)`` it can be automatically converted to any other datatype with the same methods defined and a matching ``msgType``. |
| 192 | + All ``tf2_ros`` interfaces can then be called with native type in and native type out. |
| 193 | + Note, the native type in and out do not need to match. |
35 | 194 |
|
36 | 195 | */
|
0 commit comments