6 #ifndef __pinocchio_spatial_se3_tpl_hpp__
7 #define __pinocchio_spatial_se3_tpl_hpp__
16 #include <Eigen/Geometry>
20 template<
typename _Scalar,
int _Options>
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;
47 template<
typename _Scalar,
int _Options>
50 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
68 template<
typename QuaternionLike,
typename Vector3Like>
70 const Eigen::QuaternionBase<QuaternionLike> & quat,
71 const Eigen::MatrixBase<Vector3Like> &
trans)
75 EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Vector3Like, 3)
78 template<
typename Matrix3Like,
typename Vector3Like>
79 SE3Tpl(
const Eigen::MatrixBase<Matrix3Like> & R,
const Eigen::MatrixBase<Vector3Like> &
trans)
81 ,
trans(
trans){EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Vector3Like, 3)
82 EIGEN_STATIC_ASSERT_MATRIX_SPECIFIC_SIZE(Matrix3Like, 3, 3)}
89 template<
typename S2,
int O2>
92 *
this = other.template cast<Scalar>();
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))
100 EIGEN_STATIC_ASSERT_MATRIX_SPECIFIC_SIZE(Matrix4Like, 4, 4);
105 ,
trans(LinearType::Zero())
156 return SE3Tpl().setRandom();
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();
180 template<
typename Matrix6Like>
183 typedef Eigen::Block<Matrix6Like, 3, 3> Block3;
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);
197 ActionMatrixType
res;
202 template<
typename Matrix6Like>
206 typedef Eigen::Block<Matrix6Like, 3, 3> Block3;
208 Matrix6Like &
M = action_matrix_inverse.const_cast_derived();
209 M.template block<3, 3>(ANGULAR, ANGULAR) =
M.template block<3, 3>(LINEAR, LINEAR) =
211 Block3
C =
M.template block<3, 3>(ANGULAR, LINEAR);
212 Block3
B =
M.template block<3, 3>(LINEAR, ANGULAR);
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;
222 #undef PINOCCHIO_INTERNAL_COMPUTATION
229 ActionMatrixType
res;
234 template<
typename Matrix6Like>
237 typedef Eigen::Block<Matrix6Like, 3, 3> Block3;
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);
251 ActionMatrixType
res;
258 os <<
" R =\n" <<
rot << std::endl <<
" p = " <<
trans.transpose() << std::endl;
267 return d.se3Action(*
this);
274 return d.se3ActionInverse(*
this);
277 template<
typename EigenDerived>
278 typename EigenDerived::PlainObject
284 template<
typename MapDerived>
290 template<
typename EigenDerived>
291 typename EigenDerived::PlainObject
297 template<
typename MapDerived>
341 const Scalar & prec = Eigen::NumTraits<Scalar>::dummy_precision())
const
378 template<
typename NewScalar>
382 ReturnType
res(
rot.template cast<NewScalar>(),
trans.template cast<NewScalar>());
397 rot = orthogonalProjection(
rot);
402 PlainType
res(*
this);
419 template<
typename OtherScalar>
430 template<
typename Scalar,
int Options>
439 template<
typename Scalar,
int Options,
typename NewScalar>
446 pinocchio::cast<NewScalar>(Eigen::NumTraits<Scalar>::epsilon())
447 > Eigen::NumTraits<NewScalar>::epsilon())
456 #endif // ifndef __pinocchio_spatial_se3_tpl_hpp__