Go to the documentation of this file.
6 #ifndef __pinocchio_multibody_joint_translation_hpp__
7 #define __pinocchio_multibody_joint_translation_hpp__
18 template<
typename Scalar,
int Options = context::Options>
22 template<
typename Scalar,
int Options>
28 template<
typename Scalar,
int Options,
typename MotionDerived>
34 template<
typename _Scalar,
int _Options>
42 typedef Eigen::Matrix<Scalar, 3, 1, Options>
Vector3;
43 typedef Eigen::Matrix<Scalar, 6, 1, Options>
Vector6;
44 typedef Eigen::Matrix<Scalar, 4, 4, Options>
Matrix4;
45 typedef Eigen::Matrix<Scalar, 6, 6, Options>
Matrix6;
63 template<
typename _Scalar,
int _Options>
64 struct MotionTranslationTpl : MotionBase<MotionTranslationTpl<_Scalar, _Options>>
66 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
74 template<
typename Vector3Like>
94 inline PlainReturnType
plain()
const
96 return PlainReturnType(
m_v, PlainReturnType::Vector3::Zero());
110 template<
typename Derived>
116 template<
typename Derived>
123 template<
typename S2,
int O2,
typename D2>
126 v.angular().setZero();
127 v.linear().noalias() =
m.rotation() *
m_v;
130 template<
typename S2,
int O2>
138 template<
typename S2,
int O2,
typename D2>
142 v.linear().noalias() =
m.rotation().transpose() *
m_v;
145 v.angular().setZero();
148 template<
typename S2,
int O2>
156 template<
typename M1,
typename M2>
160 mout.
linear().noalias() =
v.angular().cross(
m_v);
166 template<
typename M1>
188 template<
typename S1,
int O1,
typename MotionDerived>
189 inline typename MotionDerived::MotionPlain
192 return typename MotionDerived::MotionPlain(m2.
linear() + m1.linear(), m2.
angular());
195 template<
typename Scalar,
int Options>
198 template<
typename _Scalar,
int _Options>
209 typedef Eigen::Matrix<Scalar, 3, 1, Options>
Vector3;
210 typedef Eigen::Matrix<Scalar, 3, 3, Options>
Matrix3;
221 template<
typename Scalar,
int Options>
227 template<
typename _Scalar,
int _Options>
230 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
238 template<
typename Vector3Like>
246 PlainType
res(PlainType::Identity());
247 res.rotation().setIdentity();
253 operator PlainType()
const
258 template<
typename S2,
int O2>
280 return AngularType(3, 3);
292 template<
typename Scalar,
int Options>
295 template<
typename _Scalar,
int _Options>
321 template<
typename _Scalar,
int _Options>
325 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
342 template<
typename Vector3Like>
343 JointMotion
__mult__(
const Eigen::MatrixBase<Vector3Like> &
v)
const
345 EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Vector3Like, 3);
346 return JointMotion(
v);
362 template<
typename Derived>
369 template<
typename MatrixDerived>
371 operator*(
const Eigen::MatrixBase<MatrixDerived> & F)
const
373 assert(F.rows() == 6);
374 return F.derived().template middleRows<3>(LINEAR);
387 S.template middleRows<3>(LINEAR).setIdentity();
388 S.template middleRows<3>(ANGULAR).setZero();
392 template<
typename S1,
int O1>
395 Eigen::Matrix<S1, 6, 3, O1>
M;
396 M.template middleRows<3>(LINEAR) =
m.rotation();
397 M.template middleRows<3>(ANGULAR).setZero();
402 template<
typename S1,
int O1>
405 Eigen::Matrix<S1, 6, 3, O1>
M;
406 M.template middleRows<3>(LINEAR) =
m.rotation().transpose();
407 M.template middleRows<3>(ANGULAR).setZero();
412 template<
typename MotionDerived>
415 const typename MotionDerived::ConstAngularType
w =
m.angular();
418 skew(
w,
res.template middleRows<3>(LINEAR));
419 res.template middleRows<3>(ANGULAR).setZero();
431 template<
typename MotionDerived,
typename S2,
int O2>
432 inline typename MotionDerived::MotionPlain
435 return m2.motionAction(m1);
439 template<
typename S1,
int O1,
typename S2,
int O2>
440 inline Eigen::Matrix<S2, 6, 3, O2>
444 Eigen::Matrix<S2, 6, 3, O2>
M;
445 alphaSkew(
Y.mass(),
Y.lever(),
M.template middleRows<3>(Constraint::ANGULAR));
446 M.template middleRows<3>(Constraint::LINEAR).setZero();
447 M.template middleRows<3>(Constraint::LINEAR).diagonal().fill(
Y.mass());
453 template<
typename M6Like,
typename S2,
int O2>
454 inline const typename SizeDepType<3>::ColsReturn<M6Like>::ConstType
458 return Y.derived().template middleCols<3>(Constraint::LINEAR);
461 template<
typename S1,
int O1>
467 template<
typename S1,
int O1,
typename MotionDerived>
473 template<
typename Scalar,
int Options>
476 template<
typename _Scalar,
int _Options>
497 typedef Eigen::Matrix<Scalar, 6, NV, Options>
U_t;
498 typedef Eigen::Matrix<Scalar, NV, NV, Options>
D_t;
499 typedef Eigen::Matrix<Scalar, 6, NV, Options>
UD_t;
507 template<
typename _Scalar,
int _Options>
514 template<
typename _Scalar,
int _Options>
521 template<
typename _Scalar,
int _Options>
524 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
545 :
joint_q(ConfigVector_t::Zero())
546 ,
joint_v(TangentVector_t::Zero())
547 ,
M(Transformation_t::
Vector3::Zero())
551 ,
UDinv(UD_t::Zero())
558 return std::string(
"JointDataTranslation");
567 template<
typename _Scalar,
int _Options>
568 struct JointModelTranslationTpl
569 :
public JointModelBase<JointModelTranslationTpl<_Scalar, _Options>>
571 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
584 return JointDataDerived();
589 return {
true,
true,
true};
594 return {
true,
true,
true};
597 template<
typename ConfigVector>
598 void calc(JointDataDerived &
data,
const typename Eigen::MatrixBase<ConfigVector> &
qs)
const
600 data.joint_q = this->jointConfigSelector(
qs);
601 data.M.translation() =
data.joint_q;
604 template<
typename TangentVector>
606 calc(JointDataDerived &
data,
const Blank,
const typename Eigen::MatrixBase<TangentVector> & vs)
609 data.joint_v = this->jointVelocitySelector(vs);
613 template<
typename ConfigVector,
typename TangentVector>
615 JointDataDerived &
data,
616 const typename Eigen::MatrixBase<ConfigVector> &
qs,
617 const typename Eigen::MatrixBase<TangentVector> & vs)
const
621 data.joint_v = this->jointVelocitySelector(vs);
625 template<
typename VectorLike,
typename Matrix6Like>
627 JointDataDerived &
data,
628 const Eigen::MatrixBase<VectorLike> & armature,
629 const Eigen::MatrixBase<Matrix6Like> & I,
630 const bool update_I)
const
632 data.U = I.template middleCols<3>(Inertia::LINEAR);
634 data.StU =
data.U.template middleRows<3>(Inertia::LINEAR);
635 data.StU.diagonal() += armature;
647 return std::string(
"JointModelTranslation");
655 template<
typename NewScalar>
668 #include <boost/type_traits.hpp>
672 template<
typename Scalar,
int Options>
674 :
public integral_constant<bool, true>
678 template<
typename Scalar,
int Options>
680 :
public integral_constant<bool, true>
684 template<
typename Scalar,
int Options>
686 :
public integral_constant<bool, true>
690 template<
typename Scalar,
int Options>
692 :
public integral_constant<bool, true>
697 #endif // ifndef __pinocchio_multibody_joint_translation_hpp__
JointMotionSubspaceTranslationTpl()
const typedef Vector3 ConstAngularType
MotionTpl< Scalar, Options > ReturnType
MotionPlain se3Action_impl(const SE3Tpl< S2, O2 > &m) const
#define PINOCCHIO_JOINT_DATA_BASE_ACCESSOR_DEFAULT_RETURN_TYPE
const SizeDepType< 3 >::RowsReturn< MatrixDerived >::ConstType operator*(const Eigen::MatrixBase< MatrixDerived > &F) const
ConstLinearType linear() const
Return the linear part of the force vector.
ConstraintTranspose transpose() const
const typedef DenseBase ConstMatrixReturnType
MotionTranslationTpl< Scalar, Options > JointMotion
int idx_q(const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel)
Visit a JointModelTpl through JointIdxQVisitor to get the index in the full model configuration space...
Eigen::Matrix< Scalar, NV, 1, Options > TangentVector_t
JointDataTranslationTpl()
void setTo(MotionDense< Derived > &other) const
const Vector3 & linear() 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...
MotionTpl< Scalar, Options > ReturnType
TransformTranslationTpl< Scalar, Options > Transformation_t
PlainReturnType plain() const
MotionTranslationTpl(const Eigen::MatrixBase< Vector3Like > &v)
#define PINOCCHIO_EIGEN_CONST_CAST(TYPE, OBJ)
Macro for an automatic const_cast.
void calc(JointDataDerived &data, const typename Eigen::MatrixBase< ConfigVector > &qs) const
std::string shortname() const
void calc(JointDataDerived &data, const Blank, const typename Eigen::MatrixBase< TangentVector > &vs) const
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef JointTranslationTpl< _Scalar, _Options > JointDerived
PINOCCHIO_EIGEN_REF_CONST_TYPE(Matrix6Like) operator*(const Eigen
void se3Action_impl(const SE3Tpl< S2, O2 > &m, MotionDense< D2 > &v) const
Eigen::Matrix< S1, 6, 3, O1 > se3ActionInverse(const SE3Tpl< S1, O1 > &m) const
JointMotion __mult__(const Eigen::MatrixBase< Vector3Like > &v) const
MotionDerived::MotionPlain operator+(const MotionHelicalUnalignedTpl< S1, O1 > &m1, const MotionDense< MotionDerived > &m2)
ConstraintTranspose(const JointMotionSubspaceTranslationTpl &ref)
MotionTranslationTpl & operator=(const MotionTranslationTpl &other)
void setIndexes(JointIndex id, int q, int v)
JointDataTranslationTpl< Scalar, Options > JointDataDerived
Eigen::Matrix< Scalar, 6, 1, Options > Vector6
Return type of the ation of a Motion onto an object of type D.
Eigen::Matrix< Scalar, 3, 1, Options > JointForce
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef JointTranslationTpl< _Scalar, _Options > JointDerived
TridiagonalSymmetricMatrixApplyOnTheLeftReturnType< LhsMatrixType, TridiagonalSymmetricMatrixTpl< S, O > > operator*(const Eigen::MatrixBase< LhsMatrixType > &lhs, const TridiagonalSymmetricMatrixTpl< S, O > &rhs)
JointDataDerived createData() const
Eigen::Matrix< S1, 6, 3, O1 > ReturnType
JointTranslationTpl< _Scalar, _Options > JointDerived
ConstLinearType linear() const
MotionTranslationTpl(const MotionTranslationTpl &other)
#define PINOCCHIO_JOINT_DATA_BASE_DEFAULT_ACCESSOR
void se3ActionInverse_impl(const SE3Tpl< S2, O2 > &m, MotionDense< D2 > &v) const
MotionTpl< Scalar, Options > MotionPlain
const std::vector< bool > hasConfigurationLimitInTangent() const
Eigen::Matrix< Scalar, NV, NV, Options > D_t
Eigen::Matrix< Scalar, 3, 1, Options > Vector3
Eigen::Matrix< Scalar, 6, NV, Options > U_t
MotionZeroTpl< Scalar, Options > Bias_t
PINOCCHIO_JOINT_CAST_TYPE_SPECIALIZATION(JointModelFreeFlyerTpl)
Free-flyer joint in .
JointMotionSubspaceTranslationTpl< Scalar, Options > Constraint_t
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...
void calc_aba(JointDataDerived &data, const Eigen::MatrixBase< VectorLike > &armature, const Eigen::MatrixBase< Matrix6Like > &I, const bool update_I) const
ForceDense< Derived >::ConstLinearType operator*(const ForceDense< Derived > &phi)
static std::string classname()
JointModelBase< JointModelTranslationTpl > Base
JointModelTranslationTpl< NewScalar, Options > cast() const
MotionPlain PlainReturnType
Matrix4 HomogeneousMatrixType
Eigen::Matrix< Scalar, 3, 3, Options > ReducedSquaredMatrix
const std::vector< bool > hasConfigurationLimit() const
Eigen::Matrix< Scalar, NQ, 1, Options > ConfigVector_t
PINOCCHIO_JOINT_DATA_BASE_DEFAULT_ACCESSOR ConfigVector_t joint_q
Eigen::Matrix< Scalar, 3, 1, Options > Vector3
MotionPlain se3ActionInverse_impl(const SE3Tpl< S2, O2 > &m) const
DenseBase MatrixReturnType
Eigen::Matrix< Scalar, 4, 4, Options > Matrix4
void calc(JointDataDerived &data, const typename Eigen::MatrixBase< ConfigVector > &qs, const typename Eigen::MatrixBase< TangentVector > &vs) const
const JointMotionSubspaceTranslationTpl & ref
MotionTranslationTpl< Scalar, Options > Motion_t
ReducedSquaredMatrix::IdentityReturnType StDiagonalMatrixSOperationReturnType
Eigen::Matrix< S1, 6, 3, O1 > ReturnType
Eigen::Matrix< Scalar, 6, NV, Options > UD_t
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > const Eigen::MatrixBase< TangentVectorType > & v
bool comparison_eq(const LhsType &lhs_value, const RhsType &rhs_value)
const Vector3 & operator()() const
JointModelTranslationTpl< Scalar, Options > JointModelDerived
bool isEqual_impl(const MotionTranslationTpl &other) const
Base class for rigid transformation.
void motionAction(const MotionDense< M1 > &v, MotionDense< M2 > &mout) const
Eigen::Matrix< Scalar, 6, 6, Options > Matrix6
PINOCCHIO_JOINT_DATA_TYPEDEF_TEMPLATE(JointDerived)
MotionPlain motionAction(const MotionDense< M1 > &v) const
const typedef Vector3 ConstLinearType
void addTo(MotionDense< Derived > &other) const
EIGEN_STRONG_INLINE MotionDerived::MotionPlain operator^(const MotionDense< MotionDerived > &m1, const MotionHelicalUnalignedTpl< S2, O2 > &m2)
#define PINOCCHIO_CONSTRAINT_TYPEDEF_TPL(DERIVED)
Common traits structure to fully define base classes for CRTP.
std::string shortname() const
static std::string classname()
Eigen::Matrix< Scalar, 6, 3, Options > DenseBase
#define PINOCCHIO_EIGEN_REF_TYPE(D)
PINOCCHIO_JOINT_TYPEDEF_TEMPLATE(JointDerived)
MotionTranslationTpl< context::Scalar > MotionTranslation
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....
DenseBase motionAction(const MotionDense< MotionDerived > &m) const
JointTranslationTpl< _Scalar, _Options > JointDerived
bool isEqual(const JointMotionSubspaceTranslationTpl &) const
DenseBase matrix_impl() const
EIGEN_MAKE_ALIGNED_OPERATOR_NEW MOTION_TYPEDEF_TPL(MotionTranslationTpl)
ConstAngularType angular() const
Main pinocchio namespace.
Eigen::Matrix< S1, 6, 3, O1 > se3Action(const SE3Tpl< S1, O1 > &m) const
pinocchio
Author(s):
autogenerated on Fri Nov 1 2024 02:41:46