Skip to content

Commit

Permalink
[API CHANGE] Moved to constraint.update(x) to constraint.upadte()
Browse files Browse the repository at this point in the history
  • Loading branch information
EnricoMingo committed Mar 25, 2024
1 parent 2bffb84 commit 63479ea
Show file tree
Hide file tree
Showing 69 changed files with 185 additions and 186 deletions.
5 changes: 2 additions & 3 deletions include/OpenSoT/Constraint.h
Original file line number Diff line number Diff line change
Expand Up @@ -177,9 +177,8 @@
*/
std::string getConstraintID(){ return _constraint_id; }

/** Updates the A, b, Aeq, beq, Aineq, b*Bound matrices
@param x variable state at the current step (input) */
virtual void update(const Vector_type& x) {}
/** Updates the A, b, Aeq, beq, Aineq, b*Bound matrices */
virtual void update() {}

/**
* @brief log logs common Constraint internal variables
Expand Down
2 changes: 1 addition & 1 deletion include/OpenSoT/SubConstraint.h
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,7 @@ class SubConstraint : public Constraint<Eigen::MatrixXd, Eigen::VectorXd> {

virtual ~SubConstraint(){}

virtual void update(const Eigen::VectorXd& x);
virtual void update();

protected:
Indices _subConstraintMap;
Expand Down
4 changes: 2 additions & 2 deletions include/OpenSoT/Task.h
Original file line number Diff line number Diff line change
Expand Up @@ -372,13 +372,13 @@
@return the number of rows of A */
virtual const unsigned int getTaskSize() const { return _A.rows(); }

/** Updates the A, b, Aeq, beq, Aineq, b*Bound matrices
/** Updates the A, b, Aeq, beq, Aineq, b*Bound matrices
@param x variable state at the current step (input) */
void update(const Vector_type &x) {


for(typename std::list< ConstraintPtr >::iterator i = this->getConstraints().begin();
i != this->getConstraints().end(); ++i) (*i)->update(x);
i != this->getConstraints().end(); ++i) (*i)->update();
this->_update(x);

if(!_is_active){
Expand Down
2 changes: 1 addition & 1 deletion include/OpenSoT/constraints/Aggregated.h
Original file line number Diff line number Diff line change
Expand Up @@ -142,7 +142,7 @@ using namespace OpenSoT::utils;
EQUALITIES_TO_INEQUALITIES |
UNILATERAL_TO_BILATERAL);

void update(const Eigen::VectorXd &x);
void update();

void log(XBot::MatLogger2::Ptr logger) override;

Expand Down
2 changes: 1 addition & 1 deletion include/OpenSoT/constraints/GenericConstraint.h
Original file line number Diff line number Diff line change
Expand Up @@ -67,7 +67,7 @@ class GenericConstraint : public Constraint<Eigen::MatrixXd, Eigen::VectorXd> {
bool setBounds(const Eigen::VectorXd& upper_bound,
const Eigen::VectorXd& lower_bound);

virtual void update(const Eigen::VectorXd& x);
virtual void update();

Type getType(){return _type;}

Expand Down
2 changes: 1 addition & 1 deletion include/OpenSoT/constraints/TaskToConstraint.h
Original file line number Diff line number Diff line change
Expand Up @@ -67,7 +67,7 @@
* @brief update updates the adapted task and the adapter constraint
* @param q
*/
void update(const Eigen::VectorXd &q);
void update();

protected:

Expand Down
2 changes: 1 addition & 1 deletion include/OpenSoT/constraints/acceleration/JointLimits.h
Original file line number Diff line number Diff line change
Expand Up @@ -81,7 +81,7 @@
const double dt);


void update(const Eigen::VectorXd& x);
void update();

/**
* @brief setJointAccMax updates joint acceleration limits
Expand Down
2 changes: 1 addition & 1 deletion include/OpenSoT/constraints/acceleration/JointLimitsECBF.h
Original file line number Diff line number Diff line change
Expand Up @@ -72,7 +72,7 @@ namespace OpenSoT {
const Eigen::VectorXd &jointVelMax,
const Eigen::VectorXd &jointAccMax);

void update(const Eigen::VectorXd& x);
void update();

/**
* @brief setAlpha1 gain applied to joint position limits
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -93,7 +93,7 @@
const double dt);


void update(const Eigen::VectorXd& x);
void update();

/**
* @brief setJointAccMax update maximum accelerations
Expand Down
2 changes: 1 addition & 1 deletion include/OpenSoT/constraints/acceleration/TorqueLimits.h
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@ class TorqueLimits : public Constraint<Eigen::MatrixXd, Eigen::VectorXd> {
const std::vector<std::string>& contact_links,
const Eigen::VectorXd& torque_limits);

void update(const Eigen::VectorXd& x);
void update();

/**
* @brief setTorqueLimits to set new torque limits
Expand Down
2 changes: 1 addition & 1 deletion include/OpenSoT/constraints/acceleration/VelocityLimits.h
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,7 @@ class VelocityLimits : public Constraint<Eigen::MatrixXd, Eigen::VectorXd> {
* @brief update
* @param x
*/
virtual void update(const Eigen::VectorXd& x);
virtual void update();

/**
* @brief setVelocityLimits update velocity limits
Expand Down
4 changes: 2 additions & 2 deletions include/OpenSoT/constraints/force/CoP.h
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@ namespace OpenSoT {

private:

virtual void update(const Eigen::VectorXd& x);
virtual void update();

std::string _contact_link;

Expand Down Expand Up @@ -85,7 +85,7 @@ namespace OpenSoT {

CoP::Ptr getCoP(const std::string& contact_name);

void update(const Eigen::VectorXd &x);
void update();


private:
Expand Down
4 changes: 2 additions & 2 deletions include/OpenSoT/constraints/force/FrictionCone.h
Original file line number Diff line number Diff line change
Expand Up @@ -70,7 +70,7 @@
const friction_cone & mu);


void update(const Eigen::VectorXd &x);
void update();

void setFrictionCone(const friction_cone& frc);

Expand Down Expand Up @@ -101,7 +101,7 @@

FrictionCone::Ptr getFrictionCone(const std::string& contact_name);

void update(const Eigen::VectorXd &x);
void update();

private:
std::map<std::string, FrictionCone::Ptr> _friction_cone_map;
Expand Down
4 changes: 2 additions & 2 deletions include/OpenSoT/constraints/force/NormalTorque.h
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,7 @@ class NormalTorque: public Constraint<Eigen::MatrixXd, Eigen::VectorXd> {
const Eigen::Vector2d& Y_Lims,
const double& mu);

void update(const Eigen::VectorXd &x);
void update();

/**
* @brief setMu update friction coefficient
Expand Down Expand Up @@ -110,7 +110,7 @@ class NormalTorques: public Constraint<Eigen::MatrixXd, Eigen::VectorXd> {

NormalTorque::Ptr getNormalTorque(const std::string& contact_name);

void update(const Eigen::VectorXd &x);
void update();

private:
std::map<std::string, NormalTorque::Ptr> _normal_torque_map;
Expand Down
2 changes: 1 addition & 1 deletion include/OpenSoT/constraints/force/StaticConstraint.h
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@ namespace OpenSoT { namespace constraints { namespace force {

private:

void update(const Eigen::VectorXd& x) override;
void update() override;

const XBot::ModelInterface& _robot;
std::vector<std::string> _contact_links;
Expand Down
2 changes: 1 addition & 1 deletion include/OpenSoT/constraints/force/WrenchLimits.h
Original file line number Diff line number Diff line change
Expand Up @@ -135,7 +135,7 @@
*/
WrenchLimits::Ptr getWrenchLimits(const std::string& contact_name);

void update(const Eigen::VectorXd &x);
void update();

private:
std::map<std::string, WrenchLimits::Ptr> _wrench_lims_constraints;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -85,7 +85,7 @@
const Eigen::VectorXd& b_Cartesian,
const double boundScaling = 1.0);

void update(const Eigen::VectorXd &x);
void update();

/**
* @brief getCurrentPosition return the current Cartesian position of the bounded Task
Expand Down
2 changes: 1 addition & 1 deletion include/OpenSoT/constraints/velocity/CartesianVelocity.h
Original file line number Diff line number Diff line change
Expand Up @@ -60,7 +60,7 @@
const double dT,
const OpenSoT::tasks::velocity::CoM::Ptr& task);

virtual void update(const Eigen::VectorXd &x);
virtual void update();

/**
* @brief getVelocityLimits
Expand Down
2 changes: 1 addition & 1 deletion include/OpenSoT/constraints/velocity/CollisionAvoidance.h
Original file line number Diff line number Diff line change
Expand Up @@ -91,7 +91,7 @@ class CollisionAvoidance: public Constraint<Eigen::MatrixXd, Eigen::VectorXd>
* previously stored value
* @param x the state vector.
*/
void update(const Eigen::VectorXd &x);
void update();


/**
Expand Down
2 changes: 1 addition & 1 deletion include/OpenSoT/constraints/velocity/ConvexHull.h
Original file line number Diff line number Diff line change
Expand Up @@ -94,7 +94,7 @@
*/
void setSafetyMargin(const double safetyMargin);

void update(const Eigen::VectorXd &x);
void update();

std::list<std::string> getLinksInContact()
{
Expand Down
2 changes: 1 addition & 1 deletion include/OpenSoT/constraints/velocity/JointLimits.h
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,7 @@
const Eigen::VectorXd &jointBoundMin,
const double boundScaling = 1.0);

void update(const Eigen::VectorXd &x);
void update();
void setBoundScaling(const double boundScaling);
};
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -84,7 +84,7 @@
const double dt);


void update(const Eigen::VectorXd& x);
void update();

/**
* @brief setJointAccMax updates joint acceleration limits
Expand Down
2 changes: 1 addition & 1 deletion include/OpenSoT/constraints/velocity/OmniWheels4X.h
Original file line number Diff line number Diff line change
Expand Up @@ -74,7 +74,7 @@ namespace OpenSoT {
* @brief update the constraint
* @param x state vector
*/
virtual void update(const Eigen::VectorXd &x);
virtual void update();


private:
Expand Down
2 changes: 1 addition & 1 deletion include/OpenSoT/utils/AffineUtils.h
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,7 @@ class AffineConstraint: public Constraint<Eigen::MatrixXd, Eigen::VectorXd>
AffineConstraint(const OpenSoT::constraints::Aggregated::ConstraintPtr& constraint,
const AffineHelper& var);

virtual void update(const Eigen::VectorXd& x);
virtual void update();
~AffineConstraint();

static AffineConstraint::Ptr toAffine(const OpenSoT::constraints::Aggregated::ConstraintPtr& constraint,
Expand Down
4 changes: 2 additions & 2 deletions src/constraints/Aggregated.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -57,14 +57,14 @@ Aggregated::Aggregated(ConstraintPtr bound1,
this->generateAll();
}

void Aggregated::update(const Eigen::VectorXd& x) {
void Aggregated::update() {
/* iterating on all bounds.. */
for(typename std::list< ConstraintPtr >::iterator i = _bounds.begin();
i != _bounds.end(); i++) {

ConstraintPtr &b = *i;
/* update bounds */
b->update(x);
b->update();
}

this->generateAll();
Expand Down
2 changes: 1 addition & 1 deletion src/constraints/GenericConstraint.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -77,7 +77,7 @@ bool OpenSoT::constraints::GenericConstraint::setConstraint(const AffineHelper&
}


void OpenSoT::constraints::GenericConstraint::update(const Eigen::VectorXd& x)
void OpenSoT::constraints::GenericConstraint::update()
{

}
4 changes: 2 additions & 2 deletions src/constraints/SubConstraint.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,9 +46,9 @@ SubConstraint::SubConstraint(ConstraintPtr constrPtr, const std::list<unsigned i
}
}

void SubConstraint::update(const Eigen::VectorXd& x)
void SubConstraint::update()
{
_constraintPtr->update(x);
_constraintPtr->update();
if(_constraintPtr->isBound()) //1. constraint ptr is a bound, we transform it into a constraint with less rows
{
generateBound(this->_constraintPtr->getLowerBound(), this->_bLowerBound);
Expand Down
4 changes: 2 additions & 2 deletions src/constraints/TaskToConstraint.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -52,9 +52,9 @@ TaskToConstraint::TaskToConstraint(TaskToConstraint::TaskPtr task,
}


void TaskToConstraint::update(const Eigen::VectorXd &q)
void TaskToConstraint::update()
{
_task->update(q);
_task->update(Eigen::VectorXd(0));
this->generateAll();
}

Expand Down
6 changes: 3 additions & 3 deletions src/constraints/acceleration/JointLimits.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,11 +51,11 @@ JointLimits::JointLimits( XBot::ModelInterface& robot,
-_jointAccMax,
OpenSoT::constraints::GenericConstraint::Type::CONSTRAINT);

update(Eigen::VectorXd(1));
update();
}


void JointLimits::update(const Eigen::VectorXd& x)
void JointLimits::update()
{
_robot.getJointPosition(_q);
_robot.getJointVelocity(_qdot);
Expand Down Expand Up @@ -167,7 +167,7 @@ void JointLimits::update(const Eigen::VectorXd& x)

_generic_constraint_internal->setBounds(__upperBound, __lowerBound);

_generic_constraint_internal->update(x);
_generic_constraint_internal->update();

_Aineq = _generic_constraint_internal->getAineq();
_bLowerBound = _generic_constraint_internal->getbLowerBound();
Expand Down
6 changes: 3 additions & 3 deletions src/constraints/acceleration/JointLimitsECBF.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,10 +30,10 @@ JointLimitsECBF::JointLimitsECBF(XBot::ModelInterface &robot,
__lowerBound = -jointAccMax;
__upperBound = jointAccMax;

update(Eigen::VectorXd(1));
update();
}

void JointLimitsECBF::update(const Eigen::VectorXd &x)
void JointLimitsECBF::update()
{
_robot.getJointPosition(_q);
_robot.getJointVelocity(_qdot);
Expand Down Expand Up @@ -63,7 +63,7 @@ void JointLimitsECBF::update(const Eigen::VectorXd &x)

_generic_constraint_internal->setBounds(__upperBound, __lowerBound);

_generic_constraint_internal->update(x);
_generic_constraint_internal->update();

_Aineq = _generic_constraint_internal->getAineq();
_bLowerBound = _generic_constraint_internal->getbLowerBound();
Expand Down
6 changes: 3 additions & 3 deletions src/constraints/acceleration/JointLimitsViability.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -63,7 +63,7 @@ JointLimitsViability::JointLimitsViability(XBot::ModelInterface& robot,
-_jointAccMax,
OpenSoT::constraints::GenericConstraint::Type::CONSTRAINT);

update(Eigen::VectorXd(1));
update();
}

void JointLimitsViability::_log(XBot::MatLogger2::Ptr logger)
Expand All @@ -76,7 +76,7 @@ void JointLimitsViability::_log(XBot::MatLogger2::Ptr logger)
logger->add("_ddq_UB_via", _ddq_UB_via);
}

void JointLimitsViability::update(const Eigen::VectorXd &x)
void JointLimitsViability::update()
{
_robot.getJointPosition(_q);
_robot.getJointVelocity(_qdot);
Expand All @@ -87,7 +87,7 @@ void JointLimitsViability::update(const Eigen::VectorXd &x)

_generic_constraint_internal->setBounds(__upperBound, __lowerBound);

_generic_constraint_internal->update(x);
_generic_constraint_internal->update();

_Aineq = _generic_constraint_internal->getAineq();
_bLowerBound = _generic_constraint_internal->getbLowerBound();
Expand Down
4 changes: 2 additions & 2 deletions src/constraints/acceleration/TorqueLimits.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,10 +19,10 @@ TorqueLimits::TorqueLimits(const XBot::ModelInterface &robot,

_enabled_contacts.assign(_contact_links.size(), true);

update(Eigen::VectorXd(0));
update();
}

void TorqueLimits::update(const Eigen::VectorXd &x)
void TorqueLimits::update()
{
_robot.computeInertiaMatrix(_B);
_robot.computeNonlinearTerm(_h);
Expand Down
Loading

0 comments on commit 63479ea

Please sign in to comment.