Skip to content

Commit

Permalink
enforce clang-format
Browse files Browse the repository at this point in the history
  • Loading branch information
amcastro-tri committed May 22, 2024
1 parent a0da38e commit 9d1b7ff
Show file tree
Hide file tree
Showing 6 changed files with 92 additions and 72 deletions.
2 changes: 1 addition & 1 deletion examples/rod2d/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -111,4 +111,4 @@ drake_cc_googletest(
],
)

add_lint_tests(enable_clang_format_lint = False)
add_lint_tests()
2 changes: 1 addition & 1 deletion examples/rod2d/constraint_problem_data.h
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@ namespace rod2d {
/// constraints, etc.)
///
/// <h3>Definition of variables specific to this class</h3>
/// (See @ref constraint_variable_defs) for the more general set of
/// (See "Variable definitions" in the local README) for the more general set of
/// definitions).
///
/// - ns ∈ ℕ The number of contacts at which sliding is occurring. Note
Expand Down
4 changes: 2 additions & 2 deletions examples/rod2d/constraint_solver.h
Original file line number Diff line number Diff line change
Expand Up @@ -162,8 +162,8 @@ class ConstraintSolver {
/// `x₆`, `x₇`, and `x₈` can be viewed as mathematical programming "slack"
/// variables; and `kᴳ ∈ ℝⁿᵇ`, `kᴺ ∈ ℝⁿᶜ`, `kᴰ ∈ ℝⁿᶜᵏ`, `kᴸ ∈ ℝⁿᵘ`
/// allow customizing the problem to, e.g., correct constraint violations and
/// simulate restitution. See @ref constraint_variable_defs for complete
/// definitions of `nv`, `nc`, `nb`, etc.
/// simulate restitution. See "Variable definitions" in the local README for
/// complete definitions of `nv`, `nc`, `nb`, etc.
///
/// From the notation above in Equations (a)-(d), we can convert the MLCP
/// to a "pure" linear complementarity problem (LCP), which is easier to
Expand Down
36 changes: 29 additions & 7 deletions examples/rod2d/rod2d.cc
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@ Rod2D<T>::Rod2D(SystemType system_type, double dt)
// Both piecewise DAE and compliant approach require six continuous
// variables.
auto state_index = this->DeclareContinuousState(Rod2dStateVector<T>(), 3, 3,
0); // q, v, z
0 /* q, v, z */);
state_output_port_ =
&this->DeclareStateOutputPort("state_output", state_index);
}
Expand Down Expand Up @@ -127,7 +127,11 @@ MatrixX<T> Rod2D<T>::solve_inertia(const MatrixX<T>& B) const {
const T inv_mass = 1.0 / get_rod_mass();
const T inv_J = 1.0 / get_rod_moment_of_inertia();
Matrix3<T> iM;
iM << inv_mass, 0, 0, 0, inv_mass, 0, 0, 0, inv_J;
// clang-format off
iM << inv_mass, 0, 0,
0, inv_mass, 0,
0, 0, inv_J;
// clang-format on
return iM * B;
}

Expand Down Expand Up @@ -269,7 +273,10 @@ Matrix2<T> Rod2D<T>::GetSlidingContactFrameToWorldTransform(
DRAKE_DEMAND(xaxis_velocity != 0);
Matrix2<T> R_WC;
// R_WC's elements match how they appear lexically: one row per line.
R_WC << 0, ((xaxis_velocity > 0) ? 1 : -1), 1, 0;
// clang-format off
R_WC << 0, ((xaxis_velocity > 0) ? 1 : -1),
1, 0;
// clang-format on
return R_WC;
}

Expand All @@ -286,7 +293,10 @@ Matrix2<T> Rod2D<T>::GetNonSlidingContactFrameToWorldTransform() const {
// axis in the contact frame) is +x in the world frame.
Matrix2<T> R_WC;
// R_WC's elements match how they appear lexically: one row per line.
R_WC << 0, 1, 1, 0;
// clang-format off
R_WC << 0, 1,
1, 0;
// clang-format on
return R_WC;
}

Expand Down Expand Up @@ -412,7 +422,11 @@ void Rod2D<T>::CalcImpactProblemData(const systems::Context<T>& context,

// Setup the generalized inertia matrix.
Matrix3<T> M;
M << mass_, 0, 0, 0, mass_, 0, 0, 0, J_;
// clang-format off
M << mass_, 0, 0,
0, mass_, 0,
0, 0, J_;
// clang-format on

// Get the generalized velocity.
data->Mv =
Expand Down Expand Up @@ -768,7 +782,11 @@ Vector2<T> Rod2D<T>::CalcStickingImpactImpulse(
template <class T>
Matrix3<T> Rod2D<T>::GetInertiaMatrix() const {
Matrix3<T> M;
M << mass_, 0, 0, 0, mass_, 0, 0, 0, J_;
// clang-format off
M << mass_, 0, 0,
0, mass_, 0,
0, 0, J_;
// clang-format on
return M;
}

Expand All @@ -777,7 +795,11 @@ Matrix3<T> Rod2D<T>::GetInertiaMatrix() const {
template <class T>
Matrix3<T> Rod2D<T>::GetInverseInertiaMatrix() const {
Matrix3<T> M_inv;
M_inv << 1.0 / mass_, 0, 0, 0, 1.0 / mass_, 0, 0, 0, 1.0 / J_;
// clang-format off
M_inv << 1.0 / mass_, 0, 0,
0, 1.0 / mass_, 0,
0, 0, 1.0 / J_;
// clang-format on
return M_inv;
}

Expand Down
8 changes: 4 additions & 4 deletions examples/rod2d/rod2d_sim.cc
Original file line number Diff line number Diff line change
Expand Up @@ -44,11 +44,11 @@ int main(int argc, char* argv[]) {
// Create the rod and add it to the diagram.
Rod2D* rod;
if (FLAGS_system_type == "discretized") {
rod = builder.template AddSystem<Rod2D>(
Rod2D::SystemType::kDiscretized, FLAGS_dt);
rod = builder.template AddSystem<Rod2D>(Rod2D::SystemType::kDiscretized,
FLAGS_dt);
} else if (FLAGS_system_type == "continuous") {
rod = builder.template AddSystem<Rod2D>(Rod2D::SystemType::kContinuous,
0.0);
rod =
builder.template AddSystem<Rod2D>(Rod2D::SystemType::kContinuous, 0.0);
} else {
std::cerr << "Invalid simulation type '" << FLAGS_system_type
<< "'; note that types are case sensitive." << std::endl;
Expand Down
Loading

0 comments on commit 9d1b7ff

Please sign in to comment.