coal/math/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 COAL_TRANSFORM_H
39 #define COAL_TRANSFORM_H
40 
41 #include "coal/fwd.hh"
42 #include "coal/data_types.h"
43 
44 namespace coal {
45 
46 COAL_DEPRECATED typedef Eigen::Quaternion<CoalScalar> Quaternion3f;
47 typedef Eigen::Quaternion<CoalScalar> Quatf;
48 
49 static inline std::ostream& operator<<(std::ostream& o, const Quatf& q) {
50  o << "(" << q.w() << " " << q.x() << " " << q.y() << " " << q.z() << ")";
51  return o;
52 }
53 
55 class COAL_DLLAPI Transform3s {
58 
61 
62  public:
65  setIdentity(); // set matrix_set true
66  }
67 
68  static Transform3s Identity() { return Transform3s(); }
69 
71  template <typename Matrixx3Like, typename Vector3Like>
72  Transform3s(const Eigen::MatrixBase<Matrixx3Like>& R_,
73  const Eigen::MatrixBase<Vector3Like>& T_)
74  : R(R_), T(T_) {}
75 
77  template <typename Vector3Like>
78  Transform3s(const Quatf& q_, const Eigen::MatrixBase<Vector3Like>& T_)
79  : R(q_.toRotationMatrix()), T(T_) {}
80 
82  Transform3s(const Matrix3s& R_) : R(R_), T(Vec3s::Zero()) {}
83 
85  Transform3s(const Quatf& q_) : R(q_), T(Vec3s::Zero()) {}
86 
88  Transform3s(const Vec3s& T_) : R(Matrix3s::Identity()), T(T_) {}
89 
91  Transform3s(const Transform3s& tf) : R(tf.R), T(tf.T) {}
92 
95  R = tf.R;
96  T = tf.T;
97  return *this;
98  }
99 
101  inline const Vec3s& getTranslation() const { return T; }
102 
104  inline const Vec3s& translation() const { return T; }
105 
107  inline Vec3s& translation() { return T; }
108 
110  inline const Matrix3s& getRotation() const { return R; }
111 
113  inline const Matrix3s& rotation() const { return R; }
114 
116  inline Matrix3s& rotation() { return R; }
117 
119  inline Quatf getQuatRotation() const { return Quatf(R); }
120 
122  template <typename Matrix3Like, typename Vector3Like>
123  inline void setTransform(const Eigen::MatrixBase<Matrix3Like>& R_,
124  const Eigen::MatrixBase<Vector3Like>& T_) {
125  R.noalias() = R_;
126  T.noalias() = T_;
127  }
128 
130  inline void setTransform(const Quatf& q_, const Vec3s& T_) {
131  R = q_.toRotationMatrix();
132  T = T_;
133  }
134 
136  template <typename Derived>
137  inline void setRotation(const Eigen::MatrixBase<Derived>& R_) {
138  R.noalias() = R_;
139  }
140 
142  template <typename Derived>
143  inline void setTranslation(const Eigen::MatrixBase<Derived>& T_) {
144  T.noalias() = T_;
145  }
146 
148  inline void setQuatRotation(const Quatf& q_) { R = q_.toRotationMatrix(); }
149 
151  template <typename Derived>
152  inline Vec3s transform(const Eigen::MatrixBase<Derived>& v) const {
153  return R * v + T;
154  }
155 
157  template <typename Derived>
158  inline Vec3s inverseTransform(const Eigen::MatrixBase<Derived>& v) const {
159  return R.transpose() * (v - T);
160  }
161 
164  R.transposeInPlace();
165  T = -R * T;
166  return *this;
167  }
168 
170  inline Transform3s inverse() {
171  return Transform3s(R.transpose(), -R.transpose() * T);
172  }
173 
175  inline Transform3s inverseTimes(const Transform3s& other) const {
176  return Transform3s(R.transpose() * other.R, R.transpose() * (other.T - T));
177  }
178 
180  inline const Transform3s& operator*=(const Transform3s& other) {
181  T += R * other.T;
182  R *= other.R;
183  return *this;
184  }
185 
187  inline Transform3s operator*(const Transform3s& other) const {
188  return Transform3s(R * other.R, R * other.T + T);
189  }
190 
192  inline bool isIdentity(
193  const CoalScalar& prec =
194  Eigen::NumTraits<CoalScalar>::dummy_precision()) const {
195  return R.isIdentity(prec) && T.isZero(prec);
196  }
197 
199  inline void setIdentity() {
200  R.setIdentity();
201  T.setZero();
202  }
203 
205  static Transform3s Random() {
206  Transform3s tf = Transform3s();
207  tf.setRandom();
208  return tf;
209  }
210 
212  inline void setRandom();
213 
214  bool operator==(const Transform3s& other) const {
215  return (R == other.getRotation()) && (T == other.getTranslation());
216  }
217 
218  bool operator!=(const Transform3s& other) const { return !(*this == other); }
219 
220  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
221 };
222 
223 template <typename Derived>
224 inline Quatf fromAxisAngle(const Eigen::MatrixBase<Derived>& axis,
225  CoalScalar angle) {
226  return Quatf(Eigen::AngleAxis<CoalScalar>(angle, axis));
227 }
228 
232  // Rotational part
233  const CoalScalar u1 = (CoalScalar)rand() / RAND_MAX;
234  const CoalScalar u2 = (CoalScalar)rand() / RAND_MAX;
235  const CoalScalar u3 = (CoalScalar)rand() / RAND_MAX;
236 
237  const CoalScalar mult1 = std::sqrt(CoalScalar(1.0) - u1);
238  const CoalScalar mult2 = std::sqrt(u1);
239 
240  static const CoalScalar PI_value = static_cast<CoalScalar>(EIGEN_PI);
241  CoalScalar s2 = std::sin(2 * PI_value * u2);
242  CoalScalar c2 = std::cos(2 * PI_value * u2);
243  CoalScalar s3 = std::sin(2 * PI_value * u3);
244  CoalScalar c3 = std::cos(2 * PI_value * u3);
245 
246  Quatf q;
247  q.w() = mult1 * s2;
248  q.x() = mult1 * c2;
249  q.y() = mult2 * s3;
250  q.z() = mult2 * c3;
251  return q;
252 }
253 
254 inline void Transform3s::setRandom() {
255  const Quatf q = uniformRandomQuaternion();
256  this->rotation() = q.matrix();
257  this->translation().setRandom();
258 }
259 
263  Matrix3s basis = Matrix3s::Zero();
264  basis.col(2) = vec.normalized();
265  basis.col(1) = -vec.unitOrthogonal();
266  basis.col(0) = basis.col(1).cross(vec);
267  return basis;
268 }
269 
270 } // namespace coal
271 
272 #endif
coal::Transform3s::inverse
Transform3s inverse()
inverse transform
Definition: coal/math/transform.h:170
coal::Vec3s
Eigen::Matrix< CoalScalar, 3, 1 > Vec3s
Definition: coal/data_types.h:77
coal::Transform3s::setRandom
void setRandom()
set the transform to a random transform
Definition: coal/math/transform.h:254
coal::Transform3s::operator=
Transform3s & operator=(const Transform3s &tf)
operator =
Definition: coal/math/transform.h:94
coal::Transform3s::getQuatRotation
Quatf getQuatRotation() const
get quaternion
Definition: coal/math/transform.h:119
coal::Transform3s::Transform3s
Transform3s(const Matrix3s &R_)
Construct transform from rotation.
Definition: coal/math/transform.h:82
coal::Transform3s::Random
static Transform3s Random()
return a random transform
Definition: coal/math/transform.h:205
coal::Transform3s::R
Matrix3s R
Matrix cache.
Definition: coal/math/transform.h:57
coal::Transform3s::transform
Vec3s transform(const Eigen::MatrixBase< Derived > &v) const
transform a given vector by the transform
Definition: coal/math/transform.h:152
coal::Transform3s::operator*=
const Transform3s & operator*=(const Transform3s &other)
multiply with another transform
Definition: coal/math/transform.h:180
coal
Main namespace.
Definition: coal/broadphase/broadphase_bruteforce.h:44
vec
vec
coal::Quatf
Eigen::Quaternion< CoalScalar > Quatf
Definition: coal/math/transform.h:47
coal::uniformRandomQuaternion
Quatf uniformRandomQuaternion()
Uniformly random quaternion sphere. Code taken from Pinocchio (https://github.com/stack-of-tasks/pino...
Definition: coal/math/transform.h:231
coal::Transform3s::operator!=
bool operator!=(const Transform3s &other) const
Definition: coal/math/transform.h:218
R
R
coal::Transform3s::inverseTimes
Transform3s inverseTimes(const Transform3s &other) const
inverse the transform and multiply with another
Definition: coal/math/transform.h:175
coal::Transform3s::inverseTransform
Vec3s inverseTransform(const Eigen::MatrixBase< Derived > &v) const
transform a given vector by the inverse of the transform
Definition: coal/math/transform.h:158
coal::Transform3s
Simple transform class used locally by InterpMotion.
Definition: coal/math/transform.h:55
coal::operator<<
static std::ostream & operator<<(std::ostream &o, const Quatf &q)
Definition: coal/math/transform.h:49
coal::Transform3s::setQuatRotation
void setQuatRotation(const Quatf &q_)
set transform from rotation
Definition: coal/math/transform.h:148
coal::Transform3s::setTranslation
void setTranslation(const Eigen::MatrixBase< Derived > &T_)
set transform from translation
Definition: coal/math/transform.h:143
coal::Transform3s::translation
const Vec3s & translation() const
get translation
Definition: coal/math/transform.h:104
fwd.hh
coal::Transform3s::isIdentity
bool isIdentity(const CoalScalar &prec=Eigen::NumTraits< CoalScalar >::dummy_precision()) const
check whether the transform is identity
Definition: coal/math/transform.h:192
coal::Transform3s::Identity
static Transform3s Identity()
Definition: coal/math/transform.h:68
coal::Transform3s::T
Vec3s T
Translation vector.
Definition: coal/math/transform.h:60
coal::Transform3s::setIdentity
void setIdentity()
set the transform to be identity transform
Definition: coal/math/transform.h:199
coal::Transform3s::rotation
const Matrix3s & rotation() const
get rotation
Definition: coal/math/transform.h:113
axis
axis
q
q
coal::Transform3s::getRotation
const Matrix3s & getRotation() const
get rotation
Definition: coal/math/transform.h:110
coal::Transform3s::translation
Vec3s & translation()
get translation
Definition: coal/math/transform.h:107
coal::Transform3s::Transform3s
Transform3s(const Vec3s &T_)
Construct transform from translation.
Definition: coal/math/transform.h:88
coal::Transform3s::operator==
bool operator==(const Transform3s &other) const
Definition: coal/math/transform.h:214
coal::Quaternion3f
COAL_DEPRECATED typedef Eigen::Quaternion< CoalScalar > Quaternion3f
Definition: coal/math/transform.h:46
coal::Transform3s::Transform3s
Transform3s()
Default transform is no movement.
Definition: coal/math/transform.h:64
coal::Matrix3s
Eigen::Matrix< CoalScalar, 3, 3 > Matrix3s
Definition: coal/data_types.h:81
coal::Transform3s::setRotation
void setRotation(const Eigen::MatrixBase< Derived > &R_)
set transform from rotation
Definition: coal/math/transform.h:137
coal::Transform3s::operator*
Transform3s operator*(const Transform3s &other) const
multiply with another transform
Definition: coal/math/transform.h:187
coal::Transform3s::inverseInPlace
Transform3s & inverseInPlace()
inverse transform
Definition: coal/math/transform.h:163
coal::constructOrthonormalBasisFromVector
Matrix3s constructOrthonormalBasisFromVector(const Vec3s &vec)
Construct othonormal basis from vector. The z-axis is the normalized input vector.
Definition: coal/math/transform.h:262
coal::Transform3s::rotation
Matrix3s & rotation()
get rotation
Definition: coal/math/transform.h:116
coal::Transform3s::Transform3s
Transform3s(const Quatf &q_)
Construct transform from rotation.
Definition: coal/math/transform.h:85
coal::Transform3s::Transform3s
Transform3s(const Quatf &q_, const Eigen::MatrixBase< Vector3Like > &T_)
Construct transform from rotation and translation.
Definition: coal/math/transform.h:78
c2
c2
coal::Transform3s::Transform3s
Transform3s(const Eigen::MatrixBase< Matrixx3Like > &R_, const Eigen::MatrixBase< Vector3Like > &T_)
Construct transform from rotation and translation.
Definition: coal/math/transform.h:72
coal::Transform3s::setTransform
void setTransform(const Eigen::MatrixBase< Matrix3Like > &R_, const Eigen::MatrixBase< Vector3Like > &T_)
set transform from rotation and translation
Definition: coal/math/transform.h:123
coal::Transform3s::setTransform
void setTransform(const Quatf &q_, const Vec3s &T_)
set transform from rotation and translation
Definition: coal/math/transform.h:130
coal::Transform3s::Transform3s
Transform3s(const Transform3s &tf)
Construct transform from other transform.
Definition: coal/math/transform.h:91
data_types.h
coal::CoalScalar
double CoalScalar
Definition: coal/data_types.h:76
coal::fromAxisAngle
Quatf fromAxisAngle(const Eigen::MatrixBase< Derived > &axis, CoalScalar angle)
Definition: coal/math/transform.h:224
obb.v
list v
Definition: obb.py:48
coal::Transform3s::getTranslation
const Vec3s & getTranslation() const
get translation
Definition: coal/math/transform.h:101


hpp-fcl
Author(s):
autogenerated on Sat Nov 23 2024 03:44:59