Go to the documentation of this file.
6 #ifndef __pinocchio_multibody_constraint_generic_hpp__
7 #define __pinocchio_multibody_constraint_generic_hpp__
12 template<
int _Dim,
typename _Scalar,
int _Options>
25 typedef Eigen::Matrix<Scalar, Dim, 1, Options>
JointForce;
26 typedef Eigen::Matrix<Scalar, 6, Dim, Options>
DenseBase;
35 template<
int Dim,
typename Scalar,
int Options>
41 template<
int Dim,
typename Scalar,
int Options,
typename MotionDerived>
47 template<
int _Dim,
typename _Scalar,
int _Options>
51 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
72 EIGEN_STATIC_ASSERT_SAME_MATRIX_SIZE(DenseBase,
D);
79 _Dim !=
Eigen::Dynamic, YOU_CALLED_A_DYNAMIC_SIZE_METHOD_ON_A_FIXED_SIZE_MATRIX_OR_VECTOR)
87 _Dim ==
Eigen::Dynamic, YOU_CALLED_A_FIXED_SIZE_METHOD_ON_A_DYNAMIC_SIZE_MATRIX_OR_VECTOR)
95 template<
typename VectorLike>
96 JointMotion
__mult__(
const Eigen::MatrixBase<VectorLike> & vj)
const
98 return JointMotion(
S * vj);
109 template<
typename Derived>
112 return (
ref.
S.transpose() *
f.toVector()).eval();
116 typename Eigen::Matrix<Scalar, NV, Eigen::Dynamic>
operator*(
const Eigen::MatrixBase<D> & F)
118 return (
ref.
S.transpose() * F).eval();
138 return (
int)
S.cols();
141 template<
typename S2,
int O2>
145 typedef typename JointMotionSubspaceTpl::DenseBase ReturnType;
146 ReturnType
res(6,
S.nv());
151 template<
typename S2,
int O2>
152 friend Eigen::Matrix<_Scalar, 6, _Dim>
155 typedef Eigen::Matrix<_Scalar, 6, _Dim> ReturnType;
156 return ReturnType(Ymatrix *
S.matrix());
161 DenseBase
res(6,
nv());
168 DenseBase
res(6,
nv());
173 template<
typename MotionDerived>
176 DenseBase
res(6,
nv());
183 os <<
"S =\n" <<
S << std::endl;
197 template<
int Dim,
typename Scalar,
int Options>
205 return constraint.
matrix().transpose() * constraint.
matrix();
212 #endif // ifndef __pinocchio_multibody_constraint_generic_hpp__
Eigen::Matrix< Scalar, Dim, Dim, Options > ReducedSquaredMatrix
MotionTpl< Scalar, Options > JointMotion
JointMotionSubspaceTpl< Dim, Scalar, Options > Constraint
friend Eigen::Matrix< _Scalar, 6, _Dim > operator*(const Eigen::Matrix< S2, 6, 6, O2 > &Ymatrix, const JointMotionSubspaceTpl &S)
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 ...
JointMotionSubspaceTpl(const int dim)
ConstMatrixReturnType matrix_impl() const
JointMotionSubspaceTpl(const Eigen::MatrixBase< D > &_S)
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...
Eigen::Matrix< Scalar, Dim, 1, Options > JointForce
static JointMotionSubspaceTpl Zero(const int dim)
PINOCCHIO_EIGEN_REF_CONST_TYPE(Matrix6Like) operator*(const Eigen
static ReturnType run(const JointMotionSubspaceBase< Constraint > &constraint)
MatrixReturnType matrix_impl()
JointMotion __mult__(const Eigen::MatrixBase< VectorLike > &vj) const
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef JointMotionSubspaceBase< JointMotionSubspaceTpl > Base
Return type of the ation of a Motion onto an object of type D.
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 ...
void disp_impl(std::ostream &os) const
Eigen::Matrix< Scalar, NV, Eigen::Dynamic > operator*(const Eigen::MatrixBase< D > &F)
MatrixReturnType matrix()
DenseBase motionAction(const MotionDense< MotionDerived > &v) const
Transpose transpose() const
friend JointMotionSubspaceTpl< _Dim, _Scalar, _Options >::DenseBase operator*(const InertiaTpl< S2, O2 > &Y, const JointMotionSubspaceTpl &S)
traits< Constraint >::StDiagonalMatrixSOperationReturnType ReturnType
DenseBase se3ActionInverse(const SE3Tpl< Scalar, Options > &m) const
bool isEqual(const JointMotionSubspaceTpl &other) const
Eigen::Matrix< Scalar, 6, Dim > ReturnType
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > const Eigen::MatrixBase< TangentVectorType > & v
Transpose(const JointMotionSubspaceTpl &ref)
Eigen::Matrix< Scalar, 6, Dim, Options > DenseBase
#define PINOCCHIO_CONSTRAINT_TYPEDEF_TPL(DERIVED)
Common traits structure to fully define base classes for CRTP.
const JointMotionSubspaceTpl & ref
#define PINOCCHIO_EIGEN_REF_TYPE(D)
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.
DenseBase se3Action(const SE3Tpl< Scalar, Options > &m) const
ReducedSquaredMatrix StDiagonalMatrixSOperationReturnType
Eigen::Matrix< Scalar, 6, Dim > ReturnType
Main pinocchio namespace.
pinocchio
Author(s):
autogenerated on Fri Nov 1 2024 02:41:45