Skip to content

Commit

Permalink
fixup
Browse files Browse the repository at this point in the history
  • Loading branch information
Levi-Armstrong committed Nov 27, 2023
1 parent 609ddb1 commit 2bca583
Show file tree
Hide file tree
Showing 2 changed files with 10 additions and 10 deletions.
10 changes: 5 additions & 5 deletions trajopt_sco/src/osqp_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -62,7 +62,7 @@ OSQPModel::~OSQPModel()

Var OSQPModel::addVar(const std::string& name)
{
std::scoped_lock lock(mutex_);
std::lock_guard<std::mutex> lock(mutex_);
vars_.push_back(std::make_shared<VarRep>(vars_.size(), name, this));
lbs_.push_back(-OSQP_INFINITY);
ubs_.push_back(OSQP_INFINITY);
Expand All @@ -71,7 +71,7 @@ Var OSQPModel::addVar(const std::string& name)

Cnt OSQPModel::addEqCnt(const AffExpr& expr, const std::string& /*name*/)
{
std::scoped_lock lock(mutex_);
std::lock_guard<std::mutex> lock(mutex_);
cnts_.push_back(std::make_shared<CntRep>(cnts_.size(), this));
cnt_exprs_.push_back(expr);
cnt_types_.push_back(EQ);
Expand All @@ -80,7 +80,7 @@ Cnt OSQPModel::addEqCnt(const AffExpr& expr, const std::string& /*name*/)

Cnt OSQPModel::addIneqCnt(const AffExpr& expr, const std::string& /*name*/)
{
std::scoped_lock lock(mutex_);
std::lock_guard<std::mutex> lock(mutex_);
cnts_.push_back(std::make_shared<CntRep>(cnts_.size(), this));
cnt_exprs_.push_back(expr);
cnt_types_.push_back(INEQ);
Expand All @@ -91,7 +91,7 @@ Cnt OSQPModel::addIneqCnt(const QuadExpr&, const std::string& /*name*/) { throw

void OSQPModel::removeVars(const VarVector& vars)
{
std::scoped_lock lock(mutex_);
std::lock_guard<std::mutex> lock(mutex_);
SizeTVec inds;
vars2inds(vars, inds);
for (const auto& var : vars)
Expand All @@ -100,7 +100,7 @@ void OSQPModel::removeVars(const VarVector& vars)

void OSQPModel::removeCnts(const CntVector& cnts)
{
std::scoped_lock lock(mutex_);
std::lock_guard<std::mutex> lock(mutex_);
SizeTVec inds;
cnts2inds(cnts, inds);
for (const auto& cnt : cnts)
Expand Down
10 changes: 5 additions & 5 deletions trajopt_sco/src/qpoases_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,7 @@ qpOASESModel::qpOASESModel()
qpOASESModel::~qpOASESModel() = default;
Var qpOASESModel::addVar(const std::string& name)
{
std::scoped_lock lock(mutex_);
std::lock_guard<std::mutex> lock(mutex_);
vars_.push_back(std::make_shared<VarRep>(vars_.size(), name, this));
lb_.push_back(-QPOASES_INFTY);
ub_.push_back(QPOASES_INFTY);
Expand All @@ -47,7 +47,7 @@ Var qpOASESModel::addVar(const std::string& name)

Cnt qpOASESModel::addEqCnt(const AffExpr& expr, const std::string& /*name*/)
{
std::scoped_lock lock(mutex_);
std::lock_guard<std::mutex> lock(mutex_);
cnts_.push_back(std::make_shared<CntRep>(cnts_.size(), this));
cnt_exprs_.push_back(expr);
cnt_types_.push_back(EQ);
Expand All @@ -56,7 +56,7 @@ Cnt qpOASESModel::addEqCnt(const AffExpr& expr, const std::string& /*name*/)

Cnt qpOASESModel::addIneqCnt(const AffExpr& expr, const std::string& /*name*/)
{
std::scoped_lock lock(mutex_);
std::lock_guard<std::mutex> lock(mutex_);
cnts_.push_back(std::make_shared<CntRep>(cnts_.size(), this));
cnt_exprs_.push_back(expr);
cnt_types_.push_back(INEQ);
Expand All @@ -71,7 +71,7 @@ Cnt qpOASESModel::addIneqCnt(const QuadExpr&, const std::string& /*name*/)

void qpOASESModel::removeVars(const VarVector& vars)
{
std::scoped_lock lock(mutex_);
std::lock_guard<std::mutex> lock(mutex_);
IntVec inds;
vars2inds(vars, inds);
for (const auto& var : vars)
Expand All @@ -80,7 +80,7 @@ void qpOASESModel::removeVars(const VarVector& vars)

void qpOASESModel::removeCnts(const CntVector& cnts)
{
std::scoped_lock lock(mutex_);
std::lock_guard<std::mutex> lock(mutex_);
IntVec inds;
cnts2inds(cnts, inds);
for (const auto& cnt : cnts)
Expand Down

0 comments on commit 2bca583

Please sign in to comment.