18 #ifndef __invdyn_task_cop_equality_hpp__ 19 #define __invdyn_task_cop_equality_hpp__ 32 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
68 const std::vector<std::shared_ptr<ContactLevel> > *
m_contacts;
78 #endif // ifndef __invdyn_task_com_equality_hpp__
void setReference(const Vector3 &ref)
std::string m_contact_name
virtual const std::string & getAssociatedContactName()
const std::string & name() const
const ConstraintBase & compute(const double t, ConstRefVector q, ConstRefVector v, Data &data)
math::ConstraintEquality ConstraintEquality
Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > Vector
void setContactList(const std::vector< std::shared_ptr< ContactLevel > > *contacts)
virtual ~TaskCopEquality()
trajectories::TrajectorySample TrajectorySample
const std::vector< std::shared_ptr< ContactLevel > > * m_contacts
Eigen::Matrix< Scalar, 3, 1 > Vector3
const Vector3 & getContactNormal() const
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef math::Index Index
const ConstraintBase & getConstraint() const
math::ConstRefVector ConstRefVector
void setContactNormal(const Vector3 &n)
const Vector3 & getReference() const
Wrapper for a robot based on pinocchio.
ConstraintEquality m_constraint
TaskCopEquality(const std::string &name, RobotWrapper &robot)
Eigen::TensorRef< Tensor > ref(Eigen::TensorRef< Tensor > tensor)
int dim() const
Return the dimension of the task. should be overloaded in the child class.