30 m_constraint(name, robot.
nv()),
72 "The size of the lower velocity bounds vector needs to equal " +
73 std::to_string(
m_na));
76 "The size of the upper velocity bounds vector needs to equal " +
77 std::to_string(
m_na));
86 "The size of the lower acceleration bounds vector needs to equal " +
87 std::to_string(
m_na));
90 "The size of the upper acceleration bounds vector needs to equal " +
91 std::to_string(
m_na));
110 for (
int i = 0;
i <
m_na;
i++) {
TaskJointBounds(const std::string &name, RobotWrapper &robot, double dt)
void setVelocityBounds(ConstRefVector lower, ConstRefVector upper)
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)
math::ConstRefVector 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 & lowerBound() const
const Vector & getAccelerationLowerBounds() const
Vector m_ddq_max_due_to_vel
const Vector & upperBound() const
ConstraintBound m_constraint
int dim() const
Return the dimension of the task. should be overloaded in the child class.
#define PINOCCHIO_CHECK_INPUT_ARGUMENT(...)
const Vector & getVelocityUpperBounds() const
void setTimeStep(double dt)