spatial/se3-tpl.hpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2015-2021 CNRS INRIA
3 // Copyright (c) 2016 Wandercraft, 86 rue de Paris 91400 Orsay, France.
4 //
5 
6 #ifndef __pinocchio_spatial_se3_tpl_hpp__
7 #define __pinocchio_spatial_se3_tpl_hpp__
8 
11 
15 
16 #include <Eigen/Geometry>
17 
18 namespace pinocchio
19 {
20  template<typename _Scalar, int _Options>
21  struct traits<SE3Tpl<_Scalar, _Options>>
22  {
23  enum
24  {
25  Options = _Options,
26  LINEAR = 0,
27  ANGULAR = 3
28  };
29  typedef _Scalar Scalar;
30  typedef Eigen::Matrix<Scalar, 3, 1, Options> Vector3;
31  typedef Eigen::Matrix<Scalar, 4, 1, Options> Vector4;
32  typedef Eigen::Matrix<Scalar, 6, 1, Options> Vector6;
33  typedef Eigen::Matrix<Scalar, 3, 3, Options> Matrix3;
34  typedef Eigen::Matrix<Scalar, 4, 4, Options> Matrix4;
35  typedef Eigen::Matrix<Scalar, 6, 6, Options> Matrix6;
37  typedef typename PINOCCHIO_EIGEN_REF_TYPE(Matrix3) AngularRef;
38  typedef typename PINOCCHIO_EIGEN_REF_CONST_TYPE(Matrix3) ConstAngularRef;
40  typedef typename PINOCCHIO_EIGEN_REF_TYPE(Vector3) LinearRef;
41  typedef typename PINOCCHIO_EIGEN_REF_CONST_TYPE(Vector3) ConstLinearRef;
45  }; // traits SE3Tpl
46 
47  template<typename _Scalar, int _Options>
48  struct SE3Tpl : public SE3Base<SE3Tpl<_Scalar, _Options>>
49  {
50  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
51 
54  typedef Eigen::Quaternion<Scalar, Options> Quaternion;
55  typedef typename traits<SE3Tpl>::Vector3 Vector3;
56  typedef typename traits<SE3Tpl>::Matrix3 Matrix3;
57  typedef typename traits<SE3Tpl>::Matrix4 Matrix4;
58  typedef typename traits<SE3Tpl>::Vector4 Vector4;
59  typedef typename traits<SE3Tpl>::Matrix6 Matrix6;
60 
61  using Base::rotation;
62  using Base::translation;
63 
65  : rot()
66  , trans() {};
67 
68  template<typename QuaternionLike, typename Vector3Like>
70  const Eigen::QuaternionBase<QuaternionLike> & quat,
71  const Eigen::MatrixBase<Vector3Like> & trans)
72  : rot(quat.matrix())
73  , trans(trans)
74  {
75  EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Vector3Like, 3)
76  }
77 
78  template<typename Matrix3Like, typename Vector3Like>
79  SE3Tpl(const Eigen::MatrixBase<Matrix3Like> & R, const Eigen::MatrixBase<Vector3Like> & trans)
80  : rot(R)
81  , trans(trans){EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Vector3Like, 3)
82  EIGEN_STATIC_ASSERT_MATRIX_SPECIFIC_SIZE(Matrix3Like, 3, 3)}
83 
84  SE3Tpl(const SE3Tpl & other)
85  {
86  *this = other;
87  }
88 
89  template<typename S2, int O2>
90  explicit SE3Tpl(const SE3Tpl<S2, O2> & other)
91  {
92  *this = other.template cast<Scalar>();
93  }
94 
95  template<typename Matrix4Like>
96  explicit SE3Tpl(const Eigen::MatrixBase<Matrix4Like> & m)
97  : rot(m.template block<3, 3>(LINEAR, LINEAR))
98  , trans(m.template block<3, 1>(LINEAR, ANGULAR))
99  {
100  EIGEN_STATIC_ASSERT_MATRIX_SPECIFIC_SIZE(Matrix4Like, 4, 4);
101  }
102 
103  explicit SE3Tpl(int)
104  : rot(AngularType::Identity())
105  , trans(LinearType::Zero())
106  {
107  }
108 
109  template<int O2>
111  : rot(clone.rotation())
112  , trans(clone.translation())
113  {
114  }
115 
116  template<int O2>
118  {
119  rot = other.rotation();
120  trans = other.translation();
121  return *this;
122  }
123 
129  SE3Tpl & operator=(const SE3Tpl & other)
130  {
131  rot = other.rotation();
132  trans = other.translation();
133  return *this;
134  }
135 
136  static SE3Tpl Identity()
137  {
138  return SE3Tpl(1);
139  }
140 
142  {
143  rot.setIdentity();
144  trans.setZero();
145  return *this;
146  }
147 
149  SE3Tpl inverse() const
150  {
151  return SE3Tpl(rot.transpose(), -rot.transpose() * trans);
152  }
153 
154  static SE3Tpl Random()
155  {
156  return SE3Tpl().setRandom();
157  }
158 
160  {
161  Quaternion q;
163  rot = q.matrix();
164  trans.setRandom();
165 
166  return *this;
167  }
168 
169  HomogeneousMatrixType toHomogeneousMatrix_impl() const
170  {
171  HomogeneousMatrixType M;
172  M.template block<3, 3>(LINEAR, LINEAR) = rot;
173  M.template block<3, 1>(LINEAR, ANGULAR) = trans;
174  M.template block<1, 3>(ANGULAR, LINEAR).setZero();
175  M(3, 3) = 1;
176  return M;
177  }
178 
180  template<typename Matrix6Like>
181  void toActionMatrix_impl(const Eigen::MatrixBase<Matrix6Like> & action_matrix) const
182  {
183  typedef Eigen::Block<Matrix6Like, 3, 3> Block3;
184 
185  Matrix6Like & M = action_matrix.const_cast_derived();
186  M.template block<3, 3>(ANGULAR, ANGULAR) = M.template block<3, 3>(LINEAR, LINEAR) = rot;
187  M.template block<3, 3>(ANGULAR, LINEAR).setZero();
188  Block3 B = M.template block<3, 3>(LINEAR, ANGULAR);
189 
190  B.col(0) = trans.cross(rot.col(0));
191  B.col(1) = trans.cross(rot.col(1));
192  B.col(2) = trans.cross(rot.col(2));
193  }
194 
195  ActionMatrixType toActionMatrix_impl() const
196  {
197  ActionMatrixType res;
199  return res;
200  }
201 
202  template<typename Matrix6Like>
203  void
204  toActionMatrixInverse_impl(const Eigen::MatrixBase<Matrix6Like> & action_matrix_inverse) const
205  {
206  typedef Eigen::Block<Matrix6Like, 3, 3> Block3;
207 
208  Matrix6Like & M = action_matrix_inverse.const_cast_derived();
209  M.template block<3, 3>(ANGULAR, ANGULAR) = M.template block<3, 3>(LINEAR, LINEAR) =
210  rot.transpose();
211  Block3 C = M.template block<3, 3>(ANGULAR, LINEAR); // used as temporary
212  Block3 B = M.template block<3, 3>(LINEAR, ANGULAR);
213 
214 #define PINOCCHIO_INTERNAL_COMPUTATION(axis_id, v3_in, v3_out, R, res) \
215  CartesianAxis<axis_id>::cross(v3_in, v3_out); \
216  res.col(axis_id).noalias() = R.transpose() * v3_out;
217 
221 
222 #undef PINOCCHIO_INTERNAL_COMPUTATION
223 
224  C.setZero();
225  }
226 
227  ActionMatrixType toActionMatrixInverse_impl() const
228  {
229  ActionMatrixType res;
231  return res;
232  }
233 
234  template<typename Matrix6Like>
235  void toDualActionMatrix_impl(const Eigen::MatrixBase<Matrix6Like> & dual_action_matrix) const
236  {
237  typedef Eigen::Block<Matrix6Like, 3, 3> Block3;
238 
239  Matrix6Like & M = dual_action_matrix.const_cast_derived();
240  M.template block<3, 3>(ANGULAR, ANGULAR) = M.template block<3, 3>(LINEAR, LINEAR) = rot;
241  M.template block<3, 3>(LINEAR, ANGULAR).setZero();
242  Block3 B = M.template block<3, 3>(ANGULAR, LINEAR);
243 
244  B.col(0) = trans.cross(rot.col(0));
245  B.col(1) = trans.cross(rot.col(1));
246  B.col(2) = trans.cross(rot.col(2));
247  }
248 
249  ActionMatrixType toDualActionMatrix_impl() const
250  {
251  ActionMatrixType res;
253  return res;
254  }
255 
256  void disp_impl(std::ostream & os) const
257  {
258  os << " R =\n" << rot << std::endl << " p = " << trans.transpose() << std::endl;
259  }
260 
262 
264  template<typename D>
265  typename SE3GroupAction<D>::ReturnType act_impl(const D & d) const
266  {
267  return d.se3Action(*this);
268  }
269 
271  template<typename D>
272  typename SE3GroupAction<D>::ReturnType actInv_impl(const D & d) const
273  {
274  return d.se3ActionInverse(*this);
275  }
276 
277  template<typename EigenDerived>
278  typename EigenDerived::PlainObject
279  actOnEigenObject(const Eigen::MatrixBase<EigenDerived> & p) const
280  {
281  return (rotation() * p + translation()).eval();
282  }
283 
284  template<typename MapDerived>
285  Vector3 actOnEigenObject(const Eigen::MapBase<MapDerived> & p) const
286  {
287  return Vector3(rotation() * p + translation());
288  }
289 
290  template<typename EigenDerived>
291  typename EigenDerived::PlainObject
292  actInvOnEigenObject(const Eigen::MatrixBase<EigenDerived> & p) const
293  {
294  return (rotation().transpose() * (p - translation())).eval();
295  }
296 
297  template<typename MapDerived>
298  Vector3 actInvOnEigenObject(const Eigen::MapBase<MapDerived> & p) const
299  {
300  return Vector3(rotation().transpose() * (p - translation()));
301  }
302 
303  Vector3 act_impl(const Vector3 & p) const
304  {
305  return Vector3(rotation() * p + translation());
306  }
307 
308  Vector3 actInv_impl(const Vector3 & p) const
309  {
310  return Vector3(rotation().transpose() * (p - translation()));
311  }
312 
313  template<int O2>
315  {
316  return SE3Tpl(rot * m2.rotation(), translation() + rotation() * m2.translation());
317  }
318 
319  template<int O2>
321  {
322  return SE3Tpl(
323  rot.transpose() * m2.rotation(), rot.transpose() * (m2.translation() - translation()));
324  }
325 
326  template<int O2>
328  {
329  return this->act_impl(m2);
330  }
331 
332  template<int O2>
333  bool isEqual(const SE3Tpl<Scalar, O2> & m2) const
334  {
335  return (rotation() == m2.rotation() && translation() == m2.translation());
336  }
337 
338  template<int O2>
340  const SE3Tpl<Scalar, O2> & m2,
341  const Scalar & prec = Eigen::NumTraits<Scalar>::dummy_precision()) const
342  {
343  return rotation().isApprox(m2.rotation(), prec)
344  && translation().isApprox(m2.translation(), prec);
345  }
346 
347  bool isIdentity(const Scalar & prec = Eigen::NumTraits<Scalar>::dummy_precision()) const
348  {
349  return rotation().isIdentity(prec) && translation().isZero(prec);
350  }
351 
352  ConstAngularRef rotation_impl() const
353  {
354  return rot;
355  }
356  AngularRef rotation_impl()
357  {
358  return rot;
359  }
360  void rotation_impl(const AngularType & R)
361  {
362  rot = R;
363  }
364  ConstLinearRef translation_impl() const
365  {
366  return trans;
367  }
368  LinearRef translation_impl()
369  {
370  return trans;
371  }
372  void translation_impl(const LinearType & p)
373  {
374  trans = p;
375  }
376 
378  template<typename NewScalar>
380  {
381  typedef SE3Tpl<NewScalar, Options> ReturnType;
382  ReturnType res(rot.template cast<NewScalar>(), trans.template cast<NewScalar>());
383 
384  // During the cast, it may appear that the matrix is not normalized correctly.
385  // Force the normalization of the rotation part of the matrix.
387  return res;
388  }
389 
390  bool isNormalized(const Scalar & prec = Eigen::NumTraits<Scalar>::dummy_precision()) const
391  {
392  return isUnitary(rot, prec);
393  }
394 
395  void normalize()
396  {
397  rot = orthogonalProjection(rot);
398  }
399 
400  PlainType normalized() const
401  {
402  PlainType res(*this);
403  res.normalize();
404  return res;
405  }
406 
419  template<typename OtherScalar>
420  static SE3Tpl Interpolate(const SE3Tpl & A, const SE3Tpl & B, const OtherScalar & alpha);
421 
422  protected:
423  AngularType rot;
424  LinearType trans;
425 
426  }; // class SE3Tpl
427 
428  namespace internal
429  {
430  template<typename Scalar, int Options>
432  {
433  template<typename T>
434  static void run(T &)
435  {
436  }
437  };
438 
439  template<typename Scalar, int Options, typename NewScalar>
441  {
442  template<typename T>
443  static void run(T & self)
444  {
445  if (
446  pinocchio::cast<NewScalar>(Eigen::NumTraits<Scalar>::epsilon())
447  > Eigen::NumTraits<NewScalar>::epsilon())
448  self.normalize();
449  }
450  };
451 
452  } // namespace internal
453 
454 } // namespace pinocchio
455 
456 #endif // ifndef __pinocchio_spatial_se3_tpl_hpp__
simulation-contact-dynamics.T
int T
Definition: simulation-contact-dynamics.py:94
pinocchio::SE3Tpl::actOnEigenObject
Vector3 actOnEigenObject(const Eigen::MapBase< MapDerived > &p) const
Definition: spatial/se3-tpl.hpp:285
pinocchio::SE3Tpl::Matrix4
traits< SE3Tpl >::Matrix4 Matrix4
Definition: spatial/se3-tpl.hpp:57
m
float m
pinocchio::SE3Tpl::Base
SE3Base< SE3Tpl< _Scalar, _Options > > Base
Definition: spatial/se3-tpl.hpp:53
pinocchio::SE3Tpl::act_impl
SE3Tpl act_impl(const SE3Tpl< Scalar, O2 > &m2) const
Definition: spatial/se3-tpl.hpp:314
pinocchio::SE3Tpl::disp_impl
void disp_impl(std::ostream &os) const
Definition: spatial/se3-tpl.hpp:256
quaternion.hpp
fwd.hpp
pinocchio::SE3Tpl::act_impl
SE3GroupAction< D >::ReturnType act_impl(const D &d) const
— GROUP ACTIONS ON M6, F6 and I6 —
Definition: spatial/se3-tpl.hpp:265
pinocchio::SE3Tpl::Vector3
traits< SE3Tpl >::Vector3 Vector3
Definition: spatial/se3-tpl.hpp:55
pinocchio::SE3Tpl::act_impl
Vector3 act_impl(const Vector3 &p) const
Definition: spatial/se3-tpl.hpp:303
pinocchio::SE3Tpl::inverse
SE3Tpl inverse() const
aXb = bXa.inverse()
Definition: spatial/se3-tpl.hpp:149
pinocchio::traits< SE3Tpl< _Scalar, _Options > >::Vector6
Eigen::Matrix< Scalar, 6, 1, Options > Vector6
Definition: spatial/se3-tpl.hpp:32
omniidl_be_python_with_docstring.run
def run(tree, args)
Definition: cmake/hpp/idl/omniidl_be_python_with_docstring.py:140
pinocchio::quaternion::uniformRandom
void uniformRandom(Eigen::QuaternionBase< Derived > &q)
Uniformly random quaternion sphere.
Definition: math/quaternion.hpp:114
rotation.hpp
pinocchio::isUnitary
bool isUnitary(const Eigen::MatrixBase< MatrixLike > &mat, const typename MatrixLike::RealScalar &prec=Eigen::NumTraits< typename MatrixLike::Scalar >::dummy_precision())
Check whether the input matrix is Unitary within the given precision.
Definition: math/matrix.hpp:155
pinocchio::SE3Tpl::toActionMatrix_impl
ActionMatrixType toActionMatrix_impl() const
Definition: spatial/se3-tpl.hpp:195
pinocchio::SE3Tpl::setRandom
SE3Tpl & setRandom()
Definition: spatial/se3-tpl.hpp:159
quat
quat
pinocchio::Options
Options
Definition: joint-configuration.hpp:1116
pinocchio::SE3Tpl
Definition: context/casadi.hpp:29
pinocchio::SE3GroupAction::ReturnType
D ReturnType
Definition: spatial/se3.hpp:41
pinocchio::SE3Tpl::toActionMatrix_impl
void toActionMatrix_impl(const Eigen::MatrixBase< Matrix6Like > &action_matrix) const
Vb.toVector() = bXa.toMatrix() * Va.toVector()
Definition: spatial/se3-tpl.hpp:181
pinocchio::SE3Tpl::Matrix6
traits< SE3Tpl >::Matrix6 Matrix6
Definition: spatial/se3-tpl.hpp:59
pinocchio::traits< SE3Tpl< _Scalar, _Options > >::Vector3
Eigen::Matrix< Scalar, 3, 1, Options > Vector3
Definition: spatial/se3-tpl.hpp:30
pinocchio::PINOCCHIO_EIGEN_REF_CONST_TYPE
PINOCCHIO_EIGEN_REF_CONST_TYPE(Matrix6Like) operator*(const Eigen
Definition: joint-free-flyer.hpp:144
pinocchio::SE3Tpl::isNormalized
bool isNormalized(const Scalar &prec=Eigen::NumTraits< Scalar >::dummy_precision()) const
Definition: spatial/se3-tpl.hpp:390
simulation-closed-kinematic-chains.rotation
rotation
Definition: simulation-closed-kinematic-chains.py:24
pinocchio::SE3Tpl::rotation_impl
void rotation_impl(const AngularType &R)
Definition: spatial/se3-tpl.hpp:360
pinocchio::python::Scalar
context::Scalar Scalar
Definition: admm-solver.cpp:29
pinocchio::SE3Tpl::SE3Tpl
SE3Tpl()
Definition: spatial/se3-tpl.hpp:64
pinocchio::traits< SE3Tpl< _Scalar, _Options > >::Scalar
_Scalar Scalar
Definition: spatial/se3-tpl.hpp:29
pinocchio::SE3Tpl::rotation_impl
AngularRef rotation_impl()
Definition: spatial/se3-tpl.hpp:356
pinocchio::res
ReturnType res
Definition: spatial/classic-acceleration.hpp:57
PINOCCHIO_INTERNAL_COMPUTATION
#define PINOCCHIO_INTERNAL_COMPUTATION(axis_id, v3_in, v3_out, R, res)
R
R
pinocchio::SE3Tpl::translation_impl
ConstLinearRef translation_impl() const
Definition: spatial/se3-tpl.hpp:364
pinocchio::SE3Tpl::Interpolate
static SE3Tpl Interpolate(const SE3Tpl &A, const SE3Tpl &B, const OtherScalar &alpha)
Linear interpolation on the SE3 manifold.
pinocchio::SE3Tpl::translation_impl
void translation_impl(const LinearType &p)
Definition: spatial/se3-tpl.hpp:372
pinocchio::traits< SE3Tpl< _Scalar, _Options > >::ActionMatrixType
Matrix6 ActionMatrixType
Definition: spatial/se3-tpl.hpp:42
pinocchio::SE3Tpl::isEqual
bool isEqual(const SE3Tpl< Scalar, O2 > &m2) const
Definition: spatial/se3-tpl.hpp:333
pinocchio::traits< SE3Tpl< _Scalar, _Options > >::Matrix3
Eigen::Matrix< Scalar, 3, 3, Options > Matrix3
Definition: spatial/se3-tpl.hpp:33
B
B
pinocchio::SE3Base::translation
ConstLinearRef translation() const
Definition: se3-base.hpp:52
pinocchio::SE3Tpl::Matrix3
traits< SE3Tpl >::Matrix3 Matrix3
Definition: spatial/se3-tpl.hpp:56
pinocchio::SE3Tpl::translation
ConstLinearRef translation() const
Definition: se3-base.hpp:52
pinocchio::SE3Tpl::SE3Tpl
SE3Tpl(const SE3Tpl< Scalar, O2 > &clone)
Definition: spatial/se3-tpl.hpp:110
pinocchio::traits< SE3Tpl< _Scalar, _Options > >::Matrix6
Eigen::Matrix< Scalar, 6, 6, Options > Matrix6
Definition: spatial/se3-tpl.hpp:35
dpendulum.p
p
Definition: dpendulum.py:6
pinocchio::SE3Tpl::SE3Tpl
SE3Tpl(const SE3Tpl &other)
Definition: spatial/se3-tpl.hpp:84
pinocchio::SE3Tpl::translation_impl
LinearRef translation_impl()
Definition: spatial/se3-tpl.hpp:368
dcrba.C
C
Definition: dcrba.py:469
reachable-workspace-with-collisions.alpha
float alpha
Definition: reachable-workspace-with-collisions.py:159
cartesian-axis.hpp
pinocchio::traits< SE3Tpl< _Scalar, _Options > >::Matrix4
Eigen::Matrix< Scalar, 4, 4, Options > Matrix4
Definition: spatial/se3-tpl.hpp:34
pinocchio::SE3Tpl::Vector4
traits< SE3Tpl >::Vector4 Vector4
Definition: spatial/se3-tpl.hpp:58
pinocchio::SE3Tpl::toActionMatrixInverse_impl
void toActionMatrixInverse_impl(const Eigen::MatrixBase< Matrix6Like > &action_matrix_inverse) const
Definition: spatial/se3-tpl.hpp:204
pinocchio::SE3Tpl::rotation
ConstAngularRef rotation() const
Definition: se3-base.hpp:48
se3-base.hpp
pinocchio::SE3Tpl::SE3Tpl
SE3Tpl(const SE3Tpl< S2, O2 > &other)
Definition: spatial/se3-tpl.hpp:90
pinocchio::SE3Tpl::isApprox_impl
bool isApprox_impl(const SE3Tpl< Scalar, O2 > &m2, const Scalar &prec=Eigen::NumTraits< Scalar >::dummy_precision()) const
Definition: spatial/se3-tpl.hpp:339
pinocchio::SE3Tpl::isIdentity
bool isIdentity(const Scalar &prec=Eigen::NumTraits< Scalar >::dummy_precision()) const
Definition: spatial/se3-tpl.hpp:347
simulation-contact-dynamics.A
A
Definition: simulation-contact-dynamics.py:115
pinocchio::SE3Tpl::operator=
SE3Tpl & operator=(const SE3Tpl< Scalar, O2 > &other)
Definition: spatial/se3-tpl.hpp:117
M
M
pinocchio::SE3Tpl::SE3Tpl
SE3Tpl(const Eigen::QuaternionBase< QuaternionLike > &quat, const Eigen::MatrixBase< Vector3Like > &trans)
Definition: spatial/se3-tpl.hpp:69
pinocchio::SE3Tpl::rot
AngularType rot
Definition: spatial/se3-tpl.hpp:423
pinocchio::SE3Tpl::toDualActionMatrix_impl
void toDualActionMatrix_impl(const Eigen::MatrixBase< Matrix6Like > &dual_action_matrix) const
Definition: spatial/se3-tpl.hpp:235
pinocchio::q
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > & q
Definition: joint-configuration.hpp:1117
pinocchio::SE3Tpl::actInvOnEigenObject
Vector3 actInvOnEigenObject(const Eigen::MapBase< MapDerived > &p) const
Definition: spatial/se3-tpl.hpp:298
pinocchio::SE3Tpl::normalized
PlainType normalized() const
Definition: spatial/se3-tpl.hpp:400
pinocchio::SE3Tpl::actInvOnEigenObject
EigenDerived::PlainObject actInvOnEigenObject(const Eigen::MatrixBase< EigenDerived > &p) const
Definition: spatial/se3-tpl.hpp:292
clone
virtual CollisionGeometry * clone() const=0
pinocchio::SE3Tpl::operator=
SE3Tpl & operator=(const SE3Tpl &other)
Copy assignment operator.
Definition: spatial/se3-tpl.hpp:129
pinocchio::SE3Tpl::Quaternion
Eigen::Quaternion< Scalar, Options > Quaternion
Definition: spatial/se3-tpl.hpp:54
pinocchio::traits< SE3Tpl< _Scalar, _Options > >::PlainType
SE3Tpl< Scalar, Options > PlainType
Definition: spatial/se3-tpl.hpp:44
pinocchio::SE3Tpl::cast
SE3Tpl< NewScalar, Options > cast() const
Definition: spatial/se3-tpl.hpp:379
pinocchio::SE3Tpl::actOnEigenObject
EigenDerived::PlainObject actOnEigenObject(const Eigen::MatrixBase< EigenDerived > &p) const
Definition: spatial/se3-tpl.hpp:279
pinocchio::SE3Base
Base class for rigid transformation.
Definition: se3-base.hpp:30
pinocchio::SE3Tpl::Random
static SE3Tpl Random()
Definition: spatial/se3-tpl.hpp:154
collision-with-point-clouds.translation
translation
Definition: collision-with-point-clouds.py:32
pinocchio::SE3Tpl::toHomogeneousMatrix_impl
HomogeneousMatrixType toHomogeneousMatrix_impl() const
Definition: spatial/se3-tpl.hpp:169
pinocchio::SE3Tpl::Identity
static SE3Tpl Identity()
Definition: spatial/se3-tpl.hpp:136
pinocchio::SE3Tpl::actInv_impl
Vector3 actInv_impl(const Vector3 &p) const
Definition: spatial/se3-tpl.hpp:308
pinocchio::SE3Tpl::SE3Tpl
SE3Tpl(const Eigen::MatrixBase< Matrix3Like > &R, const Eigen::MatrixBase< Vector3Like > &trans)
Definition: spatial/se3-tpl.hpp:79
pinocchio::SE3Base::rotation
ConstAngularRef rotation() const
Definition: se3-base.hpp:48
pinocchio::SE3Tpl::SE3Tpl
SE3Tpl(int)
Definition: spatial/se3-tpl.hpp:103
pinocchio::traits
Common traits structure to fully define base classes for CRTP.
Definition: fwd.hpp:71
pinocchio::SE3Tpl::PINOCCHIO_SE3_TYPEDEF_TPL
EIGEN_MAKE_ALIGNED_OPERATOR_NEW PINOCCHIO_SE3_TYPEDEF_TPL(SE3Tpl)
pinocchio::traits< SE3Tpl< _Scalar, _Options > >::LinearType
Vector3 LinearType
Definition: spatial/se3-tpl.hpp:39
pinocchio::SE3Tpl::trans
LinearType trans
Definition: spatial/se3-tpl.hpp:424
pinocchio::SE3Tpl::toActionMatrixInverse_impl
ActionMatrixType toActionMatrixInverse_impl() const
Definition: spatial/se3-tpl.hpp:227
PINOCCHIO_EIGEN_REF_TYPE
#define PINOCCHIO_EIGEN_REF_TYPE(D)
Definition: eigen-macros.hpp:32
pinocchio::internal::cast_call_normalize_method
Definition: context/casadi.hpp:43
pinocchio::SE3Tpl::SE3Tpl
SE3Tpl(const Eigen::MatrixBase< Matrix4Like > &m)
Definition: spatial/se3-tpl.hpp:96
pinocchio::SE3Tpl::__mult__
SE3Tpl __mult__(const SE3Tpl< Scalar, O2 > &m2) const
Definition: spatial/se3-tpl.hpp:327
pinocchio::SE3Tpl::normalize
void normalize()
Definition: spatial/se3-tpl.hpp:395
pinocchio::SE3Tpl::setIdentity
SE3Tpl & setIdentity()
Definition: spatial/se3-tpl.hpp:141
pinocchio::internal::cast_call_normalize_method< SE3Tpl< Scalar, Options >, NewScalar, Scalar >::run
static void run(T &self)
Definition: spatial/se3-tpl.hpp:443
d
FCL_REAL d
pinocchio::SE3Tpl::rotation_impl
ConstAngularRef rotation_impl() const
Definition: spatial/se3-tpl.hpp:352
pinocchio::SE3Tpl::actInv_impl
SE3Tpl actInv_impl(const SE3Tpl< Scalar, O2 > &m2) const
Definition: spatial/se3-tpl.hpp:320
pinocchio::SE3Tpl::actInv_impl
SE3GroupAction< D >::ReturnType actInv_impl(const D &d) const
by = aXb.actInv(ay)
Definition: spatial/se3-tpl.hpp:272
pinocchio::internal::cast_call_normalize_method< SE3Tpl< Scalar, Options >, Scalar, Scalar >::run
static void run(T &)
Definition: spatial/se3-tpl.hpp:434
pinocchio::SE3Tpl::toDualActionMatrix_impl
ActionMatrixType toDualActionMatrix_impl() const
Definition: spatial/se3-tpl.hpp:249
pinocchio::traits< SE3Tpl< _Scalar, _Options > >::AngularType
Matrix3 AngularType
Definition: spatial/se3-tpl.hpp:36
pinocchio
Main pinocchio namespace.
Definition: timings.cpp:27
pinocchio::traits< SE3Tpl< _Scalar, _Options > >::Vector4
Eigen::Matrix< Scalar, 4, 1, Options > Vector4
Definition: spatial/se3-tpl.hpp:31
pinocchio::traits< SE3Tpl< _Scalar, _Options > >::HomogeneousMatrixType
Matrix4 HomogeneousMatrixType
Definition: spatial/se3-tpl.hpp:43


pinocchio
Author(s):
autogenerated on Sat Jun 1 2024 02:40:38