18 #ifndef __invdyn_task_joint_bounds_hpp__ 19 #define __invdyn_task_joint_bounds_hpp__ 29 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
68 #endif // ifndef __invdyn_task_joint_bounds_hpp__ math::ConstraintBound ConstraintBound
TaskJointBounds(const std::string &name, RobotWrapper &robot, double dt)
void setVelocityBounds(ConstRefVector lower, ConstRefVector upper)
const std::string & name() const
virtual ~TaskJointBounds()
Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > Vector
const ConstraintBase & getConstraint() const
const Vector & getAccelerationUpperBounds() const
void setAccelerationBounds(ConstRefVector lower, ConstRefVector upper)
virtual void setMask(math::ConstRefVector mask)
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef math::Vector Vector
math::ConstRefVector ConstRefVector
const Eigen::Ref< const Vector > ConstRefVector
const ConstraintBase & compute(const double t, ConstRefVector q, ConstRefVector v, Data &data)
Vector m_ddq_min_due_to_vel
Wrapper for a robot based on pinocchio.
const Vector & getVelocityLowerBounds() const
const Vector & getAccelerationLowerBounds() const
Vector m_ddq_max_due_to_vel
ConstraintBound m_constraint
int dim() const
Return the dimension of the task. should be overloaded in the child class.
const Vector & getVelocityUpperBounds() const
void setTimeStep(double dt)