Skip to content

Commit

Permalink
[workspace] Upgrade clang-format to release 19.1.3 (#22554)
Browse files Browse the repository at this point in the history
jwnimmer-tri authored Jan 29, 2025

Verified

This commit was created on GitHub.com and signed with GitHub’s verified signature. The key has expired.
1 parent 0eac4a3 commit d243930
Showing 22 changed files with 58 additions and 60 deletions.
2 changes: 1 addition & 1 deletion MODULE.bazel
Original file line number Diff line number Diff line change
@@ -81,7 +81,7 @@ llvm = use_repo_rule("@toolchains_llvm//toolchain:rules.bzl", "llvm")

llvm(
name = "llvm",
llvm_version = "15.0.5",
llvm_version = "19.1.3",
)

# Load dependencies which are "public", i.e., made available to downstream
9 changes: 3 additions & 6 deletions bindings/pydrake/common/test/ref_cycle_test_util_py.cc
Original file line number Diff line number Diff line change
@@ -70,13 +70,10 @@ PYBIND11_MODULE(ref_cycle_test_util, m) {
.def("ReturnNullIsCycle", &Class::ReturnNullIs, ref_cycle<0, 1>());
}

m.def(
"free_function", [](IsDynamic*, IsDynamic*) {}, ref_cycle<1, 2>());
m.def(
"invalid_arg_index", [] {}, ref_cycle<0, 1>());
m.def("free_function", [](IsDynamic*, IsDynamic*) {}, ref_cycle<1, 2>());
m.def("invalid_arg_index", [] {}, ref_cycle<0, 1>());
// Returns its argument and creates a self-cycle.
m.def(
"ouroboros", [](IsDynamic* x) { return x; }, ref_cycle<0, 1>());
m.def("ouroboros", [](IsDynamic* x) { return x; }, ref_cycle<0, 1>());
m.def("arbitrary_ok", []() {
auto d1 = py::cast(new IsDynamic);
auto d2 = py::cast(new IsDynamic);
6 changes: 3 additions & 3 deletions bindings/pydrake/common/wrap_pybind.h
Original file line number Diff line number Diff line change
@@ -137,7 +137,7 @@ auto WrapCallbacks(Func&& func) {
/// @tparam T type for the member we wish to apply keep alive semantics.
template <typename PyClass, typename Class, typename T>
void DefReadWriteKeepAlive(
PyClass* cls, const char* name, T Class::*member, const char* doc = "") {
PyClass* cls, const char* name, T Class::* member, const char* doc = "") {
auto getter = [member](const Class* obj) { return obj->*member; };
auto setter = [member](Class* obj, const T& value) { obj->*member = value; };
cls->def_property(name, // BR
@@ -157,7 +157,7 @@ void DefReadWriteKeepAlive(
/// @tparam T type for the member we wish to apply keep alive semantics.
template <typename PyClass, typename Class, typename T>
void DefReadUniquePtr(PyClass* cls, const char* name,
const std::unique_ptr<T> Class::*member, const char* doc = "") {
const std::unique_ptr<T> Class::* member, const char* doc = "") {
auto getter = py::cpp_function(
[member](const Class* obj) { return (obj->*member).get(); },
py_rvp::reference_internal);
@@ -167,7 +167,7 @@ void DefReadUniquePtr(PyClass* cls, const char* name,
// Variant of DefReadUniquePtr() for copyable_unique_ptr.
template <typename PyClass, typename Class, typename T>
void DefReadUniquePtr(PyClass* cls, const char* name,
const copyable_unique_ptr<T> Class::*member, const char* doc = "") {
const copyable_unique_ptr<T> Class::* member, const char* doc = "") {
auto getter = py::cpp_function(
[member](const Class* obj) { return (obj->*member).get(); },
py_rvp::reference_internal);
3 changes: 1 addition & 2 deletions bindings/pydrake/math_operators_pybind.h
Original file line number Diff line number Diff line change
@@ -146,8 +146,7 @@ void BindMathOperators(PyObject* obj) {
return CalcMatrixInverse(X.template cast<Promoted>().eval());
}
})
.def(
"isnan", [](const T& x) { return isnan(x); }, py::arg("x"));
.def("isnan", [](const T& x) { return isnan(x); }, py::arg("x"));
} else {
auto& cls = *obj;
cls // BR
4 changes: 2 additions & 2 deletions bindings/pydrake/multibody/plant_py.cc
Original file line number Diff line number Diff line change
@@ -246,7 +246,7 @@ void DoScalarDependentDefinitions(py::module m, T) {
cls_doc.RenameModelInstance.doc)
.def(
"AddRigidBody",
[](Class * self, const std::string& name,
[](Class* self, const std::string& name,
const SpatialInertia<double>& s) -> auto& {
return self->AddRigidBody(name, s);
},
@@ -901,7 +901,7 @@ void DoScalarDependentDefinitions(py::module m, T) {
py_rvp::reference_internal, cls_doc.GetJointByName.doc)
.def(
"GetMutableJointByName",
[](Class * self, string_view name,
[](Class* self, string_view name,
std::optional<ModelInstanceIndex> model_instance) -> auto& {
return self->GetMutableJointByName(name, model_instance);
},
3 changes: 2 additions & 1 deletion bindings/pydrake/systems/framework_py_semantics.cc
Original file line number Diff line number Diff line change
@@ -390,7 +390,8 @@ py::class_<Context<T>, ContextBase> DefineContext(py::module m) {
&Context<T>::get_abstract_state),
py_rvp::reference_internal, doc.Context.get_abstract_state.doc_0args)
.def(
"get_abstract_state", [](const Context<T>* self, int index) -> auto& {
"get_abstract_state",
[](const Context<T>* self, int index) -> auto& {
return self->get_abstract_state().get_value(index);
},
py::arg("index"), py_rvp::reference_internal,
8 changes: 6 additions & 2 deletions common/symbolic/expression/test/expression_test.cc
Original file line number Diff line number Diff line change
@@ -2381,7 +2381,9 @@ TEST_F(SymbolicExpressionTest, NormalDistribution) {
symbolic_distribution.stddev().Evaluate());

// Exceptions at construction.
{ EXPECT_THROW(normal_distribution<Expression>(1.0, -1.0), runtime_error); }
{
EXPECT_THROW(normal_distribution<Expression>(1.0, -1.0), runtime_error);
}

RandomGenerator generator{};
RandomGenerator generator_copy{generator};
@@ -2529,7 +2531,9 @@ TEST_F(SymbolicExpressionTest, ExponentialDistribution) {
symbolic_distribution.lambda().Evaluate());

// Exceptions at construction.
{ EXPECT_THROW(exponential_distribution<Expression>(-3.0), runtime_error); }
{
EXPECT_THROW(exponential_distribution<Expression>(-3.0), runtime_error);
}

RandomGenerator generator{};
RandomGenerator generator_copy{generator};
2 changes: 1 addition & 1 deletion common/symbolic/test/generic_polynomial_test.cc
Original file line number Diff line number Diff line change
@@ -100,7 +100,7 @@ TEST_F(SymbolicGenericPolynomialTest, DefaultConstructors) {

TEST_F(SymbolicGenericPolynomialTest, ConstructFromMapType1) {
GenericPolynomial<ChebyshevBasisElement>::MapType map1;
map1.emplace(ChebyshevBasisElement{var_x_}, -2.0 * a_); // T₁(x) → −2a
map1.emplace(ChebyshevBasisElement{var_x_}, -2.0 * a_); // T₁(x) → −2a
map1.emplace(ChebyshevBasisElement{var_y_, 3}, 4.0 * b_); // T₃(y) → 4b
// p=−2aT₁(x)+4bT₃(y)
const GenericPolynomial<ChebyshevBasisElement> p1(map1);
3 changes: 1 addition & 2 deletions geometry/optimization/convex_set.h
Original file line number Diff line number Diff line change
@@ -540,8 +540,7 @@ ConvexSets MakeConvexSets(Args&&... args) {
sets.resize(N);
// This is a "constexpr for" loop for 0 <= I < N.
auto args_tuple = std::forward_as_tuple(std::forward<Args>(args)...);
auto seq_into_sets = [&]<size_t... I>(
std::integer_sequence<size_t, I...> &&) {
auto seq_into_sets = [&]<size_t... I>(std::integer_sequence<size_t, I...>&&) {
((sets[I] = std::get<I>(std::move(args_tuple))), ...);
}; // NOLINT
seq_into_sets(std::make_index_sequence<N>{});
21 changes: 10 additions & 11 deletions geometry/optimization/graph_of_convex_sets.cc
Original file line number Diff line number Diff line change
@@ -1107,22 +1107,21 @@ void GraphOfConvexSets::AddPerspectiveCost(
VectorXd::Zero(A_linear.rows()), cost_vars);
} else if (L2NormCost* l2c = dynamic_cast<L2NormCost*>(cost)) {
// |Ax + b|₂ becomes ℓ ≥ |Ax+bϕ|₂.
MatrixXd A_cone =
MatrixXd::Zero(l2c->get_sparse_A().rows() + 1, vars.size());
A_cone(0, 1) = 1.0; // z₀ = ℓ.
A_cone.block(1, 0, l2c->get_sparse_A().rows(), 1) = l2c->b(); // bϕ.
A_cone.block(1, 2, l2c->get_sparse_A().rows(), l2c->get_sparse_A().cols()) =
l2c->get_sparse_A(); // Ax.
const SparseMatrix<double>& A = l2c->get_sparse_A();
MatrixXd A_cone = MatrixXd::Zero(A.rows() + 1, vars.size());
A_cone(0, 1) = 1.0; // z₀ = ℓ.
A_cone.block(1, 0, A.rows(), 1) = l2c->b(); // bϕ.
A_cone.block(1, 2, A.rows(), A.cols()) = A; // Ax.
prog->AddLorentzConeConstraint(A_cone, VectorXd::Zero(A_cone.rows()), vars);
} else if (LInfNormCost* linfc = dynamic_cast<LInfNormCost*>(cost)) {
// |Ax + b|∞ becomes ℓ ≥ |Aᵢx+bᵢϕ| ∀ i.
int A_rows = linfc->A().rows();
MatrixXd A_linear(2 * A_rows, vars.size());
A_linear.block(0, 0, A_rows, 1) = linfc->b(); // bϕ.
A_linear.block(0, 1, A_rows, 1) = -VectorXd::Ones(A_rows); // -ℓ.
A_linear.block(0, 2, A_rows, linfc->A().cols()) = linfc->A(); // Ax.
A_linear.block(A_rows, 0, A_rows, 1) = -linfc->b(); // -bϕ.
A_linear.block(A_rows, 1, A_rows, 1) = -VectorXd::Ones(A_rows); // -ℓ.
A_linear.block(0, 0, A_rows, 1) = linfc->b(); // bϕ.
A_linear.block(0, 1, A_rows, 1) = -VectorXd::Ones(A_rows); // -ℓ.
A_linear.block(0, 2, A_rows, linfc->A().cols()) = linfc->A(); // Ax.
A_linear.block(A_rows, 0, A_rows, 1) = -linfc->b(); // -bϕ.
A_linear.block(A_rows, 1, A_rows, 1) = -VectorXd::Ones(A_rows); // -ℓ.
A_linear.block(A_rows, 2, A_rows, linfc->A().cols()) = -linfc->A(); // -Ax.
prog->AddLinearConstraint(A_linear,
VectorXd::Constant(A_linear.rows(), -inf),
2 changes: 1 addition & 1 deletion geometry/proximity/make_box_mesh.cc
Original file line number Diff line number Diff line change
@@ -399,8 +399,8 @@ void AddSixTetrahedraOfCell(const Vector3<int>& lowest,
// tetrahedron. The six tetrahedra form a cycle around the diagonal v₀v₇
// of the cell. Refer to:
// http://www.baumanneduard.ch/Splitting%20a%20cube%20in%20tetrahedras2.htm
// clang-format off
const int tetrahedron[6][4]{
// clang-format off
{v[0], v[7], v[4], v[6]},
{v[0], v[7], v[6], v[2]},
{v[0], v[7], v[2], v[3]},
4 changes: 2 additions & 2 deletions geometry/proximity/volume_to_surface_mesh.cc
Original file line number Diff line number Diff line change
@@ -100,14 +100,14 @@ std::vector<std::array<int, 3>> IdentifyBoundaryFaces(

has its right-handed normal pointing outwards from the tetrahedron. We encode
those triangles (with tet-local face indices in the fourth slot) below. */
// clang-format off
const int tetrahedron_faces[4][4] = {
// clang-format off
{1, 2, 3, 0},
{3, 2, 0, 1},
{1, 3, 0, 2},
{2, 1, 0, 3}
// clang-format on
};
// clang-format on

for (int tet_index = 0; tet_index < ssize(tetrahedra); ++tet_index) {
const VolumeElement& tetrahedron = tetrahedra[tet_index];
8 changes: 4 additions & 4 deletions geometry/render_vtk/test/internal_render_engine_vtk_test.cc
Original file line number Diff line number Diff line change
@@ -1221,14 +1221,14 @@ TEST_F(RenderEngineVtkTest, RemoveVisual) {
};

// Sets the expected values prior to calling PerformCenterShapeTest().
auto set_expectations = [this](const TestColor& color, float depth,
RenderLabel label)
auto set_expectations =
[this](const TestColor& color, float depth, RenderLabel label)
// Optimizers on some platforms break code and cause test failures. Worse
// still, there is no agreement on attribute spelling.
#ifdef __clang__
__attribute__((optnone))
__attribute__((optnone))
#else
__attribute__((optimize("-O0")))
__attribute__((optimize("-O0")))
#endif
{
expected_color_ = color;
2 changes: 1 addition & 1 deletion manipulation/kuka_iiwa/iiwa_status_receiver.cc
Original file line number Diff line number Diff line change
@@ -62,7 +62,7 @@ const OutPort& IiwaStatusReceiver::get_torque_external_output_port() const {
return LeafSystem<double>::get_output_port(6);
}

template <std::vector<double> drake::lcmt_iiwa_status::*field_ptr>
template <std::vector<double> drake::lcmt_iiwa_status::* field_ptr>
void IiwaStatusReceiver::CalcLcmOutput(const Context<double>& context,
BasicVector<double>* output) const {
const auto& status = get_input_port().Eval<lcmt_iiwa_status>(context);
5 changes: 2 additions & 3 deletions math/autodiff.h
Original file line number Diff line number Diff line change
@@ -222,12 +222,11 @@ auto InitializeAutoDiffTuple(const Eigen::MatrixBase<Deriveds>&... args) {
// Set the values and gradients of the result using InitializeAutoDiff from
// each Matrix in 'args...'. This is a "constexpr for" loop for 0 <= I < N.
auto args_tuple = std::forward_as_tuple(args...);
[&]<size_t... I>(std::integer_sequence<size_t, I...> &&) {
[&]<size_t... I>(std::integer_sequence<size_t, I...>&&) {
(InitializeAutoDiff(std::get<I>(args_tuple), num_derivatives,
std::get<I>(deriv_num_starts), &std::get<I>(result)),
...);
}
(std::make_index_sequence<N>{});
}(std::make_index_sequence<N>{});

return result;
}
6 changes: 3 additions & 3 deletions math/compute_numerical_gradient.h
Original file line number Diff line number Diff line change
@@ -8,10 +8,10 @@ namespace drake {
namespace math {

enum class NumericalGradientMethod {
kForward, ///< Compute the gradient as (f(x + Δx) - f(x)) / Δx, with Δx > 0
kForward, ///< Compute the gradient as (f(x + Δx) - f(x)) / Δx, with Δx > 0
kBackward, ///< Compute the gradient as (f(x) - f(x - Δx)) / Δx, with Δx > 0
kCentral, ///< Compute the gradient as (f(x + Δx) - f(x - Δx)) / (2Δx), with
///< Δx > 0
kCentral, ///< Compute the gradient as (f(x + Δx) - f(x - Δx)) / (2Δx), with
///< Δx > 0
};

class NumericalGradientOption {
4 changes: 2 additions & 2 deletions multibody/contact_solvers/pgs_solver.cc
Original file line number Diff line number Diff line change
@@ -95,8 +95,8 @@ ContactSolverStatus PgsSolver<T>::SolveWithGuess(
// Update generalized velocities; v = v* + A⁻¹⋅Jᵀ⋅γ.
contact_data.get_Jc().MultiplyByTranspose(gamma_kp,
&tau_c_); // tau_c = Jᵀ⋅γ
dynamics_data.get_Ainv().Multiply(tau_c_, &v_kp); // v_kp = A⁻¹⋅Jᵀ⋅γ
v_kp += v_star; // v_kp = v* + A⁻¹⋅Jᵀ⋅γ
dynamics_data.get_Ainv().Multiply(tau_c_, &v_kp); // v_kp = A⁻¹⋅Jᵀ⋅γ
v_kp += v_star; // v_kp = v* + A⁻¹⋅Jᵀ⋅γ
// Update contact velocities; vc = J⋅v.
contact_data.get_Jc().Multiply(v_kp, &vc_kp);

2 changes: 1 addition & 1 deletion multibody/contact_solvers/sap/sap_limit_constraint.h
Original file line number Diff line number Diff line change
@@ -246,7 +246,7 @@ class SapLimitConstraint final : public SapConstraint<T> {
EigenPtr<VectorX<T>> tau) const final;
// no-op for this constraint.
void DoAccumulateSpatialImpulses(int, const Eigen::Ref<const VectorX<T>>&,
SpatialForce<T>*) const final{};
SpatialForce<T>*) const final {};

Parameters parameters_;
int clique_dof_{-1}; // Initialized to an invalid value.
2 changes: 1 addition & 1 deletion multibody/contact_solvers/sap/sap_model.h
Original file line number Diff line number Diff line change
@@ -88,7 +88,7 @@ struct MomentumGainCache {
template <typename T>
struct CostCache {
T cost{NAN}; // Total primal cost, = momentum_cost + regularizer_cost.
T momentum_cost{NAN}; // Momentum cost, = 1/2⋅(v−v*)ᵀ⋅A⋅(v−v*).
T momentum_cost{NAN}; // Momentum cost, = 1/2⋅(v−v*)ᵀ⋅A⋅(v−v*).
T regularizer_cost{NAN}; // Regularizer cost, = 1/2⋅γᵀ⋅R⋅γ.
};

2 changes: 1 addition & 1 deletion multibody/contact_solvers/sap/sap_solver.h
Original file line number Diff line number Diff line change
@@ -105,7 +105,7 @@ struct SapSolverParameters {
// SapStatistics::optimality_condition_reached indicates if this condition
// was reached.
double abs_tolerance{1.e-14}; // Absolute tolerance εₐ, square root of Joule.
double rel_tolerance{1.e-6}; // Relative tolerance εᵣ.
double rel_tolerance{1.e-6}; // Relative tolerance εᵣ.

// Cost condition criterion: We monitor the decrease of the cost on each
// iteration. It is not worth it to keep iterating if round-off errors do not
14 changes: 7 additions & 7 deletions multibody/plant/tamsi_solver.h
Original file line number Diff line number Diff line change
@@ -1080,13 +1080,13 @@ class TamsiSolver {
int nc_, nv_;
VectorX<T> Delta_vn_; // Δvₙᵏ = Jₙ Δvᵏ, in ℝⁿᶜ, for the k-th iteration.
VectorX<T> Delta_vt_; // Δvₜᵏ = Jₜ Δvᵏ, in ℝ²ⁿᶜ, for the k-th iteration.
VectorX<T> vn_; // vₙᵏ, in ℝⁿᶜ.
VectorX<T> vt_; // vₜᵏ, in ℝ²ⁿᶜ.
VectorX<T> fn_; // fₙᵏ, in ℝⁿᶜ.
VectorX<T> ft_; // fₜᵏ, in ℝ²ⁿᶜ.
VectorX<T> t_hat_; // Tangential directions, t̂ᵏ. In ℝ²ⁿᶜ.
VectorX<T> v_slip_; // vₛᵏ = ‖vₜᵏ‖, in ℝⁿᶜ.
VectorX<T> mus_; // (modified) regularized friction, in ℝⁿᶜ.
VectorX<T> vn_; // vₙᵏ, in ℝⁿᶜ.
VectorX<T> vt_; // vₜᵏ, in ℝ²ⁿᶜ.
VectorX<T> fn_; // fₙᵏ, in ℝⁿᶜ.
VectorX<T> ft_; // fₜᵏ, in ℝ²ⁿᶜ.
VectorX<T> t_hat_; // Tangential directions, t̂ᵏ. In ℝ²ⁿᶜ.
VectorX<T> v_slip_; // vₛᵏ = ‖vₜᵏ‖, in ℝⁿᶜ.
VectorX<T> mus_; // (modified) regularized friction, in ℝⁿᶜ.
// Vector of size nc storing ∂fₜ/∂vₜ (in ℝ²ˣ²) for each contact point.
std::vector<Matrix2<T>> dft_dv_;
MatrixX<T> Gn_; // ∇ᵥfₙ(xˢ⁺¹, vₙˢ⁺¹), in ℝⁿᶜˣⁿᵛ
6 changes: 3 additions & 3 deletions multibody/tree/test/tree_from_mobilizers_test.cc
Original file line number Diff line number Diff line change
@@ -1252,9 +1252,9 @@ TEST_F(PendulumKinematicTests, CalcVelocityKinematicsWithAutoDiffXd) {
const double Pc_from_autodiff = -V.derivatives()[0];
EXPECT_NEAR(Pc, Pc_from_autodiff, kTolerance);
} // ielbow
} // ishoulder
} // iw_elbow
} // iw_shoulder
} // ishoulder
} // iw_elbow
} // iw_shoulder
}

TEST_F(PendulumKinematicTests, PointsPositionsAndRelativeTransform) {

0 comments on commit d243930

Please sign in to comment.