Skip to content

Commit

Permalink
[solvers] Opt-in to clang-format-lint (#22096)
Browse files Browse the repository at this point in the history
  • Loading branch information
jwnimmer-tri authored Oct 30, 2024
1 parent f6bf32d commit ffbb365
Show file tree
Hide file tree
Showing 12 changed files with 31 additions and 34 deletions.
2 changes: 1 addition & 1 deletion solvers/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -2098,4 +2098,4 @@ drake_cc_googletest(
],
)

add_lint_tests(enable_clang_format_lint = False)
add_lint_tests()
19 changes: 11 additions & 8 deletions solvers/create_constraint.cc
Original file line number Diff line number Diff line change
Expand Up @@ -346,8 +346,8 @@ std::unique_ptr<Binding<LorentzConeConstraint>> MaybeParseLorentzConeConstraint(
// deprecation because of the way it is bound in pydrake.
if (!greater.is_polynomial() ||
symbolic::Polynomial(greater).TotalDegree() > 1) {
return nullptr;
}
return nullptr;
}
}
symbolic::DecomposeAffineExpressions(Vector1<Expression>{greater}, &A, &b,
&greater_vars);
Expand Down Expand Up @@ -412,12 +412,14 @@ Binding<Constraint> ParseConstraint(
if (is_constant(lhs, kInf)) {
throw std::runtime_error(
fmt::format("ParseConstraint is called with a formula ({}) with "
"a lower bound of +inf.", f));
"a lower bound of +inf.",
f));
}
if (is_constant(rhs, -kInf)) {
throw std::runtime_error(
fmt::format("ParseConstraint is called with a formula ({}) with "
"an upper bound of -inf.", f));
"an upper bound of -inf.",
f));
}
if (is_constant(lhs, -kInf)) {
// The constraint is trivial, but valid.
Expand All @@ -442,12 +444,14 @@ Binding<Constraint> ParseConstraint(
if (is_constant(rhs, kInf)) {
throw std::runtime_error(
fmt::format("ParseConstraint is called with a formula ({}) with "
"a lower bound of +inf.", f));
"a lower bound of +inf.",
f));
}
if (is_constant(lhs, -kInf)) {
throw std::runtime_error(
fmt::format("ParseConstraint is called with a formula ({}) with "
"an upper bound of -inf.", f));
"an upper bound of -inf.",
f));
}
if (is_constant(rhs, -kInf)) {
// The constraint is trivial, but valid.
Expand Down Expand Up @@ -703,8 +707,7 @@ shared_ptr<Constraint> MakePolynomialConstraint(
}

Binding<LorentzConeConstraint> ParseLorentzConeConstraint(
const symbolic::Formula& f,
LorentzConeConstraint::EvalType eval_type,
const symbolic::Formula& f, LorentzConeConstraint::EvalType eval_type,
double psd_tol, double coefficient_tol) {
auto lorentz_cone_binding = MaybeParseLorentzConeConstraint(
f,
Expand Down
1 change: 0 additions & 1 deletion solvers/create_cost.h
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,6 @@ Binding<L2NormCost> ParseL2NormCost(const symbolic::Expression& e,
*/
Binding<Cost> ParseCost(const symbolic::Expression& e);


// TODO(eric.cousineau): Remove this when functor cost is no longer exposed
// externally, and must be explicitly called.

Expand Down
4 changes: 3 additions & 1 deletion solvers/evaluator_base.cc
Original file line number Diff line number Diff line change
Expand Up @@ -73,7 +73,9 @@ std::string EvaluatorBase::DoToLatex(const VectorX<symbolic::Variable>& vars,
ss << "\\text{" << NiceTypeName::RemoveNamespaces(NiceTypeName::Get(*this))
<< "}(";
for (int i = 0; i < vars_rows; ++i) {
if (i > 0) { ss << ", "; }
if (i > 0) {
ss << ", ";
}
ss << symbolic::ToLatex(vars(i));
}
ss << ")";
Expand Down
4 changes: 2 additions & 2 deletions solvers/mathematical_program.h
Original file line number Diff line number Diff line change
Expand Up @@ -2111,8 +2111,8 @@ class MathematicalProgram {
Binding<LorentzConeConstraint> AddLorentzConeConstraint(
const symbolic::Formula& f,
LorentzConeConstraint::EvalType eval_type =
LorentzConeConstraint::EvalType::kConvexSmooth, double psd_tol = 1e-8,
double coefficient_tol = 1e-8);
LorentzConeConstraint::EvalType::kConvexSmooth,
double psd_tol = 1e-8, double coefficient_tol = 1e-8);

/**
* Adds Lorentz cone constraint referencing potentially a subset of the
Expand Down
4 changes: 1 addition & 3 deletions solvers/solver_base.h
Original file line number Diff line number Diff line change
Expand Up @@ -37,9 +37,7 @@ class SolverBase : public SolverInterface {
MathematicalProgramResult*) const override;
bool available() const override;
bool enabled() const override;
SolverId solver_id() const final {
return solver_id_;
}
SolverId solver_id() const final { return solver_id_; }
bool AreProgramAttributesSatisfied(const MathematicalProgram&) const override;
std::string ExplainUnsatisfiedProgramAttributes(
const MathematicalProgram&) const override;
Expand Down
6 changes: 2 additions & 4 deletions solvers/test/clarabel_solver_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -469,8 +469,7 @@ GTEST_TEST(TestOptions, StandaloneReproduction) {
ClarabelSolver solver;
if (solver.available()) {
SolverOptions solver_options;
const std::string repro_file_name =
temp_directory() + "/reproduction.py";
const std::string repro_file_name = temp_directory() + "/reproduction.py";
solver_options.SetOption(
CommonSolverOption::kStandaloneReproductionFileName, repro_file_name);
solver.Solve(prog, std::nullopt, solver_options);
Expand Down Expand Up @@ -506,8 +505,7 @@ GTEST_TEST(TestOptions, EmptyCones) {
ClarabelSolver solver;
if (solver.available()) {
SolverOptions solver_options;
const std::string repro_file_name =
temp_directory() + "/reproduction.py";
const std::string repro_file_name = temp_directory() + "/reproduction.py";
solver_options.SetOption(
CommonSolverOption::kStandaloneReproductionFileName, repro_file_name);
solver.Solve(prog, std::nullopt, solver_options);
Expand Down
4 changes: 2 additions & 2 deletions solvers/test/cost_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -759,8 +759,8 @@ GTEST_TEST(EvaluatorCost, Eval) {
}

GTEST_TEST(ExpressionCost, Basic) {
using std::sin;
using std::cos;
using std::sin;
Variable x("x"), y("y");
symbolic::Expression e = x * sin(y);
ExpressionCost cost(e);
Expand All @@ -779,7 +779,7 @@ GTEST_TEST(ExpressionCost, Basic) {

AutoDiffVecXd x_ad = math::InitializeAutoDiff(x_d);
AutoDiffVecXd y_ad;
RowVector2d y_deriv_expected(sin(3.5), 1.2*cos(3.5));
RowVector2d y_deriv_expected(sin(3.5), 1.2 * cos(3.5));
cost.Eval(x_ad, &y_ad);
EXPECT_TRUE(CompareMatrices(math::ExtractValue(y_ad), y_expected));
EXPECT_TRUE(CompareMatrices(math::ExtractGradient(y_ad), y_deriv_expected));
Expand Down
6 changes: 2 additions & 4 deletions solvers/test/create_constraint_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -112,8 +112,7 @@ void CheckParseLorentzConeConstraint(
lesser = get_lhs_expression(f);
}
EXPECT_TRUE(symbolic::test::PolynomialEqual(
symbolic::Polynomial(z(0)), symbolic::Polynomial(greater),
1E-10));
symbolic::Polynomial(z(0)), symbolic::Polynomial(greater), 1E-10));
ASSERT_TRUE(is_sqrt(lesser));
EXPECT_TRUE(symbolic::test::PolynomialEqual(
symbolic::Polynomial(z.tail(z.rows() - 1).squaredNorm()),
Expand Down Expand Up @@ -620,8 +619,7 @@ GTEST_TEST(ParseConstraintTest, FormulaWithInfiniteLowerOrUpperBounds) {
Variable x0("x0"), x1("x1");
Vector2<Variable> x(x0, x1);
Vector2d b(0.12, kInf);
Binding<Constraint> binding =
internal::ParseConstraint(x <= b);
Binding<Constraint> binding = internal::ParseConstraint(x <= b);
EXPECT_TRUE(CompareMatrices(binding.evaluator()->upper_bound(), b));
binding = internal::ParseConstraint(-b <= x);
// Note: The constraints are sorted via get_operands(f) which returns a
Expand Down
9 changes: 4 additions & 5 deletions solvers/test/osqp_solver_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -167,9 +167,8 @@ GTEST_TEST(OsqpSolverTest, EqualityConstrainedQPDualSolution2) {
TestEqualityConstrainedQPDualSolution2(solver);
}

void AddTestProgram(
MathematicalProgram* prog,
const MatrixDecisionVariable<3, 1>& x) {
void AddTestProgram(MathematicalProgram* prog,
const MatrixDecisionVariable<3, 1>& x) {
prog->AddLinearConstraint(x(0) + 2 * x(1) - 3 * x(2) <= 3);
prog->AddLinearConstraint(4 * x(0) - 2 * x(1) - 6 * x(2) >= -3);
prog->AddQuadraticCost(x(0) * x(0) + 2 * x(1) * x(1) + 5 * x(2) * x(2) +
Expand Down Expand Up @@ -360,8 +359,8 @@ GTEST_TEST(OsqpSolverTest, WarmStartPrimalOnly) {
const int half_iterations =
result.get_solver_details<OsqpSolver>().iter / 2;
SolverOptions solver_options;
solver_options.SetOption(
osqp_solver.solver_id(), "max_iter", half_iterations);
solver_options.SetOption(osqp_solver.solver_id(), "max_iter",
half_iterations);
const Eigen::VectorXd x_sol = result.get_x_val();
osqp_solver.Solve(prog, x_sol, solver_options, &result);
EXPECT_EQ(result.get_solver_details<OsqpSolver>().status_val, OSQP_SOLVED);
Expand Down
2 changes: 1 addition & 1 deletion solvers/test/semidefinite_relaxation_internal_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -496,7 +496,7 @@ TEST_F(MakeSemidefiniteRelaxationTestFixture,

ReinitializeRelaxation();
DoAddImpliedLinearEqualityConstraints(prog_, X_, variables_to_sorted_indices_,
relaxation_.get());
relaxation_.get());

EXPECT_EQ(relaxation_->num_vars(), 6);
EXPECT_EQ(relaxation_->positive_semidefinite_constraints().size(), 1);
Expand Down
4 changes: 2 additions & 2 deletions solvers/test/snopt_solver_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -387,11 +387,11 @@ GTEST_TEST(SnoptTest, MultiThreadTest) {
*contents = std::regex_replace(
*contents, std::regex(".Printer........................\\d"),
"(Printer).............. ####");
}
EXPECT_EQ(contents_single, contents_multi);
}
EXPECT_EQ(contents_single, contents_multi);
}
}
}

class AutoDiffOnlyCost final : public drake::solvers::Cost {
public:
Expand Down

0 comments on commit ffbb365

Please sign in to comment.