6 #ifndef __pinocchio_multibody_constraint_base_hpp__ 7 #define __pinocchio_multibody_constraint_base_hpp__ 9 #include "pinocchio/macros.hpp" 10 #include "pinocchio/spatial/fwd.hpp" 11 #include "pinocchio/spatial/motion.hpp" 12 #include "pinocchio/spatial/act-on-set.hpp" 17 #define PINOCCHIO_CONSTRAINT_TYPEDEF_GENERIC(DERIVED,TYPENAME) \ 18 typedef TYPENAME traits<DERIVED>::Scalar Scalar; \ 19 typedef TYPENAME traits<DERIVED>::JointMotion JointMotion; \ 20 typedef TYPENAME traits<DERIVED>::JointForce JointForce; \ 21 typedef TYPENAME traits<DERIVED>::DenseBase DenseBase; \ 22 typedef TYPENAME traits<DERIVED>::MatrixReturnType MatrixReturnType; \ 23 typedef TYPENAME traits<DERIVED>::ConstMatrixReturnType ConstMatrixReturnType; \ 24 enum { LINEAR = traits<DERIVED>::LINEAR, ANGULAR = traits<DERIVED>::ANGULAR }; \ 25 enum { Options = traits<DERIVED>::Options }; 27 #define PINOCCHIO_CONSTRAINT_TYPEDEF_TPL(DERIVED) PINOCCHIO_CONSTRAINT_TYPEDEF_GENERIC(DERIVED,typename) 28 #define PINOCCHIO_CONSTRAINT_TYPEDEF(DERIVED) PINOCCHIO_CONSTRAINT_TYPEDEF_GENERIC(DERIVED,PINOCCHIO_EMPTY_ARG) 34 template<
class Constra
intDerived,
typename Force>
41 template<
class Constra
intDerived,
typename ForceSet>
47 template<
class Derived>
54 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
56 Derived &
derived() {
return *
static_cast<Derived*
>(
this); }
57 const Derived &
derived()
const {
return *
static_cast<const Derived*
>(
this); }
59 template<
typename VectorLike>
60 JointMotion
operator*(
const Eigen::MatrixBase<VectorLike> & vj)
const 61 {
return derived().__mult__(vj); }
63 MatrixReturnType
matrix() {
return derived().matrix_impl(); }
64 ConstMatrixReturnType
matrix()
const {
return derived().matrix_impl(); }
66 int nv()
const {
return derived().nv_impl(); }
68 static int rows() {
return 6; }
71 template<
class OtherDerived>
73 const Scalar & prec = Eigen::NumTraits<Scalar>::dummy_precision())
const 76 void disp(std::ostream & os)
const { derived().disp_impl(os); }
77 friend std::ostream & operator << (std::ostream & os,const ConstraintBase<Derived> & X)
86 return derived().se3Action(m);
92 return derived().se3ActionInverse(m);
95 template<
typename MotionDerived>
99 return derived().motionAction(v);
104 return derived().isEqual(other.
derived());
110 template<
typename Scalar,
int Options,
typename Constra
intDerived>
120 template<
typename MatrixDerived,
typename Constra
intDerived>
131 #endif // ifndef __pinocchio_multibody_constraint_base_hpp__ JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > const Eigen::MatrixBase< TangentVectorType > & v
int nv(const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel)
Visit a JointModelTpl through JointNvVisitor to get the dimension of the joint tangent space...
Forward declaration of the multiplication operation return type. Should be overloaded, otherwise it will procude a compilation error.
void disp(std::ostream &os) const
SE3GroupAction< Derived >::ReturnType se3Action(const SE3Tpl< Scalar, Options > &m) const
boost::python::object matrix()
Return type of the Constraint::Transpose * ForceSet operation.
const Derived & derived() const
ConstMatrixReturnType matrix() const
MatrixReturnType matrix()
JointMotion operator*(const Eigen::MatrixBase< VectorLike > &vj) const
SE3GroupAction< Derived >::ReturnType se3ActionInverse(const SE3Tpl< Scalar, Options > &m) const
Main pinocchio namespace.
ReturnTypeNotDefined ReturnType
bool isApprox(const ConstraintBase< OtherDerived > &other, const Scalar &prec=Eigen::NumTraits< Scalar >::dummy_precision()) const
bool operator==(const ConstraintBase< Derived > &other) const
#define PINOCCHIO_CONSTRAINT_TYPEDEF_TPL(DERIVED)
Return type of the Constraint::Transpose * Force operation.
EIGEN_MAKE_ALIGNED_OPERATOR_NEW Derived & derived()
ReturnTypeNotDefined ReturnType
MultiplicationOp< InertiaTpl< Scalar, Options >, ConstraintDerived >::ReturnType operator*(const InertiaTpl< Scalar, Options > &Y, const ConstraintBase< ConstraintDerived > &constraint)
.
MotionAlgebraAction< Derived, MotionDerived >::ReturnType motionAction(const MotionDense< MotionDerived > &v) const