6 #ifndef __pinocchio_se3_tpl_hpp__ 7 #define __pinocchio_se3_tpl_hpp__ 9 #include "pinocchio/spatial/fwd.hpp" 10 #include "pinocchio/spatial/se3-base.hpp" 12 #include "pinocchio/math/quaternion.hpp" 13 #include "pinocchio/math/rotation.hpp" 14 #include "pinocchio/spatial/cartesian-axis.hpp" 16 #include <Eigen/Geometry> 20 template<
typename _Scalar,
int _Options>
28 typedef _Scalar Scalar;
29 typedef Eigen::Matrix<Scalar,3,1,Options> Vector3;
30 typedef Eigen::Matrix<Scalar,4,1,Options> Vector4;
31 typedef Eigen::Matrix<Scalar,6,1,Options> Vector6;
32 typedef Eigen::Matrix<Scalar,3,3,Options> Matrix3;
33 typedef Eigen::Matrix<Scalar,4,4,Options> Matrix4;
34 typedef Eigen::Matrix<Scalar,6,6,Options> Matrix6;
35 typedef Matrix3 AngularType;
36 typedef typename PINOCCHIO_EIGEN_REF_TYPE(Matrix3) AngularRef;
37 typedef typename PINOCCHIO_EIGEN_REF_CONST_TYPE(Matrix3) ConstAngularRef;
38 typedef Vector3 LinearType;
39 typedef typename PINOCCHIO_EIGEN_REF_TYPE(Vector3) LinearRef;
40 typedef typename PINOCCHIO_EIGEN_REF_CONST_TYPE(Vector3) ConstLinearRef;
41 typedef Matrix6 ActionMatrixType;
42 typedef Matrix4 HomogeneousMatrixType;
46 template<
typename _Scalar,
int _Options>
49 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
50 PINOCCHIO_SE3_TYPEDEF_TPL(
SE3Tpl);
52 typedef Eigen::Quaternion<Scalar,Options> Quaternion;
60 using Base::translation;
62 SE3Tpl(): rot(), trans() {};
64 template<
typename QuaternionLike,
typename Vector3Like>
65 SE3Tpl(
const Eigen::QuaternionBase<QuaternionLike> & quat,
66 const Eigen::MatrixBase<Vector3Like> & trans)
67 : rot(quat.matrix()), trans(trans)
69 EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Vector3Like,3)
72 template<
typename Matrix3Like,
typename Vector3Like>
73 SE3Tpl(
const Eigen::MatrixBase<Matrix3Like> & R,
74 const Eigen::MatrixBase<Vector3Like> & trans)
75 : rot(R), trans(trans)
77 EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Vector3Like,3)
78 EIGEN_STATIC_ASSERT_MATRIX_SPECIFIC_SIZE(Matrix3Like,3,3)
81 template<
typename Matrix4Like>
82 explicit SE3Tpl(
const Eigen::MatrixBase<Matrix4Like> & m)
83 : rot(m.template block<3,3>(LINEAR,LINEAR))
84 , trans(m.template block<3,1>(LINEAR,ANGULAR))
86 EIGEN_STATIC_ASSERT_MATRIX_SPECIFIC_SIZE(Matrix4Like,4,4);
90 : rot(AngularType::Identity())
91 , trans(LinearType::Zero())
96 : rot(clone.rotation()),trans(clone.translation()) {}
101 rot = other.rotation();
102 trans = other.translation();
106 static SE3Tpl Identity()
111 SE3Tpl & setIdentity()
112 { rot.setIdentity (); trans.setZero ();
return *
this;}
117 return SE3Tpl(rot.transpose(), -rot.transpose()*trans);
120 static SE3Tpl Random()
122 return SE3Tpl().setRandom();
134 HomogeneousMatrixType toHomogeneousMatrix_impl()
const 136 HomogeneousMatrixType M;
137 M.template block<3,3>(LINEAR,LINEAR) = rot;
138 M.template block<3,1>(LINEAR,ANGULAR) = trans;
139 M.template block<1,3>(ANGULAR,LINEAR).setZero();
147 typedef Eigen::Block<ActionMatrixType,3,3> Block3;
149 M.template block<3,3>(ANGULAR,ANGULAR)
150 = M.template block<3,3>(LINEAR,LINEAR) = rot;
151 M.template block<3,3>(ANGULAR,LINEAR).setZero();
152 Block3 B = M.template block<3,3>(LINEAR,ANGULAR);
154 B.col(0) = trans.cross(rot.col(0));
155 B.col(1) = trans.cross(rot.col(1));
156 B.col(2) = trans.cross(rot.col(2));
160 ActionMatrixType toActionMatrixInverse_impl()
const 162 typedef Eigen::Block<ActionMatrixType,3,3> Block3;
164 M.template block<3,3>(ANGULAR,ANGULAR)
165 = M.template block<3,3>(LINEAR,LINEAR) = rot.transpose();
166 Block3 C = M.template block<3,3>(ANGULAR,LINEAR);
167 Block3 B = M.template block<3,3>(LINEAR,ANGULAR);
169 #define PINOCCHIO_INTERNAL_COMPUTATION(axis_id,v3_in,v3_out,R,res) \ 170 CartesianAxis<axis_id>::cross(v3_in,v3_out); \ 171 res.col(axis_id).noalias() = R.transpose() * v3_out; 173 PINOCCHIO_INTERNAL_COMPUTATION(0,trans,C.col(0),rot,B);
174 PINOCCHIO_INTERNAL_COMPUTATION(1,trans,C.col(0),rot,B);
175 PINOCCHIO_INTERNAL_COMPUTATION(2,trans,C.col(0),rot,B);
177 #undef PINOCCHIO_INTERNAL_COMPUTATION 183 ActionMatrixType toDualActionMatrix_impl()
const 185 typedef Eigen::Block<ActionMatrixType,3,3> Block3;
187 M.template block<3,3>(ANGULAR,ANGULAR)
188 = M.template block<3,3>(LINEAR,LINEAR) = rot;
189 M.template block<3,3>(LINEAR,ANGULAR).setZero();
190 Block3 B = M.template block<3,3>(ANGULAR,LINEAR);
192 B.col(0) = trans.cross(rot.col(0));
193 B.col(1) = trans.cross(rot.col(1));
194 B.col(2) = trans.cross(rot.col(2));
198 void disp_impl(std::ostream & os)
const 201 <<
" R =\n" << rot << std::endl
202 <<
" p = " << trans.transpose() << std::endl;
209 typename SE3GroupAction<D>::ReturnType
212 return d.se3Action(*
this);
216 template<
typename D>
typename SE3GroupAction<D>::ReturnType
219 return d.se3ActionInverse(*
this);
222 template<
typename EigenDerived>
223 typename EigenDerived::PlainObject
224 actOnEigenObject(
const Eigen::MatrixBase<EigenDerived> & p)
const 225 {
return (rotation()*p+translation()).eval(); }
227 template<
typename MapDerived>
228 Vector3 actOnEigenObject(
const Eigen::MapBase<MapDerived> & p)
const 229 {
return Vector3(rotation()*p+translation()); }
231 template<
typename EigenDerived>
232 typename EigenDerived::PlainObject
233 actInvOnEigenObject(
const Eigen::MatrixBase<EigenDerived> & p)
const 234 {
return (rotation().transpose()*(p-translation())).eval(); }
236 template<
typename MapDerived>
237 Vector3 actInvOnEigenObject(
const Eigen::MapBase<MapDerived> & p)
const 238 {
return Vector3(rotation().transpose()*(p-translation())); }
240 Vector3 act_impl(
const Vector3 & p)
const 241 {
return Vector3(rotation()*p+translation()); }
243 Vector3 actInv_impl(
const Vector3 & p)
const 244 {
return Vector3(rotation().transpose()*(p-translation())); }
248 {
return SE3Tpl(rot*m2.rotation()
249 ,translation()+rotation()*m2.translation());}
253 {
return SE3Tpl(rot.transpose()*m2.rotation(),
254 rot.transpose()*(m2.translation()-translation()));}
258 {
return this->act_impl(m2);}
263 return (rotation() == m2.rotation() && translation() == m2.translation());
268 const Scalar & prec = Eigen::NumTraits<Scalar>::dummy_precision())
const 270 return rotation().isApprox(m2.rotation(), prec)
271 && translation().isApprox(m2.translation(), prec);
274 bool isIdentity(
const Scalar & prec = Eigen::NumTraits<Scalar>::dummy_precision())
const 276 return rotation().isIdentity(prec) && translation().isZero(prec);
279 ConstAngularRef rotation_impl()
const {
return rot; }
280 AngularRef rotation_impl() {
return rot; }
281 void rotation_impl(
const AngularType & R) { rot = R; }
282 ConstLinearRef translation_impl()
const {
return trans;}
283 LinearRef translation_impl() {
return trans;}
284 void translation_impl(
const LinearType & p) { trans = p; }
287 template<
typename NewScalar>
291 ReturnType res(rot.template cast<NewScalar>(),
292 trans.template cast<NewScalar>());
296 internal::cast_call_normalize_method<SE3Tpl,NewScalar,Scalar>::run(res);
300 bool isNormalized(
const Scalar & prec = Eigen::NumTraits<Scalar>::dummy_precision())
const 310 PlainType normalized()
const 312 PlainType res(*
this); res.normalize();
327 template<
typename OtherScalar>
328 static SE3Tpl Interpolate(
const SE3Tpl & A,
const SE3Tpl & B,
const OtherScalar & alpha);
338 template<
typename Scalar,
int Options>
339 struct cast_call_normalize_method<SE3Tpl<Scalar,Options>,Scalar,Scalar>
342 static void run(T &) {}
345 template<
typename Scalar,
int Options,
typename NewScalar>
346 struct cast_call_normalize_method<SE3Tpl<Scalar,Options>,NewScalar,Scalar>
349 static void run(T &
self)
351 if(pinocchio::cast<NewScalar>(Eigen::NumTraits<Scalar>::epsilon()) > Eigen::NumTraits<NewScalar>::epsilon())
360 #endif // ifndef __pinocchio_se3_tpl_hpp__
SE3GroupAction< D >::ReturnType act_impl(const D &d) const
— GROUP ACTIONS ON M6, F6 and I6 —
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.
SE3GroupAction< D >::ReturnType actInv_impl(const D &d) const
by = aXb.actInv(ay)
bool isNormalized(const Eigen::MatrixBase< VectorLike > &vec, const typename VectorLike::RealScalar &prec=Eigen::NumTraits< typename VectorLike::Scalar >::dummy_precision())
Check whether the input vector is Normalized within the given precision.
Matrix3 orthogonalProjection(const Eigen::MatrixBase< Matrix3 > &mat)
Orthogonal projection of a matrix on the SO(3) manifold.
SE3Tpl< NewScalar, Options > cast() const
void uniformRandom(const Eigen::QuaternionBase< Derived > &q)
Uniformly random quaternion sphere.
Main pinocchio namespace.
Base class for rigid transformation.
ActionMatrixType toActionMatrix_impl() const
Vb.toVector() = bXa.toMatrix() * Va.toVector()
Common traits structure to fully define base classes for CRTP.
void normalize(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const Eigen::MatrixBase< ConfigVectorType > &qout)
Normalize a configuration vector.
SE3Tpl inverse() const
aXb = bXa.inverse()