6 #ifndef __pinocchio_multibody_constraint_generic_hpp__ 7 #define __pinocchio_multibody_constraint_generic_hpp__ 12 template<
int _Dim,
typename _Scalar,
int _Options>
26 typedef Eigen::Matrix<Scalar,6,Dim,Options>
DenseBase;
33 template<
int Dim, typename Scalar,
int Options>
37 template<
int Dim,
typename Scalar,
int Options,
typename MotionDerived>
41 template<
int _Dim,
typename _Scalar,
int _Options>
45 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
61 EIGEN_STATIC_ASSERT_SAME_MATRIX_SIZE(DenseBase,
D);
66 EIGEN_STATIC_ASSERT(_Dim!=Eigen::Dynamic,
67 YOU_CALLED_A_DYNAMIC_SIZE_METHOD_ON_A_FIXED_SIZE_MATRIX_OR_VECTOR)
73 EIGEN_STATIC_ASSERT(_Dim==Eigen::Dynamic,
74 YOU_CALLED_A_FIXED_SIZE_METHOD_ON_A_DYNAMIC_SIZE_MATRIX_OR_VECTOR)
82 template<
typename VectorLike>
83 JointMotion
__mult__(
const Eigen::MatrixBase<VectorLike> & vj)
const 85 return JointMotion(S*vj);
93 template<
typename Derived>
95 {
return (ref.
S.transpose()*f.
toVector()).eval(); }
98 typename Eigen::Matrix<Scalar,NV,Eigen::Dynamic>
101 return (ref.
S.transpose()*F).eval();
113 template<
typename S2,
int O2>
117 typedef typename ConstraintTpl::DenseBase ReturnType;
118 ReturnType
res(6,S.
nv());
123 template<
typename S2,
int O2>
124 friend Eigen::Matrix<_Scalar,6,_Dim>
127 typedef Eigen::Matrix<_Scalar,6,_Dim> ReturnType;
128 return ReturnType(Ymatrix*S.
matrix());
134 DenseBase
res(6,
nv());
141 DenseBase
res(6,
nv());
146 template<
typename MotionDerived>
149 DenseBase
res(6,
nv());
154 void disp_impl(std::ostream & os)
const { os <<
"S =\n" << S << std::endl;}
168 #endif // ifndef __pinocchio_multibody_constraint_generic_hpp__ JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > const Eigen::MatrixBase< TangentVectorType > & v
Transpose(const ConstraintTpl &ref)
int nv(const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel)
Visit a JointModelTpl through JointNvVisitor to get the dimension of the joint tangent space...
friend ConstraintTpl< _Dim, _Scalar, _Options >::DenseBase operator*(const InertiaTpl< S2, O2 > &Y, const ConstraintTpl &S)
const ConstraintTpl & ref
friend Eigen::Matrix< _Scalar, 6, _Dim > operator*(const Eigen::Matrix< S2, 6, 6, O2 > &Ymatrix, const ConstraintTpl &S)
Return type of the ation of a Motion onto an object of type D.
PINOCCHIO_EIGEN_REF_CONST_TYPE(Matrix6Like) operator*(const Eigen
JointMotion __mult__(const Eigen::MatrixBase< VectorLike > &vj) const
ToVectorConstReturnType toVector() const
Return the force as an Eigen vector.
ConstraintTpl(const Eigen::MatrixBase< D > &_S)
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef ConstraintBase< ConstraintTpl > Base
Eigen::Matrix< Scalar, 6, Dim > ReturnType
DenseBase motionAction(const MotionDense< MotionDerived > &v) const
Eigen::Matrix< Scalar, 6, Dim > ReturnType
MatrixReturnType matrix_impl()
DenseBase se3Action(const SE3Tpl< Scalar, Options > &m) 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 motions, represented by a 6xN matrix whose columns represent a spatial...
bool isEqual(const ConstraintTpl &other) const
Eigen::Matrix< Scalar, 6, Dim, Options > DenseBase
Eigen::Matrix< Scalar, NV, Eigen::Dynamic > operator*(const Eigen::MatrixBase< D > &F)
MatrixReturnType matrix()
static ConstraintTpl Zero(const int dim)
static void se3ActionInverse(const SE3Tpl< Scalar, Options > &m, const Eigen::MatrixBase< Mat > &iV, Eigen::MatrixBase< MatRet > const &jV)
Inverse SE3 action on a set of motions, represented by a 6xN matrix whose column represent a spatial ...
#define PINOCCHIO_EIGEN_REF_TYPE(D)
Main pinocchio namespace.
ConstMatrixReturnType matrix_impl() const
ConstraintTpl(const int dim)
Common traits structure to fully define base classes for CRTP.
DenseBase se3ActionInverse(const SE3Tpl< Scalar, Options > &m) const
#define PINOCCHIO_CONSTRAINT_TYPEDEF_TPL(DERIVED)
static void inertiaAction(const InertiaTpl< Scalar, Options > &I, const Eigen::MatrixBase< Mat > &iF, Eigen::MatrixBase< MatRet > const &jF)
Action of an Inertia matrix on a set of motions, represented by a 6xN matrix whose columns represent ...
JointForce operator*(const ForceDense< Derived > &f) const
static void se3Action(const SE3Tpl< Scalar, Options > &m, const Eigen::MatrixBase< Mat > &iV, Eigen::MatrixBase< MatRet > const &jV)
SE3 action on a set of motions, represented by a 6xN matrix whose column represent a spatial motion...
Transpose transpose() const
Eigen::Matrix< Scalar, Dim, 1, Options > JointForce
void disp_impl(std::ostream &os) const
MotionTpl< Scalar, Options > JointMotion