Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00038 #ifndef FCL_TRANSFORM_H
00039 #define FCL_TRANSFORM_H
00040
00041 #include "fcl/math/matrix_3f.h"
00042 #include <boost/thread/mutex.hpp>
00043
00044 namespace fcl
00045 {
00046
00048 class Quaternion3f
00049 {
00050 public:
00052 Quaternion3f()
00053 {
00054 data[0] = 1;
00055 data[1] = 0;
00056 data[2] = 0;
00057 data[3] = 0;
00058 }
00059
00060 Quaternion3f(FCL_REAL a, FCL_REAL b, FCL_REAL c, FCL_REAL d)
00061 {
00062 data[0] = a;
00063 data[1] = b;
00064 data[2] = c;
00065 data[3] = d;
00066 }
00067
00069 bool isIdentity() const
00070 {
00071 return (data[0] == 1) && (data[1] == 0) && (data[2] == 0) && (data[3] == 0);
00072 }
00073
00075 void fromRotation(const Matrix3f& R);
00076
00078 void toRotation(Matrix3f& R) const;
00079
00081 void fromAxes(const Vec3f axis[3]);
00082
00084 void toAxes(Vec3f axis[3]) const;
00085
00087 void fromAxisAngle(const Vec3f& axis, FCL_REAL angle);
00088
00090 void toAxisAngle(Vec3f& axis, FCL_REAL& angle) const;
00091
00093 FCL_REAL dot(const Quaternion3f& other) const;
00094
00096 Quaternion3f operator + (const Quaternion3f& other) const;
00097 const Quaternion3f& operator += (const Quaternion3f& other);
00098
00100 Quaternion3f operator - (const Quaternion3f& other) const;
00101 const Quaternion3f& operator -= (const Quaternion3f& other);
00102
00104 Quaternion3f operator * (const Quaternion3f& other) const;
00105 const Quaternion3f& operator *= (const Quaternion3f& other);
00106
00108 Quaternion3f operator - () const;
00109
00111 Quaternion3f operator * (FCL_REAL t) const;
00112 const Quaternion3f& operator *= (FCL_REAL t);
00113
00115 Quaternion3f& conj();
00116
00118 Quaternion3f& inverse();
00119
00121 Vec3f transform(const Vec3f& v) const;
00122
00123 inline const FCL_REAL& getW() const { return data[0]; }
00124 inline const FCL_REAL& getX() const { return data[1]; }
00125 inline const FCL_REAL& getY() const { return data[2]; }
00126 inline const FCL_REAL& getZ() const { return data[3]; }
00127
00128 inline FCL_REAL& getW() { return data[0]; }
00129 inline FCL_REAL& getX() { return data[1]; }
00130 inline FCL_REAL& getY() { return data[2]; }
00131 inline FCL_REAL& getZ() { return data[3]; }
00132
00133 Vec3f getColumn(std::size_t i) const;
00134
00135 Vec3f getRow(std::size_t i) const;
00136
00137 private:
00138
00139 FCL_REAL data[4];
00140 };
00141
00143 Quaternion3f conj(const Quaternion3f& q);
00144
00146 Quaternion3f inverse(const Quaternion3f& q);
00147
00149 class Transform3f
00150 {
00151 boost::mutex lock_;
00152
00154 mutable bool matrix_set;
00156 mutable Matrix3f R;
00157
00159 Vec3f T;
00160
00162 Quaternion3f q;
00163
00164 const Matrix3f& getRotationInternal() const;
00165 public:
00166
00168 Transform3f()
00169 {
00170 setIdentity();
00171 }
00172
00174 Transform3f(const Matrix3f& R_, const Vec3f& T_) : matrix_set(true),
00175 R(R_),
00176 T(T_)
00177 {
00178 q.fromRotation(R_);
00179 }
00180
00182 Transform3f(const Quaternion3f& q_, const Vec3f& T_) : matrix_set(false),
00183 T(T_),
00184 q(q_)
00185 {
00186 }
00187
00189 Transform3f(const Matrix3f& R_) : matrix_set(true),
00190 R(R_)
00191 {
00192 q.fromRotation(R_);
00193 }
00194
00196 Transform3f(const Quaternion3f& q_) : matrix_set(false),
00197 q(q_)
00198 {
00199 }
00200
00202 Transform3f(const Vec3f& T_) : matrix_set(true),
00203 T(T_)
00204 {
00205 R.setIdentity();
00206 }
00207
00209 Transform3f(const Transform3f& tf) : matrix_set(tf.matrix_set),
00210 R(tf.R),
00211 T(tf.T),
00212 q(tf.q)
00213 {
00214 }
00215
00217 Transform3f& operator = (const Transform3f& tf)
00218 {
00219 matrix_set = tf.matrix_set;
00220 R = tf.R;
00221 q = tf.q;
00222 T = tf.T;
00223 return *this;
00224 }
00225
00227 inline const Vec3f& getTranslation() const
00228 {
00229 return T;
00230 }
00231
00233 inline const Matrix3f& getRotation() const
00234 {
00235 if(matrix_set) return R;
00236 return getRotationInternal();
00237 }
00238
00240 inline const Quaternion3f& getQuatRotation() const
00241 {
00242 return q;
00243 }
00244
00246 inline void setTransform(const Matrix3f& R_, const Vec3f& T_)
00247 {
00248 R = R_;
00249 T = T_;
00250 matrix_set = true;
00251 q.fromRotation(R_);
00252 }
00253
00255 inline void setTransform(const Quaternion3f& q_, const Vec3f& T_)
00256 {
00257 matrix_set = false;
00258 q = q_;
00259 T = T_;
00260 }
00261
00263 inline void setRotation(const Matrix3f& R_)
00264 {
00265 R = R_;
00266 matrix_set = true;
00267 q.fromRotation(R_);
00268 }
00269
00271 inline void setTranslation(const Vec3f& T_)
00272 {
00273 T = T_;
00274 }
00275
00277 inline void setQuatRotation(const Quaternion3f& q_)
00278 {
00279 matrix_set = false;
00280 q = q_;
00281 }
00282
00284 inline Vec3f transform(const Vec3f& v) const
00285 {
00286 return q.transform(v) + T;
00287 }
00288
00290 inline Transform3f& inverse()
00291 {
00292 matrix_set = false;
00293 q.conj();
00294 T = q.transform(-T);
00295 return *this;
00296 }
00297
00299 inline Transform3f inverseTimes(const Transform3f& other) const
00300 {
00301 const Quaternion3f& q_inv = fcl::conj(q);
00302 return Transform3f(q_inv * other.q, q_inv.transform(other.T - T));
00303 }
00304
00306 inline const Transform3f& operator *= (const Transform3f& other)
00307 {
00308 matrix_set = false;
00309 T = q.transform(other.T) + T;
00310 q *= other.q;
00311 return *this;
00312 }
00313
00315 inline Transform3f operator * (const Transform3f& other) const
00316 {
00317 Quaternion3f q_new = q * other.q;
00318 return Transform3f(q_new, q.transform(other.T) + T);
00319 }
00320
00322 inline bool isIdentity() const
00323 {
00324 return q.isIdentity() && T.isZero();
00325 }
00326
00328 inline void setIdentity()
00329 {
00330 R.setIdentity();
00331 T.setValue(0);
00332 q = Quaternion3f();
00333 matrix_set = true;
00334 }
00335
00336 };
00337
00339 Transform3f inverse(const Transform3f& tf);
00340
00342 void relativeTransform(const Transform3f& tf1, const Transform3f& tf2,
00343 Transform3f& tf);
00344
00345 }
00346
00347 #endif