From c66185df7d506cc38b6a389ed8d67b1296bd5bca Mon Sep 17 00:00:00 2001 From: Jeremy Nimmer Date: Fri, 3 Oct 2025 07:24:42 -0700 Subject: [PATCH] Fix Eigen-related constructor snafus in tests Eigen 5's simplified constructors now help the compiler flag "unused variable" errors on dead matrices. Similarly, the compiler also flags "uninitialized const" on the default constructor so we need to zero out some test constants. --- examples/multibody/cart_pole/test/cart_pole_test.cc | 1 - math/test/rigid_transform_test.cc | 1 - math/test/rotation_matrix_test.cc | 2 -- solvers/mixed_integer_rotation_constraint.cc | 3 --- solvers/test/mathematical_program_test.cc | 3 --- systems/primitives/test/affine_system_test.cc | 12 ++++++------ .../primitives/test/multilayer_perceptron_test.cc | 2 +- 7 files changed, 7 insertions(+), 17 deletions(-) diff --git a/examples/multibody/cart_pole/test/cart_pole_test.cc b/examples/multibody/cart_pole/test/cart_pole_test.cc index a0ad1abd58c9..cce814b79b98 100644 --- a/examples/multibody/cart_pole/test/cart_pole_test.cc +++ b/examples/multibody/cart_pole/test/cart_pole_test.cc @@ -143,7 +143,6 @@ TEST_F(CartPoleTest, SystemDynamics) { const Vector2 q(2.5, M_PI / 3); const Vector2 v(-1.5, 0.5); - Matrix2 M; cart_slider_->set_translation(context_.get(), q(0)); cart_slider_->set_translation_rate(context_.get(), v(0)); pole_pin_->set_angle(context_.get(), q(1)); diff --git a/math/test/rigid_transform_test.cc b/math/test/rigid_transform_test.cc index bc05f8fd3c14..e542a34dde9a 100644 --- a/math/test/rigid_transform_test.cc +++ b/math/test/rigid_transform_test.cc @@ -854,7 +854,6 @@ GTEST_TEST(RigidTransform, SpecializedTransformOperators) { // Test ApplyAxialRotation(). const Vector3d p_C(1.0, 2.0, 3.0); - Vector3d p_B; // reusable result EXPECT_TRUE(CompareMatrices(Xform::ApplyAxialRotation<0>(xrX_BC, p_C), xrX_BC * p_C, kTol)); EXPECT_TRUE(CompareMatrices(Xform::ApplyAxialRotation<1>(yrX_BC, p_C), diff --git a/math/test/rotation_matrix_test.cc b/math/test/rotation_matrix_test.cc index 5ed5846c06e9..e15bc591f11f 100644 --- a/math/test/rotation_matrix_test.cc +++ b/math/test/rotation_matrix_test.cc @@ -720,7 +720,6 @@ GTEST_TEST(RotationMatrix, AxialRotationOperators) { // Test ApplyAxialRotation(). const Vector3d v_C(1.0, 2.0, 3.0); - Vector3d v_B; // reusable result EXPECT_TRUE(CompareMatrices(Rmat::ApplyAxialRotation<0>(xR_BC, v_C), xR_BC * v_C, kTol)); EXPECT_TRUE(CompareMatrices(Rmat::ApplyAxialRotation<1>(yR_BC, v_C), @@ -803,7 +802,6 @@ GTEST_TEST(RotationMatrix, AxialRotationOptimizations) { // But ... ApplyAxialRotation() should work anyway with this junk in place. const Vector3d v_C(1.0, 2.0, 3.0); - Vector3d v_B; EXPECT_TRUE(CompareMatrices(Rmat::ApplyAxialRotation<1>(yR_BC_mangled, v_C), yR_BC * v_C, kTol)); diff --git a/solvers/mixed_integer_rotation_constraint.cc b/solvers/mixed_integer_rotation_constraint.cc index d180297a8f0d..993447b83e65 100644 --- a/solvers/mixed_integer_rotation_constraint.cc +++ b/solvers/mixed_integer_rotation_constraint.cc @@ -520,9 +520,6 @@ void AddBoxSphereIntersectionConstraints( double cos_theta = d; const double theta = std::acos(cos_theta); - Eigen::Matrix a; - Eigen::Matrix A_cross; - Eigen::Vector3d orthant_normal; Vector3 orthant_c; for (int o = 0; o < 8; o++) { // iterate over orthants diff --git a/solvers/test/mathematical_program_test.cc b/solvers/test/mathematical_program_test.cc index cc381edfbc37..6e3a49cc4146 100644 --- a/solvers/test/mathematical_program_test.cc +++ b/solvers/test/mathematical_program_test.cc @@ -4369,9 +4369,6 @@ GTEST_TEST(TestMathematicalProgram, AddConstraintMatrix2) { ASSERT_EQ(prog.GetAllConstraints().size(), 1); ASSERT_EQ(prog.GetAllLinearConstraints().size(), 1); - Eigen::Matrix A_expected; - Eigen::Matrix lower_bound_expected; - Eigen::Matrix upper_bound_expected; std::array, 2> coeff; coeff[0][0] << 1, 0; coeff[0][1] << 1, 2; diff --git a/systems/primitives/test/affine_system_test.cc b/systems/primitives/test/affine_system_test.cc index 0bfc07c34798..d8f3f9f18911 100644 --- a/systems/primitives/test/affine_system_test.cc +++ b/systems/primitives/test/affine_system_test.cc @@ -142,12 +142,12 @@ TEST_F(AffineSystemTest, UpdateCoefficients) { } TEST_F(AffineSystemTest, UpdateCoefficientsButWrongSize) { - const Eigen::Matrix new_A; - const Eigen::Matrix new_B; - const Eigen::Vector3d new_f0; - const Eigen::Matrix3d new_C; - const Eigen::Matrix4d new_D; - const Eigen::Vector4d new_y0; + const Eigen::Matrix new_A = Eigen::Matrix::Zero(); + const Eigen::Matrix new_B = Eigen::Matrix::Zero(); + const Eigen::Vector3d new_f0 = Eigen::Vector3d::Zero(); + const Eigen::Matrix3d new_C = Eigen::Matrix3d::Zero(); + const Eigen::Matrix4d new_D = Eigen::Matrix4d::Zero(); + const Eigen::Vector4d new_y0 = Eigen::Vector4d::Zero(); const std::string error_msg_regrex = "^New and current .* have different sizes\\.$"; diff --git a/systems/primitives/test/multilayer_perceptron_test.cc b/systems/primitives/test/multilayer_perceptron_test.cc index 92b49b27b45e..bec4c7ee4182 100644 --- a/systems/primitives/test/multilayer_perceptron_test.cc +++ b/systems/primitives/test/multilayer_perceptron_test.cc @@ -330,7 +330,7 @@ GTEST_TEST(MultilayerPereceptronTest, BatchOutputWithGradients) { GTEST_TEST(MultilayerPerceptronTest, BatchOutputWithGradientsThrows) { MultilayerPerceptron mlp({2, 2}); auto context = mlp.CreateDefaultContext(); - const Eigen::Matrix2d X; + const Eigen::Matrix2d X = Eigen::Matrix2d::Zero(); Eigen::Matrix2d Y, dYdX; DRAKE_EXPECT_THROWS_MESSAGE(