tf2 rolling
tf2 maintains the relationship between coordinate frames in a tree structure buffered in time, and lets the user transform points, vectors, etc between any two coordinate frames at any desired point in time.
Loading...
Searching...
No Matches
Transform.hpp
Go to the documentation of this file.
1/*
2Copyright (c) 2003-2006 Gino van den Bergen / Erwin Coumans http://continuousphysics.com/Bullet/
3
4This software is provided 'as-is', without any express or implied warranty.
5In no event will the authors be held liable for any damages arising from the use of this software.
6Permission is granted to anyone to use this software for any purpose,
7including commercial applications, and to alter it and redistribute it freely,
8subject to the following restrictions:
9
101. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required.
112. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
123. This notice may not be removed or altered from any source distribution.
13*/
14
15
16
17#ifndef TF2__LINEARMATH__TRANSFORM_HPP
18#define TF2__LINEARMATH__TRANSFORM_HPP
19
20
21#include "Matrix3x3.hpp"
23
24
25namespace tf2
26{
27
28#define TransformData TransformDoubleData
29
30
33class Transform {
34
36 Matrix3x3 m_basis;
38 Vector3 m_origin;
39
40public:
41
49 const Vector3& c = Vector3(tf2Scalar(0), tf2Scalar(0), tf2Scalar(0)))
50 : m_basis(q),
51 m_origin(c)
52 {}
53
58 const Vector3& c = Vector3(tf2Scalar(0), tf2Scalar(0), tf2Scalar(0)))
59 : m_basis(b),
60 m_origin(c)
61 {}
64 : m_basis(other.m_basis),
65 m_origin(other.m_origin)
66 {
67 }
70 {
71 m_basis = other.m_basis;
72 m_origin = other.m_origin;
73 return *this;
74 }
75
81 m_basis = t1.m_basis * t2.m_basis;
82 m_origin = t1(t2.m_origin);
83 }
84
85/* void multInverseLeft(const Transform& t1, const Transform& t2) {
86 Vector3 v = t2.m_origin - t1.m_origin;
87 m_basis = tf2MultTransposeLeft(t1.m_basis, t2.m_basis);
88 m_origin = v * t1.m_basis;
89 }
90 */
91
94 {
95 return Vector3(m_basis[0].dot(x) + m_origin.x(),
96 m_basis[1].dot(x) + m_origin.y(),
97 m_basis[2].dot(x) + m_origin.z());
98 }
99
102 {
103 return (*this)(x);
104 }
105
108 {
109 return getRotation() * q;
110 }
111
115 TF2SIMD_FORCE_INLINE const Matrix3x3& getBasis() const { return m_basis; }
116
118 TF2SIMD_FORCE_INLINE Vector3& getOrigin() { return m_origin; }
120 TF2SIMD_FORCE_INLINE const Vector3& getOrigin() const { return m_origin; }
121
126 m_basis.getRotation(q);
127 return q;
128 }
129
130
135 {
136 m_basis.setFromOpenGLSubMatrix(m);
137 m_origin.setValue(m[12],m[13],m[14]);
138 }
139
144 {
145 m_basis.getOpenGLSubMatrix(m);
146 m[12] = m_origin.x();
147 m[13] = m_origin.y();
148 m[14] = m_origin.z();
149 m[15] = tf2Scalar(1.0);
150 }
151
155 {
156 m_origin = origin;
157 }
158
160
161
164 {
165 m_basis = basis;
166 }
167
170 {
171 m_basis.setRotation(q);
172 }
173
174
178 {
179 m_basis.setIdentity();
180 m_origin.setValue(tf2Scalar(0.0), tf2Scalar(0.0), tf2Scalar(0.0));
181 }
182
187 {
188 m_origin += m_basis * t.m_origin;
189 m_basis *= t.m_basis;
190 return *this;
191 }
192
196 {
197 Matrix3x3 inv = m_basis.transpose();
198 return Transform(inv, inv * -m_origin);
199 }
200
205 Transform inverseTimes(const Transform& t) const;
206
209 Transform operator*(const Transform& t) const;
210
213 static const Transform& getIdentity()
214 {
216 return identityTransform;
217 }
218
220 void serialize(struct TransformData& dataOut) const;
221
223 void serializeFloat(struct TransformFloatData& dataOut) const;
224
226 void deSerialize(const struct TransformData& dataIn);
227
229 void deSerializeDouble(const struct TransformDoubleData& dataIn);
230
232 void deSerializeFloat(const struct TransformFloatData& dataIn);
233
234};
235
236
239{
240 Vector3 v = inVec - m_origin;
241 return (m_basis.transpose() * v);
242}
243
246{
247 Vector3 v = t.getOrigin() - m_origin;
248 return Transform(m_basis.transposeTimes(t.m_basis),
249 v * m_basis);
250}
251
254{
255 return Transform(m_basis * t.m_basis,
256 (*this)(t.m_origin));
257}
258
261{
262 return ( t1.getBasis() == t2.getBasis() &&
263 t1.getOrigin() == t2.getOrigin() );
264}
265
266
273
279
280
281
283{
284 m_basis.serialize(dataOut.m_basis);
285 m_origin.serialize(dataOut.m_origin);
286}
287
293
294
296{
297 m_basis.deSerialize(dataIn.m_basis);
298 m_origin.deSerialize(dataIn.m_origin);
299}
300
306
312
313}
314
315#endif // TF2__LINEARMATH__TRANSFORM_HPP
#define TF2SIMD_FORCE_INLINE
Definition Scalar.hpp:129
double tf2Scalar
The tf2Scalar type abstracts floating point numbers, to easily switch between double and single float...
Definition Scalar.hpp:159
#define TransformData
Definition Transform.hpp:28
The Matrix3x3 class implements a 3x3 rotation matrix, to perform linear algebra in combination with Q...
Definition Matrix3x3.hpp:33
void serialize(struct Matrix3x3Data &dataOut) const
Definition Matrix3x3.hpp:672
void deSerializeFloat(const struct Matrix3x3FloatData &dataIn)
Definition Matrix3x3.hpp:691
void setRotation(const Quaternion &q)
Set the matrix from a quaternion.
Definition Matrix3x3.hpp:155
static const Matrix3x3 & getIdentity()
Definition Matrix3x3.hpp:217
void getOpenGLSubMatrix(tf2Scalar *m) const
Fill the values of the matrix into a 9 element array.
Definition Matrix3x3.hpp:228
void deSerializeDouble(const struct Matrix3x3DoubleData &dataIn)
Definition Matrix3x3.hpp:697
void setIdentity()
Set the matrix to the identity.
Definition Matrix3x3.hpp:209
void getRotation(Quaternion &q) const
Get the matrix represented as a quaternion.
Definition Matrix3x3.hpp:247
void serializeFloat(struct Matrix3x3FloatData &dataOut) const
Definition Matrix3x3.hpp:678
void deSerialize(const struct Matrix3x3Data &dataIn)
Definition Matrix3x3.hpp:685
Matrix3x3 transposeTimes(const Matrix3x3 &m) const
Definition Matrix3x3.hpp:587
void setFromOpenGLSubMatrix(const tf2Scalar *m)
Set from a carray of tf2Scalars.
Definition Matrix3x3.hpp:125
Matrix3x3 transpose() const
Return the transpose of the matrix.
Definition Matrix3x3.hpp:559
The Quaternion implements quaternion to perform linear algebra rotations in combination with Matrix3x...
Definition Quaternion.hpp:30
The Transform class supports rigid transforms with only translation and rotation and no scaling/shear...
Definition Transform.hpp:33
Vector3 operator*(const Vector3 &x) const
Return the transform of the vector.
Definition Transform.hpp:101
Transform(const Matrix3x3 &b, const Vector3 &c=Vector3(tf2Scalar(0), tf2Scalar(0), tf2Scalar(0)))
Constructor from Matrix3x3 (optional Vector3)
Definition Transform.hpp:57
void deSerialize(const struct TransformData &dataIn)
Definition Transform.hpp:295
Transform inverse() const
Return the inverse of this transform.
Definition Transform.hpp:195
Vector3 operator()(const Vector3 &x) const
Return the transform of the vector.
Definition Transform.hpp:93
Vector3 & getOrigin()
Return the origin vector translation.
Definition Transform.hpp:118
Quaternion getRotation() const
Return a quaternion representing the rotation.
Definition Transform.hpp:124
void deSerializeDouble(const struct TransformDoubleData &dataIn)
Definition Transform.hpp:307
void setFromOpenGLMatrix(const tf2Scalar *m)
Set from an array.
Definition Transform.hpp:134
void serializeFloat(struct TransformFloatData &dataOut) const
Definition Transform.hpp:288
void setRotation(const Quaternion &q)
Set the rotational element by Quaternion.
Definition Transform.hpp:169
static const Transform & getIdentity()
Return an identity transform.
Definition Transform.hpp:213
void setOrigin(const Vector3 &origin)
Set the translational element.
Definition Transform.hpp:154
const Vector3 & getOrigin() const
Return the origin vector translation.
Definition Transform.hpp:120
Matrix3x3 & getBasis()
Return the basis matrix for the rotation.
Definition Transform.hpp:113
Transform(const Quaternion &q, const Vector3 &c=Vector3(tf2Scalar(0), tf2Scalar(0), tf2Scalar(0)))
Constructor from Quaternion (optional Vector3 )
Definition Transform.hpp:48
void mult(const Transform &t1, const Transform &t2)
Set the current transform as the value of the product of two transforms.
Definition Transform.hpp:80
void getOpenGLMatrix(tf2Scalar *m) const
Fill an array representation.
Definition Transform.hpp:143
Transform inverseTimes(const Transform &t) const
Return the inverse of this transform times the other transform.
Definition Transform.hpp:245
Transform(const Transform &other)
Copy constructor.
Definition Transform.hpp:63
Vector3 invXform(const Vector3 &inVec) const
Definition Transform.hpp:238
Transform()
No initialization constructor.
Definition Transform.hpp:44
const Matrix3x3 & getBasis() const
Return the basis matrix for the rotation.
Definition Transform.hpp:115
Transform & operator*=(const Transform &t)
Multiply this Transform by another(this = this * another)
Definition Transform.hpp:186
void setBasis(const Matrix3x3 &basis)
Set the rotational element by Matrix3x3.
Definition Transform.hpp:163
void setIdentity()
Set this transformation to the identity.
Definition Transform.hpp:177
Quaternion operator*(const Quaternion &q) const
Return the transform of the Quaternion.
Definition Transform.hpp:107
void deSerializeFloat(const struct TransformFloatData &dataIn)
Definition Transform.hpp:301
void serialize(struct TransformData &dataOut) const
Definition Transform.hpp:282
Transform & operator=(const Transform &other)
Assignment Operator.
Definition Transform.hpp:69
tf2::Vector3 can be used to represent 3D points and vectors. It has an un-used w component to suit 16...
Definition Vector3.hpp:40
const tf2Scalar & z() const
Return the z value.
Definition Vector3.hpp:269
const tf2Scalar & x() const
Return the x value.
Definition Vector3.hpp:265
void deSerialize(const struct Vector3Data &dataIn)
Definition Vector3.hpp:716
void serialize(struct Vector3Data &dataOut) const
Definition Vector3.hpp:709
void setValue(const tf2Scalar &x, const tf2Scalar &y, const tf2Scalar &z)
Definition Vector3.hpp:310
void deSerializeDouble(const struct Vector3DoubleData &dataIn)
Definition Vector3.hpp:702
void deSerializeFloat(const struct Vector3FloatData &dataIn)
Definition Vector3.hpp:688
const tf2Scalar & y() const
Return the y value.
Definition Vector3.hpp:267
void serializeFloat(struct Vector3FloatData &dataOut) const
Definition Vector3.hpp:681
Definition buffer_core.hpp:58
B toMsg(const A &a)
Function that converts from one type to a ROS message type. It has to be implemented by each data typ...
tf2Scalar dot(const Quaternion &q1, const Quaternion &q2)
Calculate the dot product between two quaternions.
Definition Quaternion.hpp:456
bool operator==(const Matrix3x3 &m1, const Matrix3x3 &m2)
Equality operator between two matrices It will test all elements are equal.
Definition Matrix3x3.hpp:650
for serialization
Definition Matrix3x3.hpp:665
for serialization
Definition Matrix3x3.hpp:659
Definition Transform.hpp:275
Matrix3x3DoubleData m_basis
Definition Transform.hpp:276
Vector3DoubleData m_origin
Definition Transform.hpp:277
for serialization
Definition Transform.hpp:269
Matrix3x3FloatData m_basis
Definition Transform.hpp:270
Vector3FloatData m_origin
Definition Transform.hpp:271
Definition Vector3.hpp:676
Definition Vector3.hpp:671
#define TF2_PUBLIC
Definition visibility_control.h:57