Skip to content

Commit fb7ce9f

Browse files
committed
Remove dead code
Eigen 5's simplified constructors now help the compiler flag "unused variable" errors on dead matrices.
1 parent 3472e68 commit fb7ce9f

File tree

5 files changed

+0
-10
lines changed

5 files changed

+0
-10
lines changed

examples/multibody/cart_pole/test/cart_pole_test.cc

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -143,7 +143,6 @@ TEST_F(CartPoleTest, SystemDynamics) {
143143
const Vector2<double> q(2.5, M_PI / 3);
144144
const Vector2<double> v(-1.5, 0.5);
145145

146-
Matrix2<double> M;
147146
cart_slider_->set_translation(context_.get(), q(0));
148147
cart_slider_->set_translation_rate(context_.get(), v(0));
149148
pole_pin_->set_angle(context_.get(), q(1));

math/test/rigid_transform_test.cc

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -854,7 +854,6 @@ GTEST_TEST(RigidTransform, SpecializedTransformOperators) {
854854

855855
// Test ApplyAxialRotation().
856856
const Vector3d p_C(1.0, 2.0, 3.0);
857-
Vector3d p_B; // reusable result
858857
EXPECT_TRUE(CompareMatrices(Xform::ApplyAxialRotation<0>(xrX_BC, p_C),
859858
xrX_BC * p_C, kTol));
860859
EXPECT_TRUE(CompareMatrices(Xform::ApplyAxialRotation<1>(yrX_BC, p_C),

math/test/rotation_matrix_test.cc

Lines changed: 0 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -720,7 +720,6 @@ GTEST_TEST(RotationMatrix, AxialRotationOperators) {
720720

721721
// Test ApplyAxialRotation().
722722
const Vector3d v_C(1.0, 2.0, 3.0);
723-
Vector3d v_B; // reusable result
724723
EXPECT_TRUE(CompareMatrices(Rmat::ApplyAxialRotation<0>(xR_BC, v_C),
725724
xR_BC * v_C, kTol));
726725
EXPECT_TRUE(CompareMatrices(Rmat::ApplyAxialRotation<1>(yR_BC, v_C),
@@ -803,7 +802,6 @@ GTEST_TEST(RotationMatrix, AxialRotationOptimizations) {
803802

804803
// But ... ApplyAxialRotation() should work anyway with this junk in place.
805804
const Vector3d v_C(1.0, 2.0, 3.0);
806-
Vector3d v_B;
807805
EXPECT_TRUE(CompareMatrices(Rmat::ApplyAxialRotation<1>(yR_BC_mangled, v_C),
808806
yR_BC * v_C, kTol));
809807

solvers/mixed_integer_rotation_constraint.cc

Lines changed: 0 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -520,9 +520,6 @@ void AddBoxSphereIntersectionConstraints(
520520
double cos_theta = d;
521521
const double theta = std::acos(cos_theta);
522522

523-
Eigen::Matrix<double, 1, 6> a;
524-
Eigen::Matrix<double, 3, 9> A_cross;
525-
526523
Eigen::Vector3d orthant_normal;
527524
Vector3<Expression> orthant_c;
528525
for (int o = 0; o < 8; o++) { // iterate over orthants

solvers/test/mathematical_program_test.cc

Lines changed: 0 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -4369,9 +4369,6 @@ GTEST_TEST(TestMathematicalProgram, AddConstraintMatrix2) {
43694369
ASSERT_EQ(prog.GetAllConstraints().size(), 1);
43704370
ASSERT_EQ(prog.GetAllLinearConstraints().size(), 1);
43714371

4372-
Eigen::Matrix<double, 4, 2> A_expected;
4373-
Eigen::Matrix<double, 4, 1> lower_bound_expected;
4374-
Eigen::Matrix<double, 4, 1> upper_bound_expected;
43754372
std::array<std::array<Eigen::RowVector2d, 2>, 2> coeff;
43764373
coeff[0][0] << 1, 0;
43774374
coeff[0][1] << 1, 2;

0 commit comments

Comments
 (0)