From e4dcbc0f8b8b0df39230bd1930626497c68299c0 Mon Sep 17 00:00:00 2001 From: Joan Aguilar Mayans Date: Tue, 22 Nov 2022 15:35:55 -0800 Subject: [PATCH] Change matrix initialization in order to support older versions of Eigen. Signed-off-by: Joan Aguilar Mayans --- dartsim/src/SDFFeatures_TEST.cc | 16 ++++++++-------- 1 file changed, 8 insertions(+), 8 deletions(-) diff --git a/dartsim/src/SDFFeatures_TEST.cc b/dartsim/src/SDFFeatures_TEST.cc index ac2b16977..1942d2a6d 100644 --- a/dartsim/src/SDFFeatures_TEST.cc +++ b/dartsim/src/SDFFeatures_TEST.cc @@ -942,14 +942,14 @@ TEST_P(SDFFeatures_TEST, AddedMass) // Expected spatial inertia matrix. This includes inertia due to the body's // mass and added mass. Note that the ordering of the matrix is different // than the one used in SDF. - const Eigen::Matrix6d expectedSpatialInertia { - {17, 17, 18, 4, 9, 13}, - {17, 20, 20, 5, 10, 14}, - {18, 20, 22, 6, 11, 15}, - {4, 5, 6, 2, 2, 3}, - {9, 10, 11, 2, 8, 8}, - {13, 14, 15, 3, 8, 13} - }; + Eigen::Matrix6d expectedSpatialInertia; + expectedSpatialInertia << + 17, 17, 18, 4, 9, 13, + 17, 20, 20, 5, 10, 14, + 18, 20, 22, 6, 11, 15, + 4, 5, 6, 2, 2, 3, + 9, 10, 11, 2, 8, 8, + 13, 14, 15, 3, 8, 13; auto world = this->LoadWorld(TEST_WORLD_DIR"/added_mass.sdf"); ASSERT_NE(nullptr, world);