diff --git a/examples/rod2d/BUILD.bazel b/examples/rod2d/BUILD.bazel index 46f5eeb3a6f4..0dbe9a41a1cc 100644 --- a/examples/rod2d/BUILD.bazel +++ b/examples/rod2d/BUILD.bazel @@ -111,4 +111,4 @@ drake_cc_googletest( ], ) -add_lint_tests(enable_clang_format_lint = False) +add_lint_tests() diff --git a/examples/rod2d/constraint_problem_data.h b/examples/rod2d/constraint_problem_data.h index 0273407067e9..ff1f9e023e05 100644 --- a/examples/rod2d/constraint_problem_data.h +++ b/examples/rod2d/constraint_problem_data.h @@ -24,7 +24,7 @@ namespace rod2d { /// constraints, etc.) /// ///

Definition of variables specific to this class

-/// (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 diff --git a/examples/rod2d/constraint_solver.h b/examples/rod2d/constraint_solver.h index da0ef6062bfb..8da67775ad91 100644 --- a/examples/rod2d/constraint_solver.h +++ b/examples/rod2d/constraint_solver.h @@ -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 diff --git a/examples/rod2d/rod2d.cc b/examples/rod2d/rod2d.cc index 2a5498242ee3..447fad2441c4 100644 --- a/examples/rod2d/rod2d.cc +++ b/examples/rod2d/rod2d.cc @@ -44,7 +44,7 @@ Rod2D::Rod2D(SystemType system_type, double dt) // Both piecewise DAE and compliant approach require six continuous // variables. auto state_index = this->DeclareContinuousState(Rod2dStateVector(), 3, 3, - 0); // q, v, z + 0 /* q, v, z */); state_output_port_ = &this->DeclareStateOutputPort("state_output", state_index); } @@ -127,7 +127,11 @@ MatrixX Rod2D::solve_inertia(const MatrixX& B) const { const T inv_mass = 1.0 / get_rod_mass(); const T inv_J = 1.0 / get_rod_moment_of_inertia(); Matrix3 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; } @@ -269,7 +273,10 @@ Matrix2 Rod2D::GetSlidingContactFrameToWorldTransform( DRAKE_DEMAND(xaxis_velocity != 0); Matrix2 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; } @@ -286,7 +293,10 @@ Matrix2 Rod2D::GetNonSlidingContactFrameToWorldTransform() const { // axis in the contact frame) is +x in the world frame. Matrix2 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; } @@ -412,7 +422,11 @@ void Rod2D::CalcImpactProblemData(const systems::Context& context, // Setup the generalized inertia matrix. Matrix3 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 = @@ -768,7 +782,11 @@ Vector2 Rod2D::CalcStickingImpactImpulse( template Matrix3 Rod2D::GetInertiaMatrix() const { Matrix3 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; } @@ -777,7 +795,11 @@ Matrix3 Rod2D::GetInertiaMatrix() const { template Matrix3 Rod2D::GetInverseInertiaMatrix() const { Matrix3 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; } diff --git a/examples/rod2d/rod2d_sim.cc b/examples/rod2d/rod2d_sim.cc index 26d26531c3b4..7a9299da88e0 100644 --- a/examples/rod2d/rod2d_sim.cc +++ b/examples/rod2d/rod2d_sim.cc @@ -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::SystemType::kDiscretized, FLAGS_dt); + rod = builder.template AddSystem(Rod2D::SystemType::kDiscretized, + FLAGS_dt); } else if (FLAGS_system_type == "continuous") { - rod = builder.template AddSystem(Rod2D::SystemType::kContinuous, - 0.0); + rod = + builder.template AddSystem(Rod2D::SystemType::kContinuous, 0.0); } else { std::cerr << "Invalid simulation type '" << FLAGS_system_type << "'; note that types are case sensitive." << std::endl; diff --git a/examples/rod2d/test/rod2d_test.cc b/examples/rod2d/test/rod2d_test.cc index daafa4265652..1199420cb4ed 100644 --- a/examples/rod2d/test/rod2d_test.cc +++ b/examples/rod2d/test/rod2d_test.cc @@ -10,14 +10,14 @@ #include "drake/examples/rod2d/constraint_solver.h" #include "drake/systems/analysis/simulator.h" -using drake::systems::VectorBase; +using drake::systems::AbstractValues; using drake::systems::BasicVector; +using drake::systems::Context; using drake::systems::ContinuousState; +using drake::systems::Simulator; using drake::systems::State; using drake::systems::SystemOutput; -using drake::systems::AbstractValues; -using drake::systems::Simulator; -using drake::systems::Context; +using drake::systems::VectorBase; using Eigen::Vector2d; using Eigen::Vector3d; @@ -72,8 +72,7 @@ class Rod2DDAETest : public ::testing::Test { using std::sqrt; const double half_len = dut_->get_rod_half_length(); const double r22 = std::sqrt(2) / 2; - ContinuousState& xc = - context_->get_mutable_continuous_state(); + ContinuousState& xc = context_->get_mutable_continuous_state(); xc[0] = -half_len * r22; xc[1] = half_len * r22; xc[2] = 3 * M_PI / 4.0; @@ -87,8 +86,7 @@ class Rod2DDAETest : public ::testing::Test { // Sets the rod to a state that corresponds to ballistic motion. void SetBallisticState() { const double half_len = dut_->get_rod_half_length(); - ContinuousState& xc = - context_->get_mutable_continuous_state(); + ContinuousState& xc = context_->get_mutable_continuous_state(); xc[0] = 0.0; xc[1] = 10 * half_len; xc[2] = M_PI_2; @@ -104,9 +102,9 @@ class Rod2DDAETest : public ::testing::Test { void SetInterpenetratingConfig() { ContinuousState& xc = context_->get_mutable_continuous_state(); // Configuration has the rod on its side. - xc[0] = 0.0; // com horizontal position - xc[1] = -1.0; // com vertical position - xc[2] = 0.0; // rod rotation + xc[0] = 0.0; // com horizontal position + xc[1] = -1.0; // com vertical position + xc[2] = 0.0; // rod rotation } // Sets the rod to a resting horizontal configuration without modifying the @@ -114,20 +112,20 @@ class Rod2DDAETest : public ::testing::Test { void SetRestingHorizontalConfig() { ContinuousState& xc = context_->get_mutable_continuous_state(); // Configuration has the rod on its side. - xc[0] = 0.0; // com horizontal position - xc[1] = 0.0; // com vertical position - xc[2] = 0.0; // rod rotation - xc[3] = xc[4] = xc[5] = 0.0; // velocity variables + xc[0] = 0.0; // com horizontal position + xc[1] = 0.0; // com vertical position + xc[2] = 0.0; // rod rotation + xc[3] = xc[4] = xc[5] = 0.0; // velocity variables } // Sets the rod to a resting vertical configuration without modifying the // mode variables. void SetRestingVerticalConfig() { ContinuousState& xc = context_->get_mutable_continuous_state(); - xc[0] = 0.0; // com horizontal position - xc[1] = dut_->get_rod_half_length(); // com vertical position - xc[2] = M_PI_2; // rod rotation - xc[3] = xc[4] = xc[5] = 0.0; // velocity variables + xc[0] = 0.0; // com horizontal position + xc[1] = dut_->get_rod_half_length(); // com vertical position + xc[2] = M_PI_2; // rod rotation + xc[3] = xc[4] = xc[5] = 0.0; // velocity variables } // Sets the contact mode such that the left endpoint is contacting. The caller @@ -143,15 +141,14 @@ class Rod2DDAETest : public ::testing::Test { // corresponds to an impact. SetSecondInitialConfig(); ContinuousState& xc = context_->get_mutable_continuous_state(); - xc[4] = -1.0; // com horizontal velocity + xc[4] = -1.0; // com horizontal velocity // TODO(edrumwri): Set the rod mode to indicate that it is in the single // contact sliding mode. } // Computes rigid impact data. - void CalcRigidImpactVelProblemData( - ConstraintVelProblemData* data) { + void CalcRigidImpactVelProblemData(ConstraintVelProblemData* data) { // Get the points of contact. std::vector contacts; dut_->GetContactPoints(*context_, &contacts); @@ -178,7 +175,8 @@ class Rod2DDAETest : public ::testing::Test { contact_solver_.ComputeGeneralizedVelocityChange(data, cf, &delta_v); // Update the velocity part of the state. - context_->get_mutable_continuous_state().get_mutable_generalized_velocity() + context_->get_mutable_continuous_state() + .get_mutable_generalized_velocity() .SetFromVector(data.solve_inertia(data.Mv) + delta_v); } @@ -193,21 +191,20 @@ class Rod2DDAETest : public ::testing::Test { // Checks the consistency of a transpose operator. void CheckTransOperatorDim( std::function(const VectorX&)> JT, - int num_constraints) { + int num_constraints) { EXPECT_EQ(JT(VectorX(num_constraints)).size(), get_rod_num_coordinates()); } // Checks consistency of rigid contact problem data. - void CheckProblemConsistency( - const ConstraintAccelProblemData& data, - int num_contacts) { + void CheckProblemConsistency(const ConstraintAccelProblemData& data, + int num_contacts) { // TODO(edrumwri): Stop short-circuiting this after piecewise DAE // implementation repaired. return; - EXPECT_EQ(num_contacts, data.sliding_contacts.size() + - data.non_sliding_contacts.size()); + EXPECT_EQ(num_contacts, + data.sliding_contacts.size() + data.non_sliding_contacts.size()); EXPECT_EQ(GetOperatorDim(data.N_mult), num_contacts); CheckTransOperatorDim(data.N_minus_muQ_transpose_mult, num_contacts); EXPECT_EQ(GetOperatorDim(data.L_mult), data.kL.size()); @@ -231,9 +228,8 @@ class Rod2DDAETest : public ::testing::Test { } // Checks consistency of rigid impact problem data. - void CheckProblemConsistency( - const ConstraintVelProblemData& data, - int num_contacts) { + void CheckProblemConsistency(const ConstraintVelProblemData& data, + int num_contacts) { EXPECT_EQ(num_contacts, data.mu.size()); EXPECT_EQ(num_contacts, data.r.size()); EXPECT_EQ(GetOperatorDim(data.N_mult), num_contacts); @@ -268,8 +264,8 @@ TEST_F(Rod2DDAETest, NamedStateVectorsNoThrow) { // Tests that named state vector components are at expected indices. TEST_F(Rod2DDAETest, ExpectedIndices) { // Set the state. - Rod2dStateVector& state = Rod2D::get_mutable_state( - context_.get()); + Rod2dStateVector& state = + Rod2D::get_mutable_state(context_.get()); state.set_x(1.0); state.set_y(2.0); state.set_theta(3.0); @@ -290,8 +286,7 @@ TEST_F(Rod2DDAETest, ExpectedIndices) { // Checks that the output port represents the state. TEST_F(Rod2DDAETest, Output) { const ContinuousState& xc = context_->get_continuous_state(); - std::unique_ptr> output = - dut_->AllocateOutput(); + std::unique_ptr> output = dut_->AllocateOutput(); dut_->CalcOutput(*context_, output.get()); for (int i = 0; i < xc.size(); ++i) EXPECT_EQ(xc[i], output->get_vector_data(0)->value()(i)); @@ -422,9 +417,9 @@ TEST_F(Rod2DDAETest, DerivativesContactingAndSticking) { // Set the coefficient of friction such that the contact forces are right // on the edge of the friction cone. Determine the predicted normal force // (this simple formula is dependent upon the upright rod configuration). - const double mu_stick = f_x / (dut_->get_rod_mass() * - -dut_->get_gravitational_acceleration() - - f_y); + const double mu_stick = + f_x / + (dut_->get_rod_mass() * -dut_->get_gravitational_acceleration() - f_y); dut_->set_mu_coulomb(mu_stick); // TODO(edrumwri): Calculate the derivatives. @@ -450,13 +445,13 @@ TEST_F(Rod2DDAETest, ImpactNoChange) { // TODO(edrumwri): Verify not impacting at initial state. // Get the continuous state. - const VectorX xc_old = context_->get_continuous_state(). - get_vector().CopyToVector(); + const VectorX xc_old = + context_->get_continuous_state().get_vector().CopyToVector(); // Model the impact and get the continuous state out. // TODO(edrumwri): Model the impact here. - const VectorX xc = context_->get_continuous_state(). - get_vector().CopyToVector(); + const VectorX xc = + context_->get_continuous_state().get_vector().CopyToVector(); // TODO(edrumwri): Verify the continuous state did not change. } @@ -760,7 +755,7 @@ class Rod2DDiscretizedTest : public ::testing::Test { BasicVector& mutable_discrete_state() { return context_->get_mutable_discrete_state(0); } -// Sets a secondary initial Rod2D configuration. + // Sets a secondary initial Rod2D configuration. void SetSecondInitialConfig() { // Set the configuration to an inconsistent (Painlevé) type state with // the rod at a 135 degree counter-clockwise angle with respect to the @@ -927,12 +922,12 @@ GTEST_TEST(Rod2DCrossValidationTest, OneStepSolutionSticking) { // piecewise DAE based approach. std::unique_ptr> f = pdae.AllocateTimeDerivatives(); // TODO(edrumwri): Compute derivatives here. - xc[3] += + dt * ((*f)[3]); - xc[4] += + dt * ((*f)[4]); - xc[5] += + dt * ((*f)[5]); - xc[0] += + dt * xc[3]; - xc[1] += + dt * xc[4]; - xc[2] += + dt * xc[5]; + xc[3] += +dt * ((*f)[3]); + xc[4] += +dt * ((*f)[4]); + xc[5] += +dt * ((*f)[5]); + xc[0] += +dt * xc[3]; + xc[1] += +dt * xc[4]; + xc[2] += +dt * xc[5]; // TODO(edrumwri): Check that the solution is nearly identical. } @@ -983,13 +978,17 @@ class Rod2DContinuousTest : public ::testing::Test { // Sets the planar pose in the context. void set_pose(double x, double y, double theta) { ContinuousState& xc = context_->get_mutable_continuous_state(); - xc[0] = x; xc[1] = y; xc[2] = theta; + xc[0] = x; + xc[1] = y; + xc[2] = theta; } // Sets the planar velocity in the context. void set_velocity(double xdot, double ydot, double thetadot) { ContinuousState& xc = context_->get_mutable_continuous_state(); - xc[3] = xdot; xc[4] = ydot; xc[5] = thetadot; + xc[3] = xdot; + xc[4] = ydot; + xc[5] = thetadot; } // Returns planar pose derivative (should be planar velocities xdot, @@ -1008,7 +1007,7 @@ class Rod2DContinuousTest : public ::testing::Test { // Sets the rod to a state that corresponds to ballistic motion. void SetBallisticState() { const double half_len = dut_->get_rod_half_length(); - set_pose(0, 10*half_len, M_PI_2); + set_pose(0, 10 * half_len, M_PI_2); set_velocity(1, 2, 3); } @@ -1021,7 +1020,7 @@ class Rod2DContinuousTest : public ::testing::Test { DRAKE_DEMAND(-1 <= k && k <= 1); const double half_len = dut_->get_rod_half_length(); const double penetration = 0.01; // 1 cm - set_pose(0, std::abs(k)*half_len - penetration, -k*M_PI_2); + set_pose(0, std::abs(k) * half_len - penetration, -k * M_PI_2); set_velocity(0, 0, 0); } @@ -1063,7 +1062,7 @@ TEST_F(Rod2DContinuousTest, ForcesHaveRightSign) { // the overall force. set_velocity(0, -10, 0); Vector3d F_Ro_W_ldown = dut_->CalcCompliantContactForces(*context_); - EXPECT_GT(F_Ro_W_ldown[1], 2*F_Ro_W_left[1]); // Did it double? + EXPECT_GT(F_Ro_W_ldown[1], 2 * F_Ro_W_left[1]); // Did it double? // An extreme upwards velocity should be a "pull out" situation resulting // in (exactly) zero force rather than a negative force. @@ -1087,7 +1086,6 @@ TEST_F(Rod2DContinuousTest, ForcesHaveRightSign) { EXPECT_NEAR(F_Ro_W_px[1], F_Ro_W_left[1], kTightTol); EXPECT_LT(F_Ro_W_px[2], -1.); - SetContactingState(1); // Right should behave same as left. Vector3d F_Ro_W_right = dut_->CalcCompliantContactForces(*context_); EXPECT_TRUE(F_Ro_W_right.isApprox(F_Ro_W_left, kTightTol)); @@ -1096,7 +1094,7 @@ TEST_F(Rod2DContinuousTest, ForcesHaveRightSign) { // be zero moment. SetContactingState(0); Vector3d F_Ro_W_both = dut_->CalcCompliantContactForces(*context_); - EXPECT_TRUE(F_Ro_W_both.isApprox(F_Ro_W_left+F_Ro_W_right, kTightTol)); + EXPECT_TRUE(F_Ro_W_both.isApprox(F_Ro_W_left + F_Ro_W_right, kTightTol)); EXPECT_NEAR(F_Ro_W_both[2], 0., kTightTol); }