6 #ifndef __pinocchio_joint_translation_hpp__ 7 #define __pinocchio_joint_translation_hpp__ 9 #include "pinocchio/macros.hpp" 10 #include "pinocchio/multibody/joint/joint-base.hpp" 11 #include "pinocchio/multibody/constraint.hpp" 12 #include "pinocchio/spatial/inertia.hpp" 13 #include "pinocchio/spatial/skew.hpp" 21 template<
typename Scalar,
int Options>
27 template<
typename Scalar,
int Options,
typename MotionDerived>
33 template<
typename _Scalar,
int _Options>
38 typedef Eigen::Matrix<Scalar,3,1,Options>
Vector3;
39 typedef Eigen::Matrix<Scalar,6,1,Options>
Vector6;
40 typedef Eigen::Matrix<Scalar,4,4,Options>
Matrix4;
41 typedef Eigen::Matrix<Scalar,6,6,Options>
Matrix6;
58 template<
typename _Scalar,
int _Options>
60 :
MotionBase< MotionTranslationTpl<_Scalar,_Options> >
62 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
68 template<
typename Vector3Like>
80 inline PlainReturnType
plain()
const 82 return PlainReturnType(m_v,PlainReturnType::Vector3::Zero());
87 return m_v == other.
m_v;
96 template<
typename Derived>
102 template<
typename Derived>
109 template<
typename S2,
int O2,
typename D2>
116 template<
typename S2,
int O2>
120 se3Action_impl(m,res);
124 template<
typename S2,
int O2,
typename D2>
134 template<
typename S2,
int O2>
138 se3ActionInverse_impl(m,res);
142 template<
typename M1,
typename M2>
152 template<
typename M1>
160 const Vector3 &
linear()
const {
return m_v; }
169 template<
typename S1,
int O1,
typename MotionDerived>
170 inline typename MotionDerived::MotionPlain
179 template<
typename _Scalar,
int _Options>
189 typedef Eigen::Matrix<Scalar,3,1,Options>
Vector3;
190 typedef Eigen::Matrix<Scalar,3,3,Options>
Matrix3;
201 template<
typename Scalar,
int Options>
205 template<
typename _Scalar,
int _Options>
207 :
SE3Base< TransformTranslationTpl<_Scalar,_Options> >
209 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
215 template<
typename Vector3Like>
217 : m_translation(translation)
222 PlainType
res(PlainType::Identity());
223 res.rotation().setIdentity();
229 operator PlainType()
const {
return plain(); }
231 template<
typename S2,
int O2>
245 AngularType
rotation()
const {
return AngularType(3,3); }
259 template<
typename _Scalar,
int _Options>
265 enum { LINEAR = 0, ANGULAR = 3 };
275 template<
typename _Scalar,
int _Options>
279 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
291 template<
typename Vector3Like>
292 JointMotion
__mult__(
const Eigen::MatrixBase<Vector3Like> &
v)
const 294 EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Vector3Like,3);
295 return JointMotion(v);
305 template<
typename Derived>
313 template<
typename MatrixDerived>
315 operator*(
const Eigen::MatrixBase<MatrixDerived> & F)
const 318 return F.derived().template middleRows<3>(LINEAR);
328 S.template middleRows<3>(LINEAR).setIdentity();
329 S.template middleRows<3>(ANGULAR).
setZero();
333 template<
typename S1,
int O1>
336 Eigen::Matrix<S1,6,3,O1>
M;
337 M.template middleRows<3>(LINEAR) = m.
rotation();
338 M.template middleRows<3>(ANGULAR).
setZero();
343 template<
typename S1,
int O1>
346 Eigen::Matrix<S1,6,3,O1>
M;
347 M.template middleRows<3>(LINEAR) = m.
rotation().transpose();
348 M.template middleRows<3>(ANGULAR).
setZero();
353 template<
typename MotionDerived>
356 const typename MotionDerived::ConstAngularType
w = m.
angular();
359 skew(w,res.template middleRows<3>(LINEAR));
360 res.template middleRows<3>(ANGULAR).
setZero();
369 template<
typename MotionDerived,
typename S2,
int O2>
370 inline typename MotionDerived::MotionPlain
378 template<
typename S1,
int O1,
typename S2,
int O2>
379 inline Eigen::Matrix<S2,6,3,O2>
384 Eigen::Matrix<S2,6,3,O2>
M;
386 M.template middleRows<3>(Constraint::LINEAR).
setZero();
387 M.template middleRows<3>(Constraint::LINEAR).diagonal().fill(Y.
mass ());
393 template<
typename M6Like,
typename S2,
int O2>
399 return Y.
derived().template middleCols<3>(Constraint::LINEAR);
402 template<
typename S1,
int O1>
406 template<
typename S1,
int O1,
typename MotionDerived>
412 template<
typename _Scalar,
int _Options>
429 typedef Eigen::Matrix<Scalar,6,NV,Options>
U_t;
430 typedef Eigen::Matrix<Scalar,NV,NV,Options>
D_t;
431 typedef Eigen::Matrix<Scalar,6,NV,Options>
UD_t;
439 template<
typename Scalar,
int Options>
443 template<
typename Scalar,
int Options>
447 template<
typename _Scalar,
int _Options>
449 :
public JointDataBase< JointDataTranslationTpl<_Scalar,_Options> >
451 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
468 : M(Transformation_t::Vector3::Zero())
469 , v(Motion_t::Vector3::Zero())
472 , UDinv(UD_t::Zero())
475 static std::string
classname() {
return std::string(
"JointDataTranslation"); }
480 template<
typename _Scalar,
int _Options>
482 :
public JointModelBase< JointModelTranslationTpl<_Scalar,_Options> >
484 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
495 JointDataDerived
createData()
const {
return JointDataDerived(); }
499 return {
true,
true,
true};
504 return {
true,
true,
true};
507 template<
typename ConfigVector>
509 const typename Eigen::MatrixBase<ConfigVector> &
qs)
const 511 data.M.translation() = this->jointConfigSelector(qs);
514 template<
typename ConfigVector,
typename TangentVector>
516 const typename Eigen::MatrixBase<ConfigVector> &
qs,
517 const typename Eigen::MatrixBase<TangentVector> & vs)
const 519 calc(data,qs.derived());
521 data.v.linear() = this->jointVelocitySelector(vs);
524 template<
typename Matrix6Like>
526 const Eigen::MatrixBase<Matrix6Like> & I,
527 const bool update_I)
const 529 data.U = I.template middleCols<3>(Inertia::LINEAR);
536 data.UDinv.template middleRows<3>(Inertia::LINEAR).setIdentity();
537 data.UDinv.template middleRows<3>(Inertia::ANGULAR).noalias() = data.U.template middleRows<3>(Inertia::ANGULAR) * data.Dinv;
542 I_.template block<3,3>(Inertia::ANGULAR,Inertia::ANGULAR)
543 -= data.UDinv.template middleRows<3>(Inertia::ANGULAR) * I_.template block<3,3>(Inertia::LINEAR, Inertia::ANGULAR);
544 I_.template middleCols<3>(Inertia::LINEAR).
setZero();
545 I_.template block<3,3>(Inertia::LINEAR,Inertia::ANGULAR).
setZero();
549 static std::string
classname() {
return std::string(
"JointModelTranslation"); }
553 template<
typename NewScalar>
566 #include <boost/type_traits.hpp> 570 template<
typename Scalar,
int Options>
572 :
public integral_constant<bool,true> {};
574 template<
typename Scalar,
int Options>
576 :
public integral_constant<bool,true> {};
578 template<
typename Scalar,
int Options>
580 :
public integral_constant<bool,true> {};
582 template<
typename Scalar,
int Options>
584 :
public integral_constant<bool,true> {};
587 #endif // ifndef __pinocchio_joint_translation_hpp__ JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > const Eigen::MatrixBase< TangentVectorType > & v
#define PINOCCHIO_SE3_TYPEDEF_TPL(Derived)
ConstraintTranspose transpose() const
ConstraintTranslationTpl()
MotionTpl< Scalar, Options > ReturnType
const DenseBase ConstMatrixReturnType
MotionTpl< Scalar, Options > MotionPlain
MotionPlain se3ActionInverse_impl(const SE3Tpl< S2, O2 > &m) const
const SizeDepType< 3 >::RowsReturn< MatrixDerived >::ConstType operator*(const Eigen::MatrixBase< MatrixDerived > &F) const
void calc_aba(JointDataDerived &data, const Eigen::MatrixBase< Matrix6Like > &I, const bool update_I) const
int idx_q(const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel)
Visit a JointModelTpl through JointIdxQVisitor to get the index in the full model configuration space...
static std::string classname()
MotionZeroTpl< Scalar, Options > Bias_t
MotionTpl< Scalar, Options > ReturnType
std::string shortname() const
JointDataDerived createData() const
int idx_v(const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel)
Visit a JointModelTpl through JointIdxVVisitor to get the index in the full model tangent space corre...
const std::vector< bool > hasConfigurationLimitInTangent() const
Eigen::Matrix< Scalar, NV, NV, Options > D_t
const Vector3 & operator()() const
Return type of the ation of a Motion onto an object of type D.
#define MOTION_TYPEDEF_TPL(Derived)
JointDataTranslationTpl< Scalar, Options > JointDataDerived
bool isEqual_impl(const MotionTranslationTpl &other) const
Eigen::Matrix< Scalar, 3, 1, Options > Vector3
PINOCCHIO_EIGEN_REF_CONST_TYPE(Matrix6Like) operator*(const Eigen
void motionAction(const MotionDense< M1 > &v, MotionDense< M2 > &mout) const
const Vector3 & lever() const
JointIndex id(const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel)
Visit a JointModelTpl through JointIdVisitor to get the index of the joint in the kinematic chain...
#define PINOCCHIO_JOINT_DATA_BASE_DEFAULT_ACCESSOR
Eigen::Matrix< Scalar, 3, 1, Options > JointForce
MotionPlain motionAction(const MotionDense< M1 > &v) const
void calc(JointDataDerived &data, const typename Eigen::MatrixBase< ConfigVector > &qs) const
Eigen::Matrix< Scalar, 6, NV, Options > UD_t
ConstraintTranspose(const ConstraintTranslationTpl &ref)
void addTo(MotionDense< Derived > &other) const
ConstLinearType linear() const
#define PINOCCHIO_EIGEN_CONST_CAST(TYPE, OBJ)
Macro for an automatic const_cast.
Eigen::Matrix< Scalar, 6, 3, Options > DenseBase
MotionDerived::MotionPlain operator+(const MotionPlanarTpl< Scalar, Options > &m1, const MotionDense< MotionDerived > &m2)
JointModelTranslationTpl< Scalar, Options > JointModelDerived
ConstAngularType angular() const
const Vector3 ConstLinearType
TransformTranslationTpl< Scalar, Options > Transformation_t
PINOCCHIO_JOINT_DATA_BASE_DEFAULT_ACCESSOR Constraint_t S
MotionTranslationTpl< Scalar, Options > Motion_t
#define PINOCCHIO_JOINT_DATA_BASE_ACCESSOR_DEFAULT_RETURN_TYPE
Eigen::Matrix< S1, 6, 3, O1 > ReturnType
PINOCCHIO_JOINT_DATA_BASE_ACCESSOR_DEFAULT_RETURN_TYPE typedef Eigen::Matrix< Scalar, NQ, 1, Options > ConfigVector_t
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef JointTranslationTpl< _Scalar, _Options > JointDerived
MotionTranslationTpl< Scalar, Options > JointMotion
Eigen::Matrix< S1, 6, 3, O1 > se3Action(const SE3Tpl< S1, O1 > &m) const
DenseBase matrix_impl() const
JointTranslationTpl< Scalar, Options > JointDerived
MotionPlain se3Action_impl(const SE3Tpl< S2, O2 > &m) const
bool isEqual(const ConstraintTranslationTpl &) const
#define PINOCCHIO_JOINT_DATA_TYPEDEF_TEMPLATE(Joint)
const Vector3 ConstAngularType
Eigen::Matrix< S1, 6, 3, O1 > se3ActionInverse(const SE3Tpl< S1, O1 > &m) const
DenseBase MatrixReturnType
const ConstraintTranslationTpl & ref
JointMotion __mult__(const Eigen::MatrixBase< Vector3Like > &v) const
ConstraintTranslationTpl< Scalar, Options > Constraint_t
std::string shortname() const
PINOCCHIO_JOINT_CAST_TYPE_SPECIALIZATION(JointModelFreeFlyerTpl)
Eigen::Matrix< Scalar, 6, 6, Options > Matrix6
PlainReturnType plain() const
void calc(JointDataDerived &data, const typename Eigen::MatrixBase< ConfigVector > &qs, const typename Eigen::MatrixBase< TangentVector > &vs) const
MotionTranslationTpl(const Eigen::MatrixBase< Vector3Like > &v)
MotionTranslationTpl< double > MotionTranslation
ConstLinearType linear() const
Return the linear part of the force vector.
#define PINOCCHIO_EIGEN_REF_TYPE(D)
ConstAngularRef rotation() const
void se3Action_impl(const SE3Tpl< S2, O2 > &m, MotionDense< D2 > &v) const
void setTo(MotionDense< Derived > &other) const
Main pinocchio namespace.
Base class for rigid transformation.
MotionPlain PlainReturnType
const Vector3 & linear() const
JointModelTranslationTpl< NewScalar, Options > cast() const
Eigen::Matrix< Scalar, 6, 1, Options > Vector6
const std::vector< bool > hasConfigurationLimit() const
JointTranslationTpl< Scalar, Options > JointDerived
void setIndexes(JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel, JointIndex id, int q, int v)
Visit a JointModelTpl through JointSetIndexesVisitor to set the indexes of the joint in the kinematic...
JointDataTranslationTpl()
void alphaSkew(const Scalar alpha, const Eigen::MatrixBase< Vector3 > &v, const Eigen::MatrixBase< Matrix3 > &M)
Computes the skew representation of a given 3d vector multiplied by a given scalar. i.e. the antisymmetric matrix representation of the cross product operator ( )
void setZero(std::vector< MatType, Eigen::aligned_allocator< MatType > > &Ms)
DenseBase motionAction(const MotionDense< MotionDerived > &m) const
Common traits structure to fully define base classes for CRTP.
Eigen::Matrix< Scalar, NV, 1, Options > TangentVector_t
JointModelBase< JointModelTranslationTpl > Base
void skew(const Eigen::MatrixBase< Vector3 > &v, const Eigen::MatrixBase< Matrix3 > &M)
Computes the skew representation of a given 3d vector, i.e. the antisymmetric matrix representation o...
#define PINOCCHIO_CONSTRAINT_TYPEDEF_TPL(DERIVED)
Eigen::Matrix< Scalar, 6, NV, Options > U_t
MotionTranslationTpl & operator=(const MotionTranslationTpl &other)
void se3ActionInverse_impl(const SE3Tpl< S2, O2 > &m, MotionDense< D2 > &v) const
static void motionAction(const MotionDense< MotionDerived > &v, const Eigen::MatrixBase< Mat > &iF, Eigen::MatrixBase< MatRet > const &jF)
Action of a motion on a set of forces, represented by a 6xN matrix whose each column represent a spat...
MotionDerived::MotionPlain operator^(const MotionDense< MotionDerived > &m1, const MotionPlanarTpl< S2, O2 > &m2)
Eigen::Matrix< S1, 6, 3, O1 > ReturnType
Eigen::Matrix< Scalar, 4, 4, Options > Matrix4
MotionTranslationTpl(const MotionTranslationTpl &other)
static std::string classname()
EIGEN_MAKE_ALIGNED_OPERATOR_NEW Derived & derived()
MatrixDerived plain(const Eigen::PlainObjectBase< MatrixDerived > &m)
MultiplicationOp< InertiaTpl< Scalar, Options >, ConstraintDerived >::ReturnType operator*(const InertiaTpl< Scalar, Options > &Y, const ConstraintBase< ConstraintDerived > &constraint)
.
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef JointTranslationTpl< _Scalar, _Options > JointDerived
Matrix4 HomogeneousMatrixType
#define PINOCCHIO_JOINT_TYPEDEF_TEMPLATE(Joint)