Go to the documentation of this file.
18 #ifndef __invdyn_task_joint_posVelAcc_bounds_hpp__
19 #define __invdyn_task_joint_posVelAcc_bounds_hpp__
24 #include <tsid/deprecated.hh>
38 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
47 double dt,
bool verbose =
true);
49 int dim()
const override;
67 void setImposeBounds(
bool impose_position_bounds,
bool impose_velocity_bounds,
68 bool impose_viability_bounds,
69 bool impose_acceleration_bounds);
103 bool verbose =
true);
184 #endif // ifndef __invdyn_task_joint_bounds_hpp__
void setTimeStep(double dt)
const ConstraintBase & getConstraint() const override
int dim() const override
Return the dimension of the task. \info should be overloaded in the child class.
void computeAccLimitsFromPosLimits(ConstRefVector q, ConstRefVector dq, bool verbose=true)
bool m_impose_velocity_bounds
Abstract class representing a linear equality/inequality constraint. Equality constraints are represe...
TaskJointPosVelAccBounds(const std::string &name, RobotWrapper &robot, double dt, bool verbose=true)
const TSID_DEPRECATED Vector & mask() const
bool m_impose_viability_bounds
Vector m_minus_dq_over_dt
void setPositionBounds(ConstRefVector lower, ConstRefVector upper)
void setVerbose(bool verbose)
void setAccelerationBounds(ConstRefVector upper)
const Vector & getAccelerationBounds() const
void computeAccLimitsFromViability(ConstRefVector q, ConstRefVector dq, bool verbose=true)
math::ConstraintBound ConstraintBound
bool m_impose_acceleration_bounds
bool m_impose_position_bounds
void setImposeBounds(bool impose_position_bounds, bool impose_velocity_bounds, bool impose_viability_bounds, bool impose_acceleration_bounds)
const typedef Eigen::Ref< const Vector > ConstRefVector
Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > Vector
Wrapper for a robot based on pinocchio.
const Vector & getPositionUpperBounds() const
const std::string & name() const
virtual void setMask(math::ConstRefVector mask) override
void computeAccLimits(ConstRefVector q, ConstRefVector dq, bool verbose=true)
void setVelocityBounds(ConstRefVector upper)
void isStateViable(ConstRefVector q, ConstRefVector dq, bool verbose=true)
const ConstraintBase & compute(double t, ConstRefVector q, ConstRefVector v, Data &data) override
const Vector & getPositionLowerBounds() const
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef math::Vector Vector
ConstraintInequality m_constraint
math::ConstraintInequality ConstraintInequality
math::ConstRefVector ConstRefVector
const Vector & getVelocityBounds() const
tsid
Author(s): Andrea Del Prete, Justin Carpentier
autogenerated on Sat May 3 2025 02:48:17