Go to the documentation of this file.
    6 #ifndef __pinocchio_multibody_constraint_base_hpp__ 
    7 #define __pinocchio_multibody_constraint_base_hpp__ 
   14 #include <boost/static_assert.hpp> 
   19 #define PINOCCHIO_CONSTRAINT_TYPEDEF_GENERIC(DERIVED, TYPENAME)                                    \ 
   20   typedef TYPENAME traits<DERIVED>::Scalar Scalar;                                                 \ 
   21   typedef TYPENAME traits<DERIVED>::JointMotion JointMotion;                                       \ 
   22   typedef TYPENAME traits<DERIVED>::JointForce JointForce;                                         \ 
   23   typedef TYPENAME traits<DERIVED>::DenseBase DenseBase;                                           \ 
   24   typedef TYPENAME traits<DERIVED>::MatrixReturnType MatrixReturnType;                             \ 
   25   typedef TYPENAME traits<DERIVED>::ConstMatrixReturnType ConstMatrixReturnType;                   \ 
   28     LINEAR = traits<DERIVED>::LINEAR,                                                              \ 
   29     ANGULAR = traits<DERIVED>::ANGULAR                                                             \ 
   33     Options = traits<DERIVED>::Options                                                             \ 
   36 #define PINOCCHIO_CONSTRAINT_TYPEDEF_TPL(DERIVED)                                                  \ 
   37   PINOCCHIO_CONSTRAINT_TYPEDEF_GENERIC(DERIVED, typename) 
   38 #define PINOCCHIO_CONSTRAINT_TYPEDEF(DERIVED)                                                      \ 
   39   PINOCCHIO_CONSTRAINT_TYPEDEF_GENERIC(DERIVED, PINOCCHIO_EMPTY_ARG) 
   45   template<
class Constra
intDerived, 
typename Force>
 
   52   template<
class Constra
intDerived, 
typename ForceSet>
 
   58   template<
class Derived>
 
   65     EIGEN_MAKE_ALIGNED_OPERATOR_NEW
 
   69       return *
static_cast<Derived *
>(
this);
 
   73       return *
static_cast<const Derived *
>(
this);
 
   76     template<
typename VectorLike>
 
   77     JointMotion 
operator*(
const Eigen::MatrixBase<VectorLike> & vj)
 const 
  105     template<
class OtherDerived>
 
  108       const Scalar & prec = Eigen::NumTraits<Scalar>::dummy_precision())
 const 
  113     void disp(std::ostream & os)
 const 
  131       return derived().se3ActionInverse(
m);
 
  134     template<
typename MotionDerived>
 
  149   template<
typename Scalar, 
int Options, 
typename Constra
intDerived>
 
  159   template<
typename MatrixDerived, 
typename Constra
intDerived>
 
  160   typename MultiplicationOp<Eigen::MatrixBase<MatrixDerived>, ConstraintDerived>::ReturnType
 
  162     const Eigen::MatrixBase<MatrixDerived> & Y,
 
  171     template<
typename Constra
int>
 
  184   template<
class Constra
intDerived>
 
  191   template<
class Constra
intDerived>
 
  202 #endif // ifndef __pinocchio_multibody_constraint_base_hpp__ 
  
ConstMatrixReturnType matrix() const
Forward declaration of the multiplication operation return type. Should be overloaded,...
static ReturnType run(const JointMotionSubspaceBase< Constraint > &)
MotionAlgebraAction< Derived, MotionDerived >::ReturnType motionAction(const MotionDense< MotionDerived > &v) const
Return type of the Constraint::Transpose * Force operation.
traits< pinocchio::JointMotionSubspaceTpl >::Scalar Scalar
ReturnTypeNotDefined ReturnType
traits< ConstraintDerived >::StDiagonalMatrixSOperationReturnType StDiagonalMatrixSOperationReturnType
traits< Constraint >::StDiagonalMatrixSOperationReturnType ReturnType
TridiagonalSymmetricMatrixApplyOnTheLeftReturnType< LhsMatrixType, TridiagonalSymmetricMatrixTpl< S, O > > operator*(const Eigen::MatrixBase< LhsMatrixType > &lhs, const TridiagonalSymmetricMatrixTpl< S, O > &rhs)
friend std::ostream & operator<<(std::ostream &os, const JointMotionSubspaceBase< Derived > &X)
bool isApprox(const JointMotionSubspaceBase< OtherDerived > &other, const Scalar &prec=Eigen::NumTraits< Scalar >::dummy_precision()) const
MatrixReturnType matrix()
void disp(std::ostream &os) const
ReturnTypeNotDefined ReturnType
EIGEN_MAKE_ALIGNED_OPERATOR_NEW Derived & derived()
SE3GroupAction< Derived >::ReturnType se3Action(const SE3Tpl< Scalar, Options > &m) const
JointMotion operator*(const Eigen::MatrixBase< VectorLike > &vj) const
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > const Eigen::MatrixBase< TangentVectorType > & v
Return type of the Constraint::Transpose * ForceSet operation.
SE3GroupAction< Derived >::ReturnType se3ActionInverse(const SE3Tpl< Scalar, Options > &m) const
#define PINOCCHIO_CONSTRAINT_TYPEDEF_TPL(DERIVED)
traits< Constraint >::ReducedSquaredMatrix ReducedSquaredMatrix
Common traits structure to fully define base classes for CRTP.
const Derived & derived() const
Main pinocchio namespace.
bool operator==(const JointMotionSubspaceBase< Derived > &other) const
pinocchio
Author(s): 
autogenerated on Wed May 28 2025 02:41:19