6 #ifndef __pinocchio_joint_prismatic_hpp__ 7 #define __pinocchio_joint_prismatic_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/spatial-axis.hpp" 14 #include "pinocchio/utils/axis-label.hpp" 21 template<
typename Scalar,
int Options,
int axis>
27 template<
typename Scalar,
int Options,
int axis,
typename MotionDerived>
33 template<
typename _Scalar,
int _Options,
int _axis>
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,
int _axis>
60 :
MotionBase < MotionPrismaticTpl<_Scalar,_Options,_axis> >
62 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
73 inline PlainReturnType
plain()
const {
return Axis() * m_v; }
75 template<
typename OtherScalar>
81 template<
typename Derived>
85 other.
linear()[_axis] += (OtherScalar) m_v;
88 template<
typename MotionDerived>
91 for(Eigen::DenseIndex k = 0; k < 3; ++k)
96 template<
typename S2,
int O2,
typename D2>
103 template<
typename S2,
int O2>
107 se3Action_impl(m,res);
111 template<
typename S2,
int O2,
typename D2>
121 template<
typename S2,
int O2>
125 se3ActionInverse_impl(m,res);
129 template<
typename M1,
typename M2>
139 template<
typename M1>
152 return m_v == other.
m_v;
160 template<
typename Scalar,
int Options,
int axis,
typename MotionDerived>
161 typename MotionDerived::MotionPlain
165 typename MotionDerived::MotionPlain
res(m2);
170 template<
typename MotionDerived,
typename S2,
int O2,
int axis>
172 typename MotionDerived::MotionPlain
180 template<
typename _Scalar,
int _Options,
int _axis>
191 typedef Eigen::Matrix<Scalar,3,1,Options>
Vector3;
192 typedef Eigen::Matrix<Scalar,3,3,Options>
Matrix3;
203 template<
typename Scalar,
int Options,
int axis>
207 template<
typename _Scalar,
int _Options,
int axis>
210 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
218 : m_displacement(displacement)
223 PlainType
res(PlainType::Identity());
224 res.rotation().setIdentity();
225 res.translation()[
axis] = m_displacement;
230 operator PlainType()
const {
return plain(); }
232 template<
typename S2,
int O2>
238 res.translation()[
axis] += m_displacement;
246 ConstLinearRef
translation()
const {
return CartesianAxis3()*displacement(); };
247 AngularType
rotation()
const {
return AngularType(3,3); }
261 template<
typename _Scalar,
int _Options,
int axis>
277 template<
typename Scalar,
int Options,
int axis>
281 template<
typename Scalar,
int Options,
int axis,
typename MotionDerived>
285 template<
typename Scalar,
int Options,
int axis,
typename ForceDerived>
289 template<
typename Scalar,
int Options,
int axis,
typename ForceSet>
291 {
typedef typename Eigen::MatrixBase<ForceSet>::ConstRowXpr
ReturnType; };
293 template<
typename _Scalar,
int _Options,
int axis>
295 :
ConstraintBase < ConstraintPrismaticTpl <_Scalar,_Options,axis> >
297 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
305 template<
typename Vector1Like>
306 JointMotion
__mult__(
const Eigen::MatrixBase<Vector1Like> &
v)
const 308 EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Vector1Like,1);
309 assert(v.size() == 1);
310 return JointMotion(v[0]);
313 template<
typename S2,
int O2>
324 template<
typename S2,
int O2>
342 template<
typename ForceDerived>
345 {
return f.
linear().template segment<1>(
axis); }
348 template<
typename Derived>
353 return F.row(LINEAR+
axis);
373 template<
typename MotionDerived>
387 template<
typename S1,
int O1,
typename S2,
int O2,
int axis>
396 template<
typename S1,
int O1,
typename S2,
int O2>
402 static inline ReturnType
run(
const Inertia &
Y,
412 res << m, S1(0), S1(0), S1(0), m*z, -m*
y;
418 template<
typename S1,
int O1,
typename S2,
int O2>
424 static inline ReturnType
run(
const Inertia &
Y,
435 res << S1(0), m, S1(0), -m*z, S1(0), m*
x;
441 template<
typename S1,
int O1,
typename S2,
int O2>
447 static inline ReturnType
run(
const Inertia &
Y,
458 res << S1(0), S1(0), m, m*
y, -m*
x, S1(0);
465 template<
typename M6Like,
typename S2,
int O2,
int axis>
474 template<
typename M6Like,
typename Scalar,
int Options,
int axis>
479 static inline ReturnType
run(
const Eigen::MatrixBase<M6Like> &
Y,
482 EIGEN_STATIC_ASSERT_MATRIX_SPECIFIC_SIZE(M6Like,6,6);
483 return Y.derived().col(Inertia::LINEAR +
axis);
488 template<
typename _Scalar,
int _Options,
int _axis>
500 template<
typename _Scalar,
int _Options,
int axis>
517 typedef Eigen::Matrix<Scalar,6,NV,Options>
U_t;
518 typedef Eigen::Matrix<Scalar,NV,NV,Options>
D_t;
519 typedef Eigen::Matrix<Scalar,6,NV,Options>
UD_t;
527 template<
typename Scalar,
int Options,
int axis>
531 template<
typename Scalar,
int Options,
int axis>
535 template<
typename _Scalar,
int _Options,
int axis>
538 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
558 , UDinv(UD_t::Zero())
563 return std::string(
"JointDataP") + axisLabel<axis>();
569 template<
typename NewScalar,
typename Scalar,
int Options,
int axis>
575 template<
typename _Scalar,
int _Options,
int axis>
577 :
public JointModelBase< JointModelPrismaticTpl<_Scalar,_Options,axis> >
579 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
589 JointDataDerived
createData()
const {
return JointDataDerived(); }
601 template<
typename ConfigVector>
603 const typename Eigen::MatrixBase<ConfigVector> &
qs)
const 606 const Scalar &
q = qs[
idx_q()];
607 data.M.displacement() =
q;
610 template<
typename ConfigVector,
typename TangentVector>
612 const typename Eigen::MatrixBase<ConfigVector> &
qs,
613 const typename Eigen::MatrixBase<TangentVector> & vs)
const 615 calc(data,qs.derived());
618 const S2 &
v = vs[
idx_v()];
619 data.v.linearRate() =
v;
622 template<
typename Matrix6Like>
623 void calc_aba(JointDataDerived &
data,
const Eigen::MatrixBase<Matrix6Like> & I,
const bool update_I)
const 625 data.U = I.col(Inertia::LINEAR +
axis);
626 data.Dinv[0] =
Scalar(1)/I(Inertia::LINEAR +
axis, Inertia::LINEAR +
axis);
627 data.UDinv.noalias() = data.U * data.Dinv[0];
635 return std::string(
"JointModelP") + axisLabel<axis>();
640 template<
typename NewScalar>
665 #include <boost/type_traits.hpp> 669 template<
typename Scalar,
int Options,
int axis>
671 :
public integral_constant<bool,true> {};
673 template<
typename Scalar,
int Options,
int axis>
675 :
public integral_constant<bool,true> {};
677 template<
typename Scalar,
int Options,
int axis>
679 :
public integral_constant<bool,true> {};
681 template<
typename Scalar,
int Options,
int axis>
683 :
public integral_constant<bool,true> {};
686 #endif // ifndef __pinocchio_joint_prismatic_hpp__ JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > const Eigen::MatrixBase< TangentVectorType > & v
ConstraintPrismaticTpl< Scalar, Options, axis > Constraint_t
#define PINOCCHIO_SE3_TYPEDEF_TPL(Derived)
MotionPrismaticTpl< Scalar, Options, axis > Motion_t
JointModelPrismaticTpl< double, 0, 0 > JointModelPX
void setTo(MotionDense< MotionDerived > &other) const
Forward declaration of the multiplication operation return type. Should be overloaded, otherwise it will procude a compilation error.
PlainReturnType plain() const
MotionPrismaticTpl __mult__(const OtherScalar &alpha) const
JointMotion __mult__(const Eigen::MatrixBase< Vector1Like > &v) const
MultiplicationOp< Inertia, Constraint >::ReturnType ReturnType
std::string shortname() const
TransposeConst transpose() const
const DenseBase ConstMatrixReturnType
const Vector3 ConstAngularType
int idx_q(const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel)
Visit a JointModelTpl through JointIdxQVisitor to get the index in the full model configuration space...
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...
MotionAlgebraAction< ConstraintPrismaticTpl, MotionDerived >::ReturnType motionAction(const MotionDense< MotionDerived > &m) const
Return type of the Constraint::Transpose * ForceSet operation.
JointPrismaticTpl< double, 0, 1 > JointPY
MotionTpl< Scalar, Options > ReturnType
Return type of the ation of a Motion onto an object of type D.
DenseBase MatrixReturnType
#define MOTION_TYPEDEF_TPL(Derived)
PINOCCHIO_EIGEN_REF_CONST_TYPE(Matrix6Like) operator*(const Eigen
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef JointPrismaticTpl< _Scalar, _Options, axis > JointDerived
void motionAction(const MotionDense< M1 > &v, MotionDense< M2 > &mout) const
SpatialAxis< LINEAR+axis > Axis
const Vector3 & lever() const
JointModelPrismaticTpl< double, 0, 1 > JointModelPY
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
MotionPlain se3ActionInverse_impl(const SE3Tpl< S2, O2 > &m) const
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef JointPrismaticTpl< _Scalar, _Options, axis > JointDerived
Eigen::Matrix< Scalar, 3, 1, Options > Vector3
static ReturnType run(const Inertia &Y, const Constraint &)
static std::string classname()
const std::vector< bool > hasConfigurationLimitInTangent() const
JointDataPrismaticTpl< double, 0, 0 > JointDataPX
ConstraintPrismaticTpl< S2, O2, 0 > Constraint
InertiaTpl< S1, O1 > Inertia
JointModelBase< JointModelPrismaticTpl > Base
static ReturnType run(const Inertia &Y, const Constraint &)
std::string shortname() const
ForceDense< ForceDerived >::ConstLinearType::template ConstFixedSegmentReturnType< 1 >::Type ReturnType
void calc_aba(JointDataDerived &data, const Eigen::MatrixBase< Matrix6Like > &I, const bool update_I) const
SE3GroupAction< ConstraintPrismaticTpl >::ReturnType se3ActionInverse(const SE3Tpl< S2, O2 > &m) const
ConstLinearType linear() const
Eigen::Matrix< Scalar, 6, NV, Options > U_t
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > & q
#define PINOCCHIO_EIGEN_CONST_CAST(TYPE, OBJ)
Macro for an automatic const_cast.
Eigen::Matrix< Scalar, 6, 1, Options > Vector6
PINOCCHIO_JOINT_DATA_BASE_DEFAULT_ACCESSOR Constraint_t S
MotionDerived::MotionPlain operator+(const MotionPlanarTpl< Scalar, Options > &m1, const MotionDense< MotionDerived > &m2)
static ReturnType run(const Inertia &Y, const Constraint &)
JointDataDerived createData() const
ConstAngularType angular() const
MotionAlgebraAction< OtherSpatialType, Derived >::ReturnType cross(const OtherSpatialType &d) const
JointPrismaticTpl< Scalar, Options, axis > JointDerived
const ConstraintPrismaticTpl & ref
Eigen::Matrix< Scalar, 6, 1, Options > DenseBase
MotionPrismaticTpl< Scalar, Options, axis > JointMotion
JointModelPrismaticTpl< Scalar, Options, axis > JointModelDerived
ConstraintPrismaticTpl< Scalar, Options, axis > Constraint
void calc(JointDataDerived &data, const typename Eigen::MatrixBase< ConfigVector > &qs) const
MotionPlain se3Action_impl(const SE3Tpl< S2, O2 > &m) const
#define PINOCCHIO_JOINT_DATA_BASE_ACCESSOR_DEFAULT_RETURN_TYPE
InertiaTpl< S1, O1 > Inertia
void calc(JointDataDerived &data, const typename Eigen::MatrixBase< ConfigVector > &qs, const typename Eigen::MatrixBase< TangentVector > &vs) const
MotionPrismaticTpl(const Scalar &v)
void se3ActionInverse_impl(const SE3Tpl< S2, O2 > &m, MotionDense< D2 > &v) const
const std::vector< bool > hasConfigurationLimit() const
JointPrismaticTpl< double, 0, 0 > JointPX
JointDataPrismaticTpl< Scalar, Options, axis > JointDataDerived
MultiplicationOp< Eigen::MatrixBase< M6Like >, Constraint >::ReturnType ReturnType
#define PINOCCHIO_JOINT_DATA_TYPEDEF_TEMPLATE(Joint)
Eigen::Matrix< Scalar, 6, 1, Options > ReturnType
MotionZeroTpl< Scalar, Options > Bias_t
JointDataPrismaticTpl< double, 0, 1 > JointDataPY
static std::string classname()
void se3Action_impl(const SE3Tpl< S2, O2 > &m, MotionDense< D2 > &v) const
Axis::CartesianAxis3 CartesianAxis3
JointPrismaticTpl< Scalar, Options, axis > JointDerived
MultiplicationOp< Inertia, Constraint >::ReturnType ReturnType
Eigen::Matrix< Scalar, 6, 1, Options > ReturnType
bool isEqual_impl(const MotionPrismaticTpl &other) const
Eigen::Matrix< Scalar, NV, NV, Options > D_t
const Vector3 ConstLinearType
Eigen::Matrix< Scalar, 6, NV, Options > UD_t
ConstraintForceSetOp< ConstraintPrismaticTpl, Derived >::ReturnType operator*(const Eigen::MatrixBase< Derived > &F)
JointModelPrismaticTpl< NewScalar, Options, axis > cast() const
Matrix4 HomogeneousMatrixType
void addTo(MotionDense< Derived > &other) const
bool isEqual(const ConstraintPrismaticTpl &) const
JointModelPrismaticTpl< NewScalar, Options, axis > type
ConstraintPrismaticTpl< S2, O2, 2 > Constraint
ConstLinearType linear() const
Return the linear part of the force vector.
MotionPlain motionAction(const MotionDense< M1 > &v) const
Eigen::Matrix< Scalar, NV, 1, Options > TangentVector_t
#define PINOCCHIO_EIGEN_REF_TYPE(D)
ConstraintPrismaticTpl< S2, O2, 1 > Constraint
ConstAngularRef rotation() const
M6Like::ConstColXpr ReturnType
Main pinocchio namespace.
ReturnTypeNotDefined ReturnType
Base class for rigid transformation.
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...
MotionTpl< Scalar, Options > ReturnType
Eigen::Matrix< Scalar, 6, 6, Options > Matrix6
JointModelPrismaticTpl< double, 0, 2 > JointModelPZ
Common traits structure to fully define base classes for CRTP.
Eigen::Matrix< S2, 6, 1, O2 > ReturnType
JointDataPrismaticTpl< double, 0, 2 > JointDataPZ
PINOCCHIO_JOINT_DATA_BASE_ACCESSOR_DEFAULT_RETURN_TYPE typedef Eigen::Matrix< Scalar, NQ, 1, Options > ConfigVector_t
InertiaTpl< S1, O1 > Inertia
MotionTpl< Scalar, Options > MotionPlain
MotionPlain PlainReturnType
TransformPrismaticTpl< Scalar, Options, axis > Transformation_t
#define PINOCCHIO_CONSTRAINT_TYPEDEF_TPL(DERIVED)
Eigen::Matrix< Scalar, 4, 4, Options > Matrix4
Eigen::MatrixBase< ForceSet >::ConstRowXpr ReturnType
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...
MultiplicationOp< Inertia, Constraint >::ReturnType ReturnType
static ReturnType run(const Eigen::MatrixBase< M6Like > &Y, const Constraint &)
const Scalar & linearRate() const
Type of the cast of a class C templated by Scalar and Options, to a new NewScalar type...
Eigen::Matrix< Scalar, 1, 1, Options > JointForce
SE3GroupAction< ConstraintPrismaticTpl >::ReturnType se3Action(const SE3Tpl< S2, O2 > &m) const
MotionDerived::MotionPlain operator^(const MotionDense< MotionDerived > &m1, const MotionPlanarTpl< S2, O2 > &m2)
SpatialAxis< _axis+LINEAR > Axis
DenseBase matrix_impl() const
Return type of the Constraint::Transpose * Force operation.
MatrixDerived plain(const Eigen::PlainObjectBase< MatrixDerived > &m)
ReturnTypeNotDefined ReturnType
JointPrismaticTpl< double, 0, 2 > JointPZ
MultiplicationOp< InertiaTpl< Scalar, Options >, ConstraintDerived >::ReturnType operator*(const InertiaTpl< Scalar, Options > &Y, const ConstraintBase< ConstraintDerived > &constraint)
.
TransposeConst(const ConstraintPrismaticTpl &ref)
#define PINOCCHIO_JOINT_TYPEDEF_TEMPLATE(Joint)