Go to the documentation of this file.
5 #ifndef __pinocchio_multibody_joint_helical_unaligned_hpp__
6 #define __pinocchio_multibody_joint_helical_unaligned_hpp__
21 template<
typename Scalar,
int Options>
24 template<
typename Scalar,
int Options>
30 template<
typename Scalar,
int Options,
typename MotionDerived>
36 template<
typename _Scalar,
int _Options>
44 typedef Eigen::Matrix<Scalar, 3, 1, Options>
Vector3;
45 typedef Eigen::Matrix<Scalar, 6, 1, Options>
Vector6;
46 typedef Eigen::Matrix<Scalar, 4, 4, Options>
Matrix4;
47 typedef Eigen::Matrix<Scalar, 6, 6, Options>
Matrix6;
65 template<
typename _Scalar,
int _Options>
66 struct MotionHelicalUnalignedTpl : MotionBase<MotionHelicalUnalignedTpl<_Scalar, _Options>>
68 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
76 template<
typename Vector3Like,
typename OtherScalar>
78 const Eigen::MatrixBase<Vector3Like> &
axis,
const OtherScalar &
w,
const OtherScalar &
v)
85 inline PlainReturnType
plain()
const
90 template<
typename OtherScalar>
96 template<
typename MotionDerived>
99 for (Eigen::DenseIndex k = 0; k < 3; ++k)
106 template<
typename MotionDerived>
113 template<
typename S2,
int O2,
typename D2>
116 v.angular().noalias() =
m_w *
m.rotation() *
m_axis;
117 v.linear().noalias() =
m.translation().cross(
v.angular()) +
m_v *
m.rotation() *
m_axis;
120 template<
typename S2,
int O2>
128 template<
typename S2,
int O2,
typename D2>
132 v.angular().noalias() =
m_axis.cross(
m.translation());
134 v.linear().noalias() =
135 m.rotation().transpose() *
v.angular() +
m_v * (
m.rotation().transpose() *
m_axis);
138 v.angular().noalias() =
m.rotation().transpose() *
m_axis *
m_w;
141 template<
typename S2,
int O2>
149 template<
typename M1,
typename M2>
164 template<
typename M1>
211 template<
typename S1,
int O1,
typename MotionDerived>
212 typename MotionDerived::MotionPlain
215 typename MotionDerived::MotionPlain
res(m2);
220 template<
typename MotionDerived,
typename S2,
int O2>
221 EIGEN_STRONG_INLINE
typename MotionDerived::MotionPlain
224 return m2.motionAction(m1);
227 template<
typename Scalar,
int Options>
230 template<
typename Scalar,
int Options>
236 template<
typename Scalar,
int Options,
typename MotionDerived>
242 template<
typename Scalar,
int Options,
typename ForceDerived>
248 template<
typename Scalar,
int Options,
typename ForceSet>
251 typedef typename Eigen::Matrix<Scalar, Eigen::Dynamic, Eigen::Dynamic>
ReturnType;
254 template<
typename _Scalar,
int _Options>
276 typedef Eigen::Matrix<Scalar, 3, 1, Options>
Vector3;
281 template<
typename _Scalar,
int _Options>
285 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
299 template<
typename Vector3Like>
301 const Eigen::MatrixBase<Vector3Like> &
axis,
const Scalar &
h)
307 template<
typename Vector1Like>
308 JointMotion
__mult__(
const Eigen::MatrixBase<Vector1Like> &
v)
const
310 EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Vector1Like, 1);
311 assert(
v.size() == 1);
315 template<
typename S1,
int O1>
322 res.template segment<3>(ANGULAR).noalias() =
m.rotation() *
m_axis;
323 res.template segment<3>(LINEAR).noalias() =
324 m.translation().cross(
res.template segment<3>(ANGULAR)) +
m_pitch * (
m.rotation() *
m_axis);
328 template<
typename S1,
int O1>
336 res.template segment<3>(ANGULAR).noalias() =
m.rotation().transpose() *
m_axis;
337 res.template segment<3>(LINEAR).noalias() =
338 -
m.rotation().transpose() *
m.translation().cross(
m_axis)
357 template<
typename ForceDerived>
369 template<
typename Derived>
373 assert(F.rows() == 6);
375 ref.
axis().transpose() * F.template middleRows<3>(ANGULAR)
395 S.template segment<3>(ANGULAR) =
m_axis;
399 template<
typename MotionDerived>
403 const typename MotionDerived::ConstLinearType
v =
m.linear();
404 const typename MotionDerived::ConstAngularType
w =
m.angular();
407 res.template segment<3>(LINEAR).noalias() =
v.cross(
m_axis);
409 res.template segment<3>(LINEAR).noalias() +=
res.template segment<3>(ANGULAR);
410 res.template segment<3>(ANGULAR).noalias() =
w.cross(
m_axis);
444 template<
typename _Scalar,
int _Options>
450 Eigen::Matrix<_Scalar, 1, 1, _Options>
res;
451 res(0) = (S_transpose.
ref.
axis() * S_transpose.
ref.
h()).dot(
S.axis() *
S.h())
452 + (S_transpose.
ref.
axis().dot(
S.axis()));
456 template<
typename S1,
int O1,
typename S2,
int O2>
465 template<
typename S1,
int O1,
typename S2,
int O2>
477 const S2 & m_pitch = cru.
h();
482 res.template segment<3>(Inertia::LINEAR) = -
m *
c.cross(cru.
axis());
483 res.template segment<3>(Inertia::ANGULAR).noalias() = I * cru.
axis();
484 res.template segment<3>(Inertia::ANGULAR) +=
c.cross(cru.
axis()) *
m * m_pitch;
485 res.template segment<3>(Inertia::ANGULAR) +=
486 c.cross(
res.template segment<3>(Inertia::LINEAR));
487 res.template segment<3>(Inertia::LINEAR) +=
m * m_pitch * cru.
axis();
493 template<
typename M6Like,
typename Scalar,
int Options>
495 Eigen::MatrixBase<M6Like>,
504 template<
typename M6Like,
typename Scalar,
int Options>
506 Eigen::MatrixBase<M6Like>,
513 EIGEN_STATIC_ASSERT_MATRIX_SPECIFIC_SIZE(M6Like, 6, 6);
514 return Y.derived().template middleCols<3>(Constraint::ANGULAR) * cru.
axis()
515 +
Y.derived().template middleCols<3>(Constraint::LINEAR) * cru.
axis() * cru.
h();
520 template<
typename Scalar,
int Options>
523 template<
typename _Scalar,
int _Options>
544 typedef Eigen::Matrix<Scalar, 6, NV, Options>
U_t;
545 typedef Eigen::Matrix<Scalar, NV, NV, Options>
D_t;
546 typedef Eigen::Matrix<Scalar, 6, NV, Options>
UD_t;
554 template<
typename _Scalar,
int _Options>
561 template<
typename _Scalar,
int _Options>
568 template<
typename _Scalar,
int _Options>
570 :
public JointDataBase<JointDataHelicalUnalignedTpl<_Scalar, _Options>>
572 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
592 :
joint_q(ConfigVector_t::Zero())
593 ,
joint_v(TangentVector_t::Zero())
595 ,
M(Transformation_t::Identity())
599 ,
UDinv(UD_t::Zero())
604 template<
typename Vector3Like>
606 :
joint_q(ConfigVector_t::Zero())
607 ,
joint_v(TangentVector_t::Zero())
609 ,
M(Transformation_t::Identity())
613 ,
UDinv(UD_t::Zero())
620 return std::string(
"JointDataHelicalUnaligned");
630 template<
typename _Scalar,
int _Options>
631 struct JointModelHelicalUnalignedTpl
632 :
public JointModelBase<JointModelHelicalUnalignedTpl<_Scalar, _Options>>
634 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
637 typedef Eigen::Matrix<Scalar, 3, 1, _Options>
Vector3;
649 template<
typename Vector3Like>
654 EIGEN_STATIC_ASSERT_VECTOR_ONLY(Vector3Like);
667 template<
typename Vector3Like>
672 EIGEN_STATIC_ASSERT_VECTOR_ONLY(Vector3Like);
688 return JointDataDerived();
698 template<
typename ConfigVector>
699 void calc(JointDataDerived &
data,
const typename Eigen::MatrixBase<ConfigVector> &
qs)
const
709 template<
typename TangentVector>
711 calc(JointDataDerived &
data,
const Blank,
const typename Eigen::MatrixBase<TangentVector> & vs)
719 template<
typename ConfigVector,
typename TangentVector>
721 JointDataDerived &
data,
722 const typename Eigen::MatrixBase<ConfigVector> &
qs,
723 const typename Eigen::MatrixBase<TangentVector> & vs)
const
731 template<
typename VectorLike,
typename Matrix6Like>
733 JointDataDerived &
data,
734 const Eigen::MatrixBase<VectorLike> & armature,
735 const Eigen::MatrixBase<Matrix6Like> & I,
736 const bool update_I)
const
738 data.U.noalias() = I.template middleCols<3>(Motion::ANGULAR) *
axis
739 +
m_pitch * I.template middleCols<3>(Motion::LINEAR) *
axis;
740 data.StU[0] =
axis.dot(
data.U.template segment<3>(Motion::ANGULAR))
741 +
m_pitch *
axis.dot(
data.U.template segment<3>(Motion::LINEAR)) + armature[0];
750 return std::string(
"JointModelHelicalUnaligned");
758 template<
typename NewScalar>
774 #include <boost/type_traits.hpp>
778 template<
typename Scalar,
int Options>
780 :
public integral_constant<bool, true>
784 template<
typename Scalar,
int Options>
786 :
public integral_constant<bool, true>
790 template<
typename Scalar,
int Options>
792 :
public integral_constant<bool, true>
796 template<
typename Scalar,
int Options>
798 :
public integral_constant<bool, true>
803 #endif // ifndef __pinocchio_multibody_joint_helical_unaligned_hpp__
ReducedSquaredMatrix::IdentityReturnType StDiagonalMatrixSOperationReturnType
static ReturnType run(const Eigen::MatrixBase< M6Like > &Y, const Constraint &cru)
#define PINOCCHIO_JOINT_DATA_BASE_ACCESSOR_DEFAULT_RETURN_TYPE
Eigen::Matrix< Scalar, NV, 1, Options > TangentVector_t
JointHelicalUnalignedTpl< _Scalar, _Options > JointDerived
Forward declaration of the multiplication operation return type. Should be overloaded,...
JointDataHelicalUnalignedTpl()
Eigen::Matrix< Scalar, 1, 1, Options > ReducedSquaredMatrix
JointModelHelicalUnalignedTpl()
JointDataHelicalUnalignedTpl< Scalar, Options > JointDataDerived
Eigen::Matrix< Scalar, 6, 1, Options > ReturnType
MotionTpl< Scalar, Options > MotionPlain
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.
int idx_q(const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel)
Visit a JointModelTpl through JointIdxQVisitor to get the index in the full model configuration space...
void calc(JointDataDerived &data, const typename Eigen::MatrixBase< ConfigVector > &qs) const
Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic > ReturnType
Eigen::Matrix< Scalar, NQ, 1, Options > ConfigVector_t
Return type of the Constraint::Transpose * Force operation.
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...
#define PINOCCHIO_EIGEN_CONST_CAST(TYPE, OBJ)
Macro for an automatic const_cast.
JointHelicalUnalignedTpl< _Scalar, _Options > JointDerived
Eigen::Matrix< Scalar, 1, 1 > ReturnType
PINOCCHIO_EIGEN_REF_CONST_TYPE(Matrix6Like) operator*(const Eigen
ConstraintForceSetOp< JointMotionSubspaceHelicalUnalignedTpl, Derived >::ReturnType operator*(const Eigen::MatrixBase< Derived > &F) const
[CRBA] MatrixBase operator* (Constraint::Transpose S, ForceSet::Block)
SE3GroupAction< JointMotionSubspaceHelicalUnalignedTpl >::ReturnType se3ActionInverse(const SE3Tpl< S1, O1 > &m) const
MotionHelicalUnalignedTpl __mult__(const OtherScalar &alpha) const
JointMotionSubspaceHelicalUnalignedTpl< S2, O2 >::Vector3 Vector3
void calc(JointDataDerived &data, const typename Eigen::MatrixBase< ConfigVector > &qs, const typename Eigen::MatrixBase< TangentVector > &vs) const
bool isEqual(const JointModelHelicalUnalignedTpl &other) const
static ReturnType run(const Inertia &Y, const Constraint &cru)
MotionDerived::MotionPlain operator+(const MotionHelicalUnalignedTpl< S1, O1 > &m1, const MotionDense< MotionDerived > &m2)
MotionAlgebraAction< JointMotionSubspaceHelicalUnalignedTpl, MotionDerived >::ReturnType motionAction(const MotionDense< MotionDerived > &m) const
TransposeConst transpose() const
ReturnTypeNotDefined ReturnType
void setIndexes(JointIndex id, int q, int v)
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef JointHelicalUnalignedTpl< _Scalar, _Options > JointDerived
MotionPlain se3Action_impl(const SE3Tpl< S2, O2 > &m) const
Return type of the ation of a Motion onto an object of type D.
Eigen::Matrix< Scalar, 3, 1, Options > Vector3
InertiaTpl< S1, O1 > Inertia
TridiagonalSymmetricMatrixApplyOnTheLeftReturnType< LhsMatrixType, TridiagonalSymmetricMatrixTpl< S, O > > operator*(const Eigen::MatrixBase< LhsMatrixType > &lhs, const TridiagonalSymmetricMatrixTpl< S, O > &rhs)
Eigen::Matrix< Scalar, 6, 1, Options > DenseBase
traits< JointMotionSubspaceHelicalUnalignedTpl >::Vector3 Vector3
const typedef Vector3 ConstAngularType
ConstLinearType linear() const
const std::vector< bool > hasConfigurationLimit() const
Eigen::Matrix< Scalar, 3, 1, Options > Vector3
const std::vector< bool > hasConfigurationLimitInTangent() const
MotionPlain motionAction(const MotionDense< M1 > &v) const
#define PINOCCHIO_JOINT_DATA_BASE_DEFAULT_ACCESSOR
void addTo(MotionDense< MotionDerived > &v) const
const JointMotionSubspaceHelicalUnalignedTpl & ref
std::string shortname() const
static std::string classname()
Eigen::Matrix< Scalar, 6, 6, Options > Matrix6
Symmetric3Tpl< Scalar, Options > Symmetric3
JointMotion __mult__(const Eigen::MatrixBase< Vector1Like > &v) const
MotionTpl< Scalar, Options > ReturnType
EIGEN_MAKE_ALIGNED_OPERATOR_NEW MOTION_TYPEDEF_TPL(MotionHelicalUnalignedTpl)
MotionPlain PlainReturnType
ReturnTypeNotDefined ReturnType
bool isEqual_impl(const MotionHelicalUnalignedTpl &other) const
PINOCCHIO_JOINT_CAST_TYPE_SPECIALIZATION(JointModelFreeFlyerTpl)
Free-flyer joint in .
Eigen::Matrix< Scalar, 3, 1, _Options > Vector3
void calc_aba(JointDataDerived &data, const Eigen::MatrixBase< VectorLike > &armature, const Eigen::MatrixBase< Matrix6Like > &I, const bool update_I) const
DenseBase MatrixReturnType
Eigen::Matrix< Scalar, NV, NV, Options > D_t
DenseBase matrix_impl() const
MotionHelicalUnalignedTpl< Scalar, Options > JointMotion
JointModelBase< JointModelHelicalUnalignedTpl > Base
JointMotionSubspaceHelicalUnalignedTpl(const Eigen::MatrixBase< Vector3Like > &axis, const Scalar &h)
JointMotionSubspaceHelicalUnalignedTpl< Scalar, Options > Constraint
PINOCCHIO_JOINT_DATA_TYPEDEF_TEMPLATE(JointDerived)
JointMotionSubspaceHelicalUnalignedTpl()
const Vector3 & axis() const
void se3Action_impl(const SE3Tpl< S2, O2 > &m, MotionDense< D2 > &v) const
Eigen::Matrix< Scalar, 3, 1, Options > Vector3
Eigen::Matrix< Scalar, 6, NV, Options > U_t
Eigen::Matrix< Scalar, 4, 4, Options > Matrix4
SE3GroupAction< JointMotionSubspaceHelicalUnalignedTpl >::ReturnType se3Action(const SE3Tpl< S1, O1 > &m) const
Eigen::Matrix< Scalar, 1, 1, Options > JointForce
const typedef DenseBase ConstMatrixReturnType
MotionTpl< Scalar, Options > ReturnType
MotionZeroTpl< Scalar, Options > Bias_t
MultiplicationOp< Inertia, Constraint >::ReturnType ReturnType
JointDataHelicalUnalignedTpl(const Eigen::MatrixBase< Vector3Like > &axis)
MotionHelicalUnalignedTpl()
MotionPlain se3ActionInverse_impl(const SE3Tpl< S2, O2 > &m) const
ConstraintForceOp< JointMotionSubspaceHelicalUnalignedTpl, ForceDerived >::ReturnType operator*(const ForceDense< ForceDerived > &f) const
std::string shortname() const
void toRotationMatrix(const Eigen::MatrixBase< Vector3 > &axis, const Scalar &cos_value, const Scalar &sin_value, const Eigen::MatrixBase< Matrix3 > &res)
Computes a rotation matrix from a vector and values of sin and cos orientations values.
PINOCCHIO_JOINT_DATA_BASE_DEFAULT_ACCESSOR ConfigVector_t joint_q
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > const Eigen::MatrixBase< TangentVectorType > & v
bool comparison_eq(const LhsType &lhs_value, const RhsType &rhs_value)
Matrix4 HomogeneousMatrixType
Return type of the Constraint::Transpose * ForceSet operation.
SE3Tpl< Scalar, Options > Transformation_t
PINOCCHIO_JOINT_TYPEDEF_TEMPLATE(JointDerived)
JointMotionSubspaceHelicalUnalignedTpl< S2, O2 > Constraint
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef JointHelicalUnalignedTpl< _Scalar, _Options > JointDerived
Eigen::Matrix< Scalar, 6, NV, Options > UD_t
Eigen::Matrix< Scalar, 6, 1, Options > ReturnType
void setTo(MotionDense< MotionDerived > &m) const
JointModelHelicalUnalignedTpl(const Scalar &x, const Scalar &y, const Scalar &z, const Scalar &h)
JointModelHelicalUnalignedTpl(const Eigen::MatrixBase< Vector3Like > &axis)
EIGEN_STRONG_INLINE MotionDerived::MotionPlain operator^(const MotionDense< MotionDerived > &m1, const MotionHelicalUnalignedTpl< S2, O2 > &m2)
static std::string classname()
#define PINOCCHIO_CONSTRAINT_TYPEDEF_TPL(DERIVED)
PlainReturnType plain() const
bool isEqual(const JointMotionSubspaceHelicalUnalignedTpl &other) const
const Vector3 & axis() const
Common traits structure to fully define base classes for CRTP.
Eigen::Matrix< Scalar, 6, 1, Options > Vector6
JointDataDerived createData() const
void se3ActionInverse_impl(const SE3Tpl< S2, O2 > &m, MotionDense< D2 > &v) const
#define PINOCCHIO_EIGEN_REF_TYPE(D)
Eigen::Matrix< Scalar, 6, 1 > ReturnType
JointModelHelicalUnalignedTpl(const Eigen::MatrixBase< Vector3Like > &axis, const Scalar &h)
const typedef Eigen::Matrix< Scalar, 6, 1 > ReturnType
Eigen::Matrix< S2, 6, 1, O2 > ReturnType
const Scalar & angularRate() const
void calc(JointDataDerived &data, const Blank, const typename Eigen::MatrixBase< TangentVector > &vs) const
JointMotionSubspaceHelicalUnalignedTpl< Scalar, Options > Constraint_t
JointModelHelicalUnalignedTpl< NewScalar, Options > cast() const
const typedef Vector3 ConstLinearType
TransposeConst(const JointMotionSubspaceHelicalUnalignedTpl &ref)
void motionAction(const MotionDense< M1 > &v, MotionDense< M2 > &mout) const
bool isEqual(const JointModelBase< OtherDerived > &) const
const Scalar & linearRate() const
void normalize(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const Eigen::MatrixBase< ConfigVectorType > &qout)
Normalize a configuration vector.
ConstAngularType angular() const
Cast scalar type from type FROM to type TO.
JointModelHelicalUnalignedTpl< Scalar, Options > JointModelDerived
MotionHelicalUnalignedTpl(const Eigen::MatrixBase< Vector3Like > &axis, const OtherScalar &w, const OtherScalar &v)
Main pinocchio namespace.
MotionHelicalUnalignedTpl< Scalar, Options > Motion_t
pinocchio
Author(s):
autogenerated on Fri Nov 1 2024 02:41:45