Go to the documentation of this file.
6 #ifndef __pinocchio_multibody_joint_prismatic_hpp__
7 #define __pinocchio_multibody_joint_prismatic_hpp__
19 template<
typename Scalar,
int Options,
int _axis>
22 template<
typename Scalar,
int Options,
int axis>
28 template<
typename Scalar,
int Options,
int axis,
typename MotionDerived>
34 template<
typename _Scalar,
int _Options,
int _axis>
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,
int _axis>
64 struct MotionPrismaticTpl : MotionBase<MotionPrismaticTpl<_Scalar, _Options, _axis>>
66 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
85 inline PlainReturnType
plain()
const
90 template<
typename OtherScalar>
96 template<
typename Derived>
100 other.
linear()[_axis] += (OtherScalar)
m_v;
103 template<
typename MotionDerived>
106 for (Eigen::DenseIndex k = 0; k < 3; ++k)
113 template<
typename S2,
int O2,
typename D2>
116 v.angular().setZero();
117 v.linear().noalias() =
m_v * (
m.rotation().col(
axis));
120 template<
typename S2,
int O2>
128 template<
typename S2,
int O2,
typename D2>
132 v.linear().noalias() =
m_v * (
m.rotation().transpose().col(
axis));
135 v.angular().setZero();
138 template<
typename S2,
int O2>
146 template<
typename M1,
typename M2>
156 template<
typename M1>
182 template<
typename Scalar,
int Options,
int axis,
typename MotionDerived>
186 typename MotionDerived::MotionPlain
res(m2);
191 template<
typename MotionDerived,
typename S2,
int O2,
int axis>
192 EIGEN_STRONG_INLINE
typename MotionDerived::MotionPlain
195 return m2.motionAction(m1);
198 template<
typename Scalar,
int Options,
int axis>
201 template<
typename _Scalar,
int _Options,
int _axis>
213 typedef Eigen::Matrix<Scalar, 3, 1, Options>
Vector3;
214 typedef Eigen::Matrix<Scalar, 3, 3, Options>
Matrix3;
225 template<
typename Scalar,
int Options,
int axis>
231 template<
typename _Scalar,
int _Options,
int axis>
234 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
250 PlainType
res(PlainType::Identity());
251 res.rotation().setIdentity();
257 operator PlainType()
const
262 template<
typename S2,
int O2>
288 return AngularType(3, 3);
300 template<
typename Scalar,
int Options,
int axis>
303 template<
typename _Scalar,
int _Options,
int axis>
327 template<
typename Scalar,
int Options,
int axis>
333 template<
typename Scalar,
int Options,
int axis,
typename MotionDerived>
339 template<
typename Scalar,
int Options,
int axis,
typename ForceDerived>
343 ForceDerived>::ConstLinearType::template ConstFixedSegmentReturnType<1>::Type
ReturnType;
346 template<
typename Scalar,
int Options,
int axis,
typename ForceSet>
349 typedef typename Eigen::MatrixBase<ForceSet>::ConstRowXpr
ReturnType;
352 template<
typename _Scalar,
int _Options,
int axis>
356 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
367 template<
typename Vector1Like>
368 JointMotion
__mult__(
const Eigen::MatrixBase<Vector1Like> &
v)
const
370 EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Vector1Like, 1);
371 assert(
v.size() == 1);
372 return JointMotion(
v[0]);
375 template<
typename S2,
int O2>
381 v.linear() =
m.rotation().col(
axis);
382 v.angular().setZero();
386 template<
typename S2,
int O2>
392 v.linear() =
m.rotation().transpose().col(
axis);
393 v.angular().setZero();
410 template<
typename ForceDerived>
414 return f.linear().template segment<1>(
axis);
418 template<
typename Derived>
422 assert(F.rows() == 6);
423 return F.row(LINEAR +
axis);
446 template<
typename MotionDerived>
463 template<
typename S1,
int O1,
typename S2,
int O2,
int axis>
472 template<
typename S1,
int O1,
typename S2,
int O2>
483 const S1 &
m =
Y.mass(), &
y =
Y.lever()[1], &z =
Y.lever()[2];
484 res <<
m, S1(0), S1(0), S1(0),
m * z, -
m *
y;
490 template<
typename S1,
int O1,
typename S2,
int O2>
501 const S1 &
m =
Y.mass(), &
x =
Y.lever()[0], &z =
Y.lever()[2];
503 res << S1(0),
m, S1(0), -
m * z, S1(0),
m *
x;
509 template<
typename S1,
int O1,
typename S2,
int O2>
520 const S1 &
m =
Y.mass(), &
x =
Y.lever()[0], &
y =
Y.lever()[1];
522 res << S1(0), S1(0),
m,
m *
y, -
m *
x, S1(0);
529 template<
typename M6Like,
typename S2,
int O2,
int axis>
538 template<
typename M6Like,
typename Scalar,
int Options,
int axis>
540 Eigen::MatrixBase<M6Like>,
549 EIGEN_STATIC_ASSERT_MATRIX_SPECIFIC_SIZE(M6Like, 6, 6);
550 return Y.derived().col(Inertia::LINEAR +
axis);
555 template<
typename _Scalar,
int _Options,
int _axis>
567 template<
typename _Scalar,
int _Options,
int axis>
588 typedef Eigen::Matrix<Scalar, 6, NV, Options>
U_t;
589 typedef Eigen::Matrix<Scalar, NV, NV, Options>
D_t;
590 typedef Eigen::Matrix<Scalar, 6, NV, Options>
UD_t;
598 template<
typename _Scalar,
int _Options,
int axis>
605 template<
typename _Scalar,
int _Options,
int axis>
612 template<
typename _Scalar,
int _Options,
int axis>
614 :
public JointDataBase<JointDataPrismaticTpl<_Scalar, _Options, axis>>
616 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
636 :
joint_q(ConfigVector_t::Zero())
637 ,
joint_v(TangentVector_t::Zero())
642 ,
UDinv(UD_t::Zero())
649 return std::string(
"JointDataP") + axisLabel<axis>();
658 template<
typename NewScalar,
typename Scalar,
int Options,
int axis>
664 template<
typename _Scalar,
int _Options,
int axis>
666 :
public JointModelBase<JointModelPrismaticTpl<_Scalar, _Options, axis>>
668 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
678 typedef Eigen::Matrix<Scalar, 3, 1, _Options>
Vector3;
682 return JointDataDerived();
695 template<
typename ConfigVector>
696 void calc(JointDataDerived &
data,
const typename Eigen::MatrixBase<ConfigVector> &
qs)
const
699 data.M.displacement() =
data.joint_q[0];
702 template<
typename TangentVector>
704 calc(JointDataDerived &
data,
const Blank,
const typename Eigen::MatrixBase<TangentVector> & vs)
708 data.v.linearRate() =
data.joint_v[0];
711 template<
typename ConfigVector,
typename TangentVector>
713 JointDataDerived &
data,
714 const typename Eigen::MatrixBase<ConfigVector> &
qs,
715 const typename Eigen::MatrixBase<TangentVector> & vs)
const
720 data.v.linearRate() =
data.joint_v[0];
723 template<
typename VectorLike,
typename Matrix6Like>
725 JointDataDerived &
data,
726 const Eigen::MatrixBase<VectorLike> & armature,
727 const Eigen::MatrixBase<Matrix6Like> & I,
728 const bool update_I)
const
730 data.U = I.col(Inertia::LINEAR +
axis);
731 data.Dinv[0] =
Scalar(1) / (I(Inertia::LINEAR +
axis, Inertia::LINEAR +
axis) + armature[0]);
740 return std::string(
"JointModelP") + axisLabel<axis>();
752 return Vector3::UnitX();
754 return Vector3::UnitY();
756 return Vector3::UnitZ();
758 assert(
false &&
"must never happen");
764 template<
typename NewScalar>
789 #include <boost/type_traits.hpp>
793 template<
typename Scalar,
int Options,
int axis>
795 :
public integral_constant<bool, true>
799 template<
typename Scalar,
int Options,
int axis>
801 :
public integral_constant<bool, true>
805 template<
typename Scalar,
int Options,
int axis>
807 :
public integral_constant<bool, true>
811 template<
typename Scalar,
int Options,
int axis>
813 :
public integral_constant<bool, true>
818 #endif // ifndef __pinocchio_multibody_joint_prismatic_hpp__
MotionPrismaticTpl< Scalar, Options, axis > Motion_t
void calc_aba(JointDataDerived &data, const Eigen::MatrixBase< VectorLike > &armature, const Eigen::MatrixBase< Matrix6Like > &I, const bool update_I) const
Eigen::Matrix< Scalar, 6, NV, Options > U_t
std::string shortname() const
#define PINOCCHIO_JOINT_DATA_BASE_ACCESSOR_DEFAULT_RETURN_TYPE
void se3ActionInverse_impl(const SE3Tpl< S2, O2 > &m, MotionDense< D2 > &v) const
Forward declaration of the multiplication operation return type. Should be overloaded,...
const typedef Vector3 ConstLinearType
JointMotionSubspacePrismaticTpl< S2, O2, 0 > Constraint
JointPrismaticTpl< context::Scalar, context::Options, 0 > JointPX
Eigen::Matrix< Scalar, 3, 1, _Options > Vector3
bool isEqual_impl(const MotionPrismaticTpl &other) const
PINOCCHIO_JOINT_DATA_TYPEDEF_TEMPLATE(JointDerived)
JointDataPrismaticTpl< Scalar, Options, axis > JointDataDerived
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_MAKE_ALIGNED_OPERATOR_NEW typedef JointPrismaticTpl< _Scalar, _Options, axis > JointDerived
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...
Axis::CartesianAxis3 CartesianAxis3
#define PINOCCHIO_EIGEN_CONST_CAST(TYPE, OBJ)
Macro for an automatic const_cast.
PINOCCHIO_EIGEN_REF_CONST_TYPE(Matrix6Like) operator*(const Eigen
static ReturnType run(const Eigen::MatrixBase< M6Like > &Y, const Constraint &)
void addTo(MotionDense< Derived > &other) const
void calc(JointDataDerived &data, const typename Eigen::MatrixBase< ConfigVector > &qs) const
InertiaTpl< S1, O1 > Inertia
ConstraintForceSetOp< JointMotionSubspacePrismaticTpl, Derived >::ReturnType operator*(const Eigen::MatrixBase< Derived > &F)
Vector3 getMotionAxis() const
JointModelPrismaticTpl< NewScalar, Options, axis > cast() const
MotionPlain motionAction(const MotionDense< M1 > &v) const
JointModelPrismaticTpl< Scalar, Options, axis > JointModelDerived
const Scalar & linearRate() const
MotionDerived::MotionPlain operator+(const MotionHelicalUnalignedTpl< S1, O1 > &m1, const MotionDense< MotionDerived > &m2)
MultiplicationOp< Inertia, Constraint >::ReturnType ReturnType
static ReturnType run(const Inertia &Y, const Constraint &)
void calc(JointDataDerived &data, const Blank, const typename Eigen::MatrixBase< TangentVector > &vs) const
ReturnTypeNotDefined ReturnType
void setIndexes(JointIndex id, int q, int v)
const std::vector< bool > hasConfigurationLimit() const
JointPrismaticTpl< context::Scalar, context::Options, 1 > JointPY
MotionAlgebraAction< JointMotionSubspacePrismaticTpl, MotionDerived >::ReturnType motionAction(const MotionDense< MotionDerived > &m) const
static std::string classname()
Return type of the ation of a Motion onto an object of type D.
SE3GroupAction< JointMotionSubspacePrismaticTpl >::ReturnType se3Action(const SE3Tpl< S2, O2 > &m) const
MotionPrismaticTpl __mult__(const OtherScalar &alpha) const
const JointMotionSubspacePrismaticTpl & ref
ConstLinearType linear() const
const typedef Vector3 ConstAngularType
#define PINOCCHIO_JOINT_DATA_BASE_DEFAULT_ACCESSOR
SE3GroupAction< JointMotionSubspacePrismaticTpl >::ReturnType se3ActionInverse(const SE3Tpl< S2, O2 > &m) const
JointMotionSubspacePrismaticTpl()
M6Like::ConstColXpr ReturnType
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef JointPrismaticTpl< _Scalar, _Options, axis > JointDerived
ReturnTypeNotDefined ReturnType
InertiaTpl< S1, O1 > Inertia
const typedef DenseBase ConstMatrixReturnType
Eigen::Matrix< Scalar, 1, 1, Options > ReducedSquaredMatrix
Eigen::Matrix< Scalar, 6, NV, Options > UD_t
std::string shortname() const
ReducedSquaredMatrix::IdentityReturnType StDiagonalMatrixSOperationReturnType
JointMotionSubspacePrismaticTpl< Scalar, Options, axis > Constraint_t
TransformPrismaticTpl< Scalar, Options, axis > Transformation_t
MotionTpl< Scalar, Options > MotionPlain
bool isEqual(const JointMotionSubspacePrismaticTpl &) const
void setTo(MotionDense< MotionDerived > &other) const
JointDataPrismaticTpl< context::Scalar, context::Options, 1 > JointDataPY
JointModelPrismaticTpl< context::Scalar, context::Options, 1 > JointModelPY
Eigen::Matrix< Scalar, 6, 6, Options > Matrix6
static ReturnType run(const Inertia &Y, const Constraint &)
SpatialAxis< LINEAR+axis > Axis
ForceDense< ForceDerived >::ConstLinearType::template ConstFixedSegmentReturnType< 1 >::Type ReturnType
const std::vector< bool > hasConfigurationLimitInTangent() const
JointModelPrismaticTpl< context::Scalar, context::Options, 2 > JointModelPZ
ConstraintForceOp< JointMotionSubspacePrismaticTpl, ForceDerived >::ReturnType operator*(const ForceDense< ForceDerived > &f) const
Eigen::MatrixBase< ForceSet >::ConstRowXpr ReturnType
JointModelBase< JointModelPrismaticTpl > Base
JointDataPrismaticTpl< context::Scalar, context::Options, 0 > JointDataPX
MotionPlain PlainReturnType
JointPrismaticTpl< _Scalar, _Options, axis > JointDerived
void calc(JointDataDerived &data, const typename Eigen::MatrixBase< ConfigVector > &qs, const typename Eigen::MatrixBase< TangentVector > &vs) const
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > const Eigen::MatrixBase< TangentVectorType > & v
bool comparison_eq(const LhsType &lhs_value, const RhsType &rhs_value)
Eigen::Matrix< Scalar, NV, NV, Options > D_t
Return type of the Constraint::Transpose * ForceSet operation.
PINOCCHIO_JOINT_DATA_BASE_DEFAULT_ACCESSOR ConfigVector_t joint_q
MotionPrismaticTpl(const Scalar &v)
DenseBase matrix_impl() const
MotionPlain se3ActionInverse_impl(const SE3Tpl< S2, O2 > &m) const
Base class for rigid transformation.
MotionZeroTpl< Scalar, Options > Bias_t
JointPrismaticTpl< _Scalar, _Options, axis > JointDerived
JointPrismaticTpl< context::Scalar, context::Options, 2 > JointPZ
JointDataDerived createData() const
Eigen::Matrix< Scalar, 1, 1, Options > JointForce
Eigen::Matrix< Scalar, 6, 1, Options > ReturnType
InertiaTpl< S1, O1 > Inertia
Eigen::Matrix< S2, 6, 1, O2 > ReturnType
PINOCCHIO_JOINT_TYPEDEF_TEMPLATE(JointDerived)
PlainReturnType plain() const
JointModelPrismaticTpl< NewScalar, Options, axis > type
static std::string classname()
Eigen::Matrix< Scalar, NV, 1, Options > TangentVector_t
EIGEN_STRONG_INLINE MotionDerived::MotionPlain operator^(const MotionDense< MotionDerived > &m1, const MotionHelicalUnalignedTpl< S2, O2 > &m2)
Eigen::Matrix< Scalar, 4, 4, Options > Matrix4
#define PINOCCHIO_CONSTRAINT_TYPEDEF_TPL(DERIVED)
MultiplicationOp< Inertia, Constraint >::ReturnType ReturnType
JointMotion __mult__(const Eigen::MatrixBase< Vector1Like > &v) const
SpatialAxis< _axis+LINEAR > Axis
Eigen::Matrix< Scalar, NQ, 1, Options > ConfigVector_t
void motionAction(const MotionDense< M1 > &v, MotionDense< M2 > &mout) const
TransposeConst transpose() const
Matrix4 HomogeneousMatrixType
JointModelPrismaticTpl< context::Scalar, context::Options, 0 > JointModelPX
Common traits structure to fully define base classes for CRTP.
MultiplicationOp< Inertia, Constraint >::ReturnType ReturnType
MultiplicationOp< Eigen::MatrixBase< M6Like >, Constraint >::ReturnType ReturnType
Eigen::Matrix< Scalar, 6, 1, Options > Vector6
#define PINOCCHIO_EIGEN_REF_TYPE(D)
Eigen::Matrix< Scalar, 6, 1, Options > ReturnType
TransposeConst(const JointMotionSubspacePrismaticTpl &ref)
static ReturnType run(const Inertia &Y, const Constraint &)
JointMotionSubspacePrismaticTpl< S2, O2, 2 > Constraint
Type of the cast of a class C templated by Scalar and Options, to a new NewScalar type....
JointMotionSubspacePrismaticTpl< S2, O2, 1 > Constraint
EIGEN_MAKE_ALIGNED_OPERATOR_NEW MOTION_TYPEDEF_TPL(MotionPrismaticTpl)
JointMotionSubspacePrismaticTpl< Scalar, Options, axis > Constraint
Eigen::Matrix< Scalar, 3, 1, Options > Vector3
MotionTpl< Scalar, Options > ReturnType
void se3Action_impl(const SE3Tpl< S2, O2 > &m, MotionDense< D2 > &v) const
Eigen::Matrix< Scalar, 6, 1, Options > DenseBase
DenseBase MatrixReturnType
ConstAngularType angular() const
MotionTpl< Scalar, Options > ReturnType
static void alphaCross(const Scalar &s, const Eigen::MatrixBase< V3_in > &vin, const Eigen::MatrixBase< V3_out > &vout)
Main pinocchio namespace.
JointDataPrismaticTpl< context::Scalar, context::Options, 2 > JointDataPZ
MotionPrismaticTpl< Scalar, Options, axis > JointMotion
MotionPlain se3Action_impl(const SE3Tpl< S2, O2 > &m) const
pinocchio
Author(s):
autogenerated on Fri Nov 1 2024 02:41:46