hpp-fcl  3.0.0
HPP fork of FCL -- The Flexible Collision Library
transform.h
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2011-2014, Willow Garage, Inc.
5  * Copyright (c) 2014-2015, Open Source Robotics Foundation
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of Open Source Robotics Foundation nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  */
35 
38 #ifndef HPP_FCL_TRANSFORM_H
39 #define HPP_FCL_TRANSFORM_H
40 
41 #include "hpp/fcl/fwd.hh"
42 #include "hpp/fcl/data_types.h"
43 
44 namespace hpp {
45 namespace fcl {
46 
47 HPP_FCL_DEPRECATED typedef Eigen::Quaternion<FCL_REAL> Quaternion3f;
48 typedef Eigen::Quaternion<FCL_REAL> Quatf;
49 
50 static inline std::ostream& operator<<(std::ostream& o, const Quatf& q) {
51  o << "(" << q.w() << " " << q.x() << " " << q.y() << " " << q.z() << ")";
52  return o;
53 }
54 
58  Matrix3f R;
59 
61  Vec3f T;
62 
63  public:
66  setIdentity(); // set matrix_set true
67  }
68 
69  static Transform3f Identity() { return Transform3f(); }
70 
72  template <typename Matrixx3Like, typename Vector3Like>
73  Transform3f(const Eigen::MatrixBase<Matrixx3Like>& R_,
74  const Eigen::MatrixBase<Vector3Like>& T_)
75  : R(R_), T(T_) {}
76 
78  template <typename Vector3Like>
79  Transform3f(const Quatf& q_, const Eigen::MatrixBase<Vector3Like>& T_)
80  : R(q_.toRotationMatrix()), T(T_) {}
81 
83  Transform3f(const Matrix3f& R_) : R(R_), T(Vec3f::Zero()) {}
84 
86  Transform3f(const Quatf& q_) : R(q_), T(Vec3f::Zero()) {}
87 
89  Transform3f(const Vec3f& T_) : R(Matrix3f::Identity()), T(T_) {}
90 
92  Transform3f(const Transform3f& tf) : R(tf.R), T(tf.T) {}
93 
96  R = tf.R;
97  T = tf.T;
98  return *this;
99  }
100 
102  inline const Vec3f& getTranslation() const { return T; }
103 
105  inline const Vec3f& translation() const { return T; }
106 
108  inline Vec3f& translation() { return T; }
109 
111  inline const Matrix3f& getRotation() const { return R; }
112 
114  inline const Matrix3f& rotation() const { return R; }
115 
117  inline Matrix3f& rotation() { return R; }
118 
120  inline Quatf getQuatRotation() const { return Quatf(R); }
121 
123  template <typename Matrix3Like, typename Vector3Like>
124  inline void setTransform(const Eigen::MatrixBase<Matrix3Like>& R_,
125  const Eigen::MatrixBase<Vector3Like>& T_) {
126  R.noalias() = R_;
127  T.noalias() = T_;
128  }
129 
131  inline void setTransform(const Quatf& q_, const Vec3f& T_) {
132  R = q_.toRotationMatrix();
133  T = T_;
134  }
135 
137  template <typename Derived>
138  inline void setRotation(const Eigen::MatrixBase<Derived>& R_) {
139  R.noalias() = R_;
140  }
141 
143  template <typename Derived>
144  inline void setTranslation(const Eigen::MatrixBase<Derived>& T_) {
145  T.noalias() = T_;
146  }
147 
149  inline void setQuatRotation(const Quatf& q_) { R = q_.toRotationMatrix(); }
150 
152  template <typename Derived>
153  inline Vec3f transform(const Eigen::MatrixBase<Derived>& v) const {
154  return R * v + T;
155  }
156 
158  template <typename Derived>
159  inline Vec3f inverseTransform(const Eigen::MatrixBase<Derived>& v) const {
160  return R.transpose() * (v - T);
161  }
162 
165  R.transposeInPlace();
166  T = -R * T;
167  return *this;
168  }
169 
171  inline Transform3f inverse() {
172  return Transform3f(R.transpose(), -R.transpose() * T);
173  }
174 
176  inline Transform3f inverseTimes(const Transform3f& other) const {
177  return Transform3f(R.transpose() * other.R, R.transpose() * (other.T - T));
178  }
179 
181  inline const Transform3f& operator*=(const Transform3f& other) {
182  T += R * other.T;
183  R *= other.R;
184  return *this;
185  }
186 
188  inline Transform3f operator*(const Transform3f& other) const {
189  return Transform3f(R * other.R, R * other.T + T);
190  }
191 
193  inline bool isIdentity(
194  const FCL_REAL& prec =
195  Eigen::NumTraits<FCL_REAL>::dummy_precision()) const {
196  return R.isIdentity(prec) && T.isZero(prec);
197  }
198 
200  inline void setIdentity() {
201  R.setIdentity();
202  T.setZero();
203  }
204 
206  static Transform3f Random() { return Transform3f().setRandom(); }
207 
209  Transform3f& setRandom();
210 
211  bool operator==(const Transform3f& other) const {
212  return (R == other.getRotation()) && (T == other.getTranslation());
213  }
214 
215  bool operator!=(const Transform3f& other) const { return !(*this == other); }
216 
217  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
218 };
219 
220 template <typename Derived>
221 inline Quatf fromAxisAngle(const Eigen::MatrixBase<Derived>& axis,
222  FCL_REAL angle) {
223  return Quatf(Eigen::AngleAxis<FCL_REAL>(angle, axis));
224 }
225 
229  // Rotational part
230  const FCL_REAL u1 = (FCL_REAL)rand() / RAND_MAX;
231  const FCL_REAL u2 = (FCL_REAL)rand() / RAND_MAX;
232  const FCL_REAL u3 = (FCL_REAL)rand() / RAND_MAX;
233 
234  const FCL_REAL mult1 = std::sqrt(FCL_REAL(1.0) - u1);
235  const FCL_REAL mult2 = std::sqrt(u1);
236 
237  static const FCL_REAL PI_value = static_cast<FCL_REAL>(EIGEN_PI);
238  FCL_REAL s2 = std::sin(2 * PI_value * u2);
239  FCL_REAL c2 = std::cos(2 * PI_value * u2);
240  FCL_REAL s3 = std::sin(2 * PI_value * u3);
241  FCL_REAL c3 = std::cos(2 * PI_value * u3);
242 
243  Quatf q;
244  q.w() = mult1 * s2;
245  q.x() = mult1 * c2;
246  q.y() = mult2 * s3;
247  q.z() = mult2 * c3;
248  return q;
249 }
250 
252  const Quatf q = uniformRandomQuaternion();
253  this->rotation() = q.matrix();
254  this->translation().setRandom();
255 
256  return *this;
257 }
258 
262  Matrix3f basis = Matrix3f::Zero();
263  basis.col(2) = vec.normalized();
264  basis.col(1) = -vec.unitOrthogonal();
265  basis.col(0) = basis.col(1).cross(vec);
266  return basis;
267 }
268 
269 } // namespace fcl
270 } // namespace hpp
271 
272 #endif
Simple transform class used locally by InterpMotion.
Definition: transform.h:56
Transform3f(const Vec3f &T_)
Construct transform from translation.
Definition: transform.h:89
Quatf getQuatRotation() const
get quaternion
Definition: transform.h:120
Transform3f operator*(const Transform3f &other) const
multiply with another transform
Definition: transform.h:188
const Transform3f & operator*=(const Transform3f &other)
multiply with another transform
Definition: transform.h:181
Transform3f & setRandom()
set the transform to a random transform
Definition: transform.h:251
void setTransform(const Eigen::MatrixBase< Matrix3Like > &R_, const Eigen::MatrixBase< Vector3Like > &T_)
set transform from rotation and translation
Definition: transform.h:124
const Vec3f & getTranslation() const
get translation
Definition: transform.h:102
bool operator!=(const Transform3f &other) const
Definition: transform.h:215
void setTransform(const Quatf &q_, const Vec3f &T_)
set transform from rotation and translation
Definition: transform.h:131
void setQuatRotation(const Quatf &q_)
set transform from rotation
Definition: transform.h:149
const Matrix3f & getRotation() const
get rotation
Definition: transform.h:111
const Matrix3f & rotation() const
get rotation
Definition: transform.h:114
Transform3f inverseTimes(const Transform3f &other) const
inverse the transform and multiply with another
Definition: transform.h:176
Vec3f & translation()
get translation
Definition: transform.h:108
Transform3f(const Eigen::MatrixBase< Matrixx3Like > &R_, const Eigen::MatrixBase< Vector3Like > &T_)
Construct transform from rotation and translation.
Definition: transform.h:73
Transform3f(const Transform3f &tf)
Construct transform from other transform.
Definition: transform.h:92
static Transform3f Identity()
Definition: transform.h:69
bool operator==(const Transform3f &other) const
Definition: transform.h:211
const Vec3f & translation() const
get translation
Definition: transform.h:105
bool isIdentity(const FCL_REAL &prec=Eigen::NumTraits< FCL_REAL >::dummy_precision()) const
check whether the transform is identity
Definition: transform.h:193
Transform3f()
Default transform is no movement.
Definition: transform.h:65
Transform3f(const Quatf &q_)
Construct transform from rotation.
Definition: transform.h:86
void setTranslation(const Eigen::MatrixBase< Derived > &T_)
set transform from translation
Definition: transform.h:144
Vec3f transform(const Eigen::MatrixBase< Derived > &v) const
transform a given vector by the transform
Definition: transform.h:153
Vec3f inverseTransform(const Eigen::MatrixBase< Derived > &v) const
transform a given vector by the inverse of the transform
Definition: transform.h:159
void setIdentity()
set the transform to be identity transform
Definition: transform.h:200
Transform3f & operator=(const Transform3f &tf)
operator =
Definition: transform.h:95
Matrix3f & rotation()
get rotation
Definition: transform.h:117
void setRotation(const Eigen::MatrixBase< Derived > &R_)
set transform from rotation
Definition: transform.h:138
Transform3f & inverseInPlace()
inverse transform
Definition: transform.h:164
Transform3f inverse()
inverse transform
Definition: transform.h:171
Transform3f(const Matrix3f &R_)
Construct transform from rotation.
Definition: transform.h:83
static Transform3f Random()
return a random transform
Definition: transform.h:206
Transform3f(const Quatf &q_, const Eigen::MatrixBase< Vector3Like > &T_)
Construct transform from rotation and translation.
Definition: transform.h:79
#define HPP_FCL_DLLAPI
Definition: config.hh:88
#define HPP_FCL_DEPRECATED
Definition: deprecated.hh:37
Matrix3f constructOrthonormalBasisFromVector(const Vec3f &vec)
Construct othonormal basis from vector. The z-axis is the normalized input vector.
Definition: transform.h:261
Eigen::Matrix< FCL_REAL, 3, 3 > Matrix3f
Definition: data_types.h:71
Eigen::Matrix< FCL_REAL, 3, 1 > Vec3f
Definition: data_types.h:67
Eigen::Quaternion< FCL_REAL > Quatf
Definition: transform.h:48
Eigen::Quaternion< FCL_REAL > Quaternion3f
Definition: transform.h:47
Quatf uniformRandomQuaternion()
Uniformly random quaternion sphere. Code taken from Pinocchio (https://github.com/stack-of-tasks/pino...
Definition: transform.h:228
double FCL_REAL
Definition: data_types.h:66
Quatf fromAxisAngle(const Eigen::MatrixBase< Derived > &axis, FCL_REAL angle)
Definition: transform.h:221
Main namespace.
Definition: broadphase_bruteforce.h:44