diff --git a/fuse_constraints/CMakeLists.txt b/fuse_constraints/CMakeLists.txt
index b2a6a2790..946cbfa47 100644
--- a/fuse_constraints/CMakeLists.txt
+++ b/fuse_constraints/CMakeLists.txt
@@ -11,7 +11,7 @@ if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
endif()
-find_package(ament_cmake REQUIRED)
+find_package(ament_cmake_ros REQUIRED)
find_package(fuse_core REQUIRED)
find_package(fuse_graphs REQUIRED)
find_package(fuse_variables REQUIRED)
@@ -31,7 +31,7 @@ include(suitesparse-extras.cmake)
###########
# fuse_constraints library
-add_library(${PROJECT_NAME} SHARED
+add_library(${PROJECT_NAME}
src/absolute_constraint.cpp
src/absolute_orientation_3d_stamped_constraint.cpp
src/absolute_orientation_3d_stamped_euler_constraint.cpp
@@ -95,21 +95,11 @@ install(DIRECTORY include/
DESTINATION include/${PROJECT_NAME}
)
-install(
- FILES fuse_plugins.xml
- DESTINATION share/${PROJECT_NAME}
-)
-
-find_package(ament_cmake REQUIRED)
-find_package(fuse_core REQUIRED)
-find_package(fuse_graphs REQUIRED)
-find_package(fuse_variables REQUIRED)
-find_package(geometry_msgs REQUIRED)
-find_package(pluginlib REQUIRED)
-find_package(rclcpp REQUIRED)
+pluginlib_export_plugin_description_file(fuse_core fuse_plugins.xml)
+ament_export_targets(${PROJECT_NAME}-export HAS_LIBRARY_TARGET)
ament_export_dependencies(
- ament_cmake
+ ament_cmake_ros
fuse_core
fuse_graphs
fuse_variables
diff --git a/fuse_constraints/package.xml b/fuse_constraints/package.xml
index 13abf591c..76cd0c439 100644
--- a/fuse_constraints/package.xml
+++ b/fuse_constraints/package.xml
@@ -11,10 +11,10 @@
Stephen Williams
- Stephen Williams
BSD
+ Stephen Williams
- ament_cmake
+ ament_cmake_ros
eigen
libceres-dev
diff --git a/fuse_constraints/test/test_absolute_constraint.cpp b/fuse_constraints/test/test_absolute_constraint.cpp
index e6df8909a..448227242 100644
--- a/fuse_constraints/test/test_absolute_constraint.cpp
+++ b/fuse_constraints/test/test_absolute_constraint.cpp
@@ -451,9 +451,3 @@ TEST(AbsoluteConstraint, Serialization)
EXPECT_MATRIX_EQ(expected.mean(), actual.mean());
EXPECT_MATRIX_EQ(expected.sqrtInformation(), actual.sqrtInformation());
}
-
-int main(int argc, char **argv)
-{
- testing::InitGoogleTest(&argc, argv);
- return RUN_ALL_TESTS();
-}
diff --git a/fuse_constraints/test/test_absolute_orientation_3d_stamped_constraint.cpp b/fuse_constraints/test/test_absolute_orientation_3d_stamped_constraint.cpp
index 09cb88fb8..24e3cc5e7 100644
--- a/fuse_constraints/test/test_absolute_orientation_3d_stamped_constraint.cpp
+++ b/fuse_constraints/test/test_absolute_orientation_3d_stamped_constraint.cpp
@@ -194,9 +194,3 @@ TEST(AbsoluteOrientation3DStampedConstraint, Serialization)
EXPECT_MATRIX_EQ(expected.mean(), actual.mean());
EXPECT_MATRIX_EQ(expected.sqrtInformation(), actual.sqrtInformation());
}
-
-int main(int argc, char **argv)
-{
- testing::InitGoogleTest(&argc, argv);
- return RUN_ALL_TESTS();
-}
diff --git a/fuse_constraints/test/test_absolute_orientation_3d_stamped_euler_constraint.cpp b/fuse_constraints/test/test_absolute_orientation_3d_stamped_euler_constraint.cpp
index b9388a378..5c81770d6 100644
--- a/fuse_constraints/test/test_absolute_orientation_3d_stamped_euler_constraint.cpp
+++ b/fuse_constraints/test/test_absolute_orientation_3d_stamped_euler_constraint.cpp
@@ -251,9 +251,3 @@ TEST(AbsoluteOrientation3DStampedEulerConstraint, Serialization)
EXPECT_MATRIX_EQ(expected.mean(), actual.mean());
EXPECT_MATRIX_EQ(expected.sqrtInformation(), actual.sqrtInformation());
}
-
-int main(int argc, char **argv)
-{
- testing::InitGoogleTest(&argc, argv);
- return RUN_ALL_TESTS();
-}
diff --git a/fuse_constraints/test/test_absolute_pose_2d_stamped_constraint.cpp b/fuse_constraints/test/test_absolute_pose_2d_stamped_constraint.cpp
index ed47067ec..8d3785070 100644
--- a/fuse_constraints/test/test_absolute_pose_2d_stamped_constraint.cpp
+++ b/fuse_constraints/test/test_absolute_pose_2d_stamped_constraint.cpp
@@ -309,9 +309,3 @@ TEST(AbsolutePose2DStampedConstraint, Serialization)
EXPECT_MATRIX_EQ(expected.mean(), actual.mean());
EXPECT_MATRIX_EQ(expected.sqrtInformation(), actual.sqrtInformation());
}
-
-int main(int argc, char **argv)
-{
- testing::InitGoogleTest(&argc, argv);
- return RUN_ALL_TESTS();
-}
diff --git a/fuse_constraints/test/test_absolute_pose_3d_stamped_constraint.cpp b/fuse_constraints/test/test_absolute_pose_3d_stamped_constraint.cpp
index 6b8a89c13..2e5ce89b1 100644
--- a/fuse_constraints/test/test_absolute_pose_3d_stamped_constraint.cpp
+++ b/fuse_constraints/test/test_absolute_pose_3d_stamped_constraint.cpp
@@ -63,12 +63,12 @@ TEST(AbsolutePose3DStampedConstraint, Constructor)
// Generated PD matrix using Octave: R = rand(6, 6); A = R * R' (use format long g to get the required precision)
fuse_core::Matrix6d cov;
- cov << 2.0847236144069, 1.10752598122138, 1.02943174290333, 1.96120532313878, 1.96735470687891, 1.5153042667951,
- 1.10752598122138, 1.39176289439125, 0.643422499737987, 1.35471905449013, 1.18353784377297, 1.28979625492894,
- 1.02943174290333, 0.643422499737987, 1.26701658550187, 1.23641771365403, 1.55169301761377, 1.34706781598061,
- 1.96120532313878, 1.35471905449013, 1.23641771365403, 2.39750866789926, 2.06887486311147, 2.04350823837035,
- 1.96735470687891, 1.18353784377297, 1.55169301761377, 2.06887486311147, 2.503913946461, 1.73844731158092,
- 1.5153042667951, 1.28979625492894, 1.34706781598061, 2.04350823837035, 1.73844731158092, 2.15326088526198;
+ cov << 2.0847236144069, 1.10752598122138, 1.02943174290333, 1.96120532313878, 1.96735470687891, 1.5153042667951, // NOLINT
+ 1.10752598122138, 1.39176289439125, 0.643422499737987, 1.35471905449013, 1.18353784377297, 1.28979625492894, // NOLINT
+ 1.02943174290333, 0.643422499737987, 1.26701658550187, 1.23641771365403, 1.55169301761377, 1.34706781598061, // NOLINT
+ 1.96120532313878, 1.35471905449013, 1.23641771365403, 2.39750866789926, 2.06887486311147, 2.04350823837035, // NOLINT
+ 1.96735470687891, 1.18353784377297, 1.55169301761377, 2.06887486311147, 2.503913946461, 1.73844731158092, // NOLINT
+ 1.5153042667951, 1.28979625492894, 1.34706781598061, 2.04350823837035, 1.73844731158092, 2.15326088526198; // NOLINT
EXPECT_NO_THROW(
AbsolutePose3DStampedConstraint constraint("test", position_variable, orientation_variable, mean, cov));
@@ -85,12 +85,12 @@ TEST(AbsolutePose3DStampedConstraint, Covariance)
// Generated PD matrix using Octiave: R = rand(6, 6); A = R * R' (use format long g to get the required precision)
fuse_core::Matrix6d cov;
- cov << 2.0847236144069, 1.10752598122138, 1.02943174290333, 1.96120532313878, 1.96735470687891, 1.5153042667951,
- 1.10752598122138, 1.39176289439125, 0.643422499737987, 1.35471905449013, 1.18353784377297, 1.28979625492894,
- 1.02943174290333, 0.643422499737987, 1.26701658550187, 1.23641771365403, 1.55169301761377, 1.34706781598061,
- 1.96120532313878, 1.35471905449013, 1.23641771365403, 2.39750866789926, 2.06887486311147, 2.04350823837035,
- 1.96735470687891, 1.18353784377297, 1.55169301761377, 2.06887486311147, 2.503913946461, 1.73844731158092,
- 1.5153042667951, 1.28979625492894, 1.34706781598061, 2.04350823837035, 1.73844731158092, 2.15326088526198;
+ cov << 2.0847236144069, 1.10752598122138, 1.02943174290333, 1.96120532313878, 1.96735470687891, 1.5153042667951, // NOLINT
+ 1.10752598122138, 1.39176289439125, 0.643422499737987, 1.35471905449013, 1.18353784377297, 1.28979625492894, // NOLINT
+ 1.02943174290333, 0.643422499737987, 1.26701658550187, 1.23641771365403, 1.55169301761377, 1.34706781598061, // NOLINT
+ 1.96120532313878, 1.35471905449013, 1.23641771365403, 2.39750866789926, 2.06887486311147, 2.04350823837035, // NOLINT
+ 1.96735470687891, 1.18353784377297, 1.55169301761377, 2.06887486311147, 2.503913946461, 1.73844731158092, // NOLINT
+ 1.5153042667951, 1.28979625492894, 1.34706781598061, 2.04350823837035, 1.73844731158092, 2.15326088526198; // NOLINT
AbsolutePose3DStampedConstraint constraint("test", position_variable, orientation_variable, mean, cov);
@@ -227,12 +227,12 @@ TEST(AbsolutePose3DStampedConstraint, Serialization)
// Generated PD matrix using Octave: R = rand(6, 6); A = R * R' (use format long g to get the required precision)
fuse_core::Matrix6d cov;
- cov << 2.0847236144069, 1.10752598122138, 1.02943174290333, 1.96120532313878, 1.96735470687891, 1.5153042667951,
- 1.10752598122138, 1.39176289439125, 0.643422499737987, 1.35471905449013, 1.18353784377297, 1.28979625492894,
- 1.02943174290333, 0.643422499737987, 1.26701658550187, 1.23641771365403, 1.55169301761377, 1.34706781598061,
- 1.96120532313878, 1.35471905449013, 1.23641771365403, 2.39750866789926, 2.06887486311147, 2.04350823837035,
- 1.96735470687891, 1.18353784377297, 1.55169301761377, 2.06887486311147, 2.503913946461, 1.73844731158092,
- 1.5153042667951, 1.28979625492894, 1.34706781598061, 2.04350823837035, 1.73844731158092, 2.15326088526198;
+ cov << 2.0847236144069, 1.10752598122138, 1.02943174290333, 1.96120532313878, 1.96735470687891, 1.5153042667951, // NOLINT
+ 1.10752598122138, 1.39176289439125, 0.643422499737987, 1.35471905449013, 1.18353784377297, 1.28979625492894, // NOLINT
+ 1.02943174290333, 0.643422499737987, 1.26701658550187, 1.23641771365403, 1.55169301761377, 1.34706781598061, // NOLINT
+ 1.96120532313878, 1.35471905449013, 1.23641771365403, 2.39750866789926, 2.06887486311147, 2.04350823837035, // NOLINT
+ 1.96735470687891, 1.18353784377297, 1.55169301761377, 2.06887486311147, 2.503913946461, 1.73844731158092, // NOLINT
+ 1.5153042667951, 1.28979625492894, 1.34706781598061, 2.04350823837035, 1.73844731158092, 2.15326088526198; // NOLINT
AbsolutePose3DStampedConstraint expected("test", position_variable, orientation_variable, mean, cov);
@@ -256,9 +256,3 @@ TEST(AbsolutePose3DStampedConstraint, Serialization)
EXPECT_MATRIX_EQ(expected.mean(), actual.mean());
EXPECT_MATRIX_EQ(expected.sqrtInformation(), actual.sqrtInformation());
}
-
-int main(int argc, char **argv)
-{
- testing::InitGoogleTest(&argc, argv);
- return RUN_ALL_TESTS();
-}
diff --git a/fuse_constraints/test/test_marginal_constraint.cpp b/fuse_constraints/test/test_marginal_constraint.cpp
index 6f3a2057c..e83314c4b 100644
--- a/fuse_constraints/test/test_marginal_constraint.cpp
+++ b/fuse_constraints/test/test_marginal_constraint.cpp
@@ -275,9 +275,3 @@ TEST(MarginalConstraint, Serialization)
EXPECT_TRUE(static_cast(actual_derived));
}
}
-
-int main(int argc, char **argv)
-{
- testing::InitGoogleTest(&argc, argv);
- return RUN_ALL_TESTS();
-}
diff --git a/fuse_constraints/test/test_marginalize_variables.cpp b/fuse_constraints/test/test_marginalize_variables.cpp
index f7d021025..f41fd43fd 100644
--- a/fuse_constraints/test/test_marginalize_variables.cpp
+++ b/fuse_constraints/test/test_marginalize_variables.cpp
@@ -725,9 +725,3 @@ TEST(MarginalizeVariables, MarginalizeFixedVariables)
EXPECT_NEAR(expected_x3_cov[i], actual_x3_cov[i], 1.0e-3);
}
}
-
-int main(int argc, char **argv)
-{
- testing::InitGoogleTest(&argc, argv);
- return RUN_ALL_TESTS();
-}
diff --git a/fuse_constraints/test/test_normal_delta_pose_2d.cpp b/fuse_constraints/test/test_normal_delta_pose_2d.cpp
index eaf6193ff..4099ba6ce 100644
--- a/fuse_constraints/test/test_normal_delta_pose_2d.cpp
+++ b/fuse_constraints/test/test_normal_delta_pose_2d.cpp
@@ -138,9 +138,3 @@ TEST_F(NormalDeltaPose2DTestFixture, AnalyticAndAutoDiffCostFunctionsAreEqualFor
ExpectCostFunctionsAreEqual(autodiff_cost_function, cost_function);
}
}
-
-int main(int argc, char **argv)
-{
- testing::InitGoogleTest(&argc, argv);
- return RUN_ALL_TESTS();
-}
diff --git a/fuse_constraints/test/test_normal_prior_pose_2d.cpp b/fuse_constraints/test/test_normal_prior_pose_2d.cpp
index fd8fae281..1f94790d8 100644
--- a/fuse_constraints/test/test_normal_prior_pose_2d.cpp
+++ b/fuse_constraints/test/test_normal_prior_pose_2d.cpp
@@ -138,9 +138,3 @@ TEST_F(NormalPriorPose2DTestFixture, AnalyticAndAutoDiffCostFunctionsAreEqualFor
ExpectCostFunctionsAreEqual(autodiff_cost_function, cost_function);
}
}
-
-int main(int argc, char **argv)
-{
- testing::InitGoogleTest(&argc, argv);
- return RUN_ALL_TESTS();
-}
diff --git a/fuse_constraints/test/test_relative_constraint.cpp b/fuse_constraints/test/test_relative_constraint.cpp
index 9a70a2d86..b21bd9f71 100644
--- a/fuse_constraints/test/test_relative_constraint.cpp
+++ b/fuse_constraints/test/test_relative_constraint.cpp
@@ -522,9 +522,3 @@ TEST(RelativeConstraint, Serialization)
EXPECT_MATRIX_EQ(expected.delta(), actual.delta());
EXPECT_MATRIX_EQ(expected.sqrtInformation(), actual.sqrtInformation());
}
-
-int main(int argc, char **argv)
-{
- testing::InitGoogleTest(&argc, argv);
- return RUN_ALL_TESTS();
-}
diff --git a/fuse_constraints/test/test_relative_pose_2d_stamped_constraint.cpp b/fuse_constraints/test/test_relative_pose_2d_stamped_constraint.cpp
index 48f6e7e63..d7c8cc7df 100644
--- a/fuse_constraints/test/test_relative_pose_2d_stamped_constraint.cpp
+++ b/fuse_constraints/test/test_relative_pose_2d_stamped_constraint.cpp
@@ -467,9 +467,3 @@ TEST(RelativePose2DStampedConstraint, Serialization)
EXPECT_MATRIX_EQ(expected.delta(), actual.delta());
EXPECT_MATRIX_EQ(expected.sqrtInformation(), actual.sqrtInformation());
}
-
-int main(int argc, char **argv)
-{
- testing::InitGoogleTest(&argc, argv);
- return RUN_ALL_TESTS();
-}
diff --git a/fuse_constraints/test/test_relative_pose_3d_stamped_constraint.cpp b/fuse_constraints/test/test_relative_pose_3d_stamped_constraint.cpp
index 2f4492815..448d66cd2 100644
--- a/fuse_constraints/test/test_relative_pose_3d_stamped_constraint.cpp
+++ b/fuse_constraints/test/test_relative_pose_3d_stamped_constraint.cpp
@@ -67,12 +67,12 @@ TEST(RelativePose3DStampedConstraint, Constructor)
// Generated PD matrix using Octave: R = rand(6, 6); A = R * R' (use format long g to get the required precision)
fuse_core::Matrix6d cov;
- cov << 2.0847236144069, 1.10752598122138, 1.02943174290333, 1.96120532313878, 1.96735470687891, 1.5153042667951,
- 1.10752598122138, 1.39176289439125, 0.643422499737987, 1.35471905449013, 1.18353784377297, 1.28979625492894,
- 1.02943174290333, 0.643422499737987, 1.26701658550187, 1.23641771365403, 1.55169301761377, 1.34706781598061,
- 1.96120532313878, 1.35471905449013, 1.23641771365403, 2.39750866789926, 2.06887486311147, 2.04350823837035,
- 1.96735470687891, 1.18353784377297, 1.55169301761377, 2.06887486311147, 2.503913946461, 1.73844731158092,
- 1.5153042667951, 1.28979625492894, 1.34706781598061, 2.04350823837035, 1.73844731158092, 2.15326088526198;
+ cov << 2.0847236144069, 1.10752598122138, 1.02943174290333, 1.96120532313878, 1.96735470687891, 1.5153042667951, // NOLINT
+ 1.10752598122138, 1.39176289439125, 0.643422499737987, 1.35471905449013, 1.18353784377297, 1.28979625492894, // NOLINT
+ 1.02943174290333, 0.643422499737987, 1.26701658550187, 1.23641771365403, 1.55169301761377, 1.34706781598061, // NOLINT
+ 1.96120532313878, 1.35471905449013, 1.23641771365403, 2.39750866789926, 2.06887486311147, 2.04350823837035, // NOLINT
+ 1.96735470687891, 1.18353784377297, 1.55169301761377, 2.06887486311147, 2.503913946461, 1.73844731158092, // NOLINT
+ 1.5153042667951, 1.28979625492894, 1.34706781598061, 2.04350823837035, 1.73844731158092, 2.15326088526198; // NOLINT
EXPECT_NO_THROW(
RelativePose3DStampedConstraint constraint("test", position1, orientation1, position2, orientation2, delta, cov));
@@ -90,12 +90,12 @@ TEST(RelativePose3DStampedConstraint, Covariance)
// Generated PD matrix using Octiave: R = rand(6, 6); A = R * R' (use format long g to get the required precision)
fuse_core::Matrix6d cov;
- cov << 2.0847236144069, 1.10752598122138, 1.02943174290333, 1.96120532313878, 1.96735470687891, 1.5153042667951,
- 1.10752598122138, 1.39176289439125, 0.643422499737987, 1.35471905449013, 1.18353784377297, 1.28979625492894,
- 1.02943174290333, 0.643422499737987, 1.26701658550187, 1.23641771365403, 1.55169301761377, 1.34706781598061,
- 1.96120532313878, 1.35471905449013, 1.23641771365403, 2.39750866789926, 2.06887486311147, 2.04350823837035,
- 1.96735470687891, 1.18353784377297, 1.55169301761377, 2.06887486311147, 2.503913946461, 1.73844731158092,
- 1.5153042667951, 1.28979625492894, 1.34706781598061, 2.04350823837035, 1.73844731158092, 2.15326088526198;
+ cov << 2.0847236144069, 1.10752598122138, 1.02943174290333, 1.96120532313878, 1.96735470687891, 1.5153042667951, // NOLINT
+ 1.10752598122138, 1.39176289439125, 0.643422499737987, 1.35471905449013, 1.18353784377297, 1.28979625492894, // NOLINT
+ 1.02943174290333, 0.643422499737987, 1.26701658550187, 1.23641771365403, 1.55169301761377, 1.34706781598061, // NOLINT
+ 1.96120532313878, 1.35471905449013, 1.23641771365403, 2.39750866789926, 2.06887486311147, 2.04350823837035, // NOLINT
+ 1.96735470687891, 1.18353784377297, 1.55169301761377, 2.06887486311147, 2.503913946461, 1.73844731158092, // NOLINT
+ 1.5153042667951, 1.28979625492894, 1.34706781598061, 2.04350823837035, 1.73844731158092, 2.15326088526198; // NOLINT
RelativePose3DStampedConstraint constraint(
"test",
@@ -108,9 +108,9 @@ TEST(RelativePose3DStampedConstraint, Covariance)
// Define the expected matrices (used Octave to compute sqrt_info: 'chol(inv(A))')
fuse_core::Matrix6d expected_sqrt_info;
- expected_sqrt_info << 2.12658752275893, 1.20265444927878, 4.71225672571804, 1.43587520991272, -4.12764062992821, -3.19509486240291, // NOLINT
- 0.0, 2.41958656956248, 5.93151964116945, 3.72535320852517, -4.23326858606213, -5.27776664777548, // NOLINT
- 0.0, 0.0, 3.82674686590005, 2.80341171946161, -2.68168478581452, -2.8894384435255, // NOLINT
+ expected_sqrt_info << 2.12658752275893, 1.20265444927878, 4.71225672571804, 1.43587520991272, -4.12764062992821, -3.19509486240291, // NOLINT
+ 0.0, 2.41958656956248, 5.93151964116945, 3.72535320852517, -4.23326858606213, -5.27776664777548, // NOLINT
+ 0.0, 0.0, 3.82674686590005, 2.80341171946161, -2.68168478581452, -2.8894384435255, // NOLINT
0.0, 0.0, 0.0, 1.83006791372784, -0.696917410192509, -1.17412835464633, // NOLINT
0.0, 0.0, 0.0, 0.0, 0.953302832761324, -0.769654414882847, // NOLINT
0.0, 0.0, 0.0, 0.0, 0.0, 0.681477739760948; // NOLINT
@@ -318,12 +318,12 @@ TEST(RelativePose3DStampedConstraint, Serialization)
// Generated PD matrix using Octave: R = rand(6, 6); A = R * R' (use format long g to get the required precision)
fuse_core::Matrix6d cov;
- cov << 2.0847236144069, 1.10752598122138, 1.02943174290333, 1.96120532313878, 1.96735470687891, 1.5153042667951,
- 1.10752598122138, 1.39176289439125, 0.643422499737987, 1.35471905449013, 1.18353784377297, 1.28979625492894,
- 1.02943174290333, 0.643422499737987, 1.26701658550187, 1.23641771365403, 1.55169301761377, 1.34706781598061,
- 1.96120532313878, 1.35471905449013, 1.23641771365403, 2.39750866789926, 2.06887486311147, 2.04350823837035,
- 1.96735470687891, 1.18353784377297, 1.55169301761377, 2.06887486311147, 2.503913946461, 1.73844731158092,
- 1.5153042667951, 1.28979625492894, 1.34706781598061, 2.04350823837035, 1.73844731158092, 2.15326088526198;
+ cov << 2.0847236144069, 1.10752598122138, 1.02943174290333, 1.96120532313878, 1.96735470687891, 1.5153042667951, // NOLINT
+ 1.10752598122138, 1.39176289439125, 0.643422499737987, 1.35471905449013, 1.18353784377297, 1.28979625492894, // NOLINT
+ 1.02943174290333, 0.643422499737987, 1.26701658550187, 1.23641771365403, 1.55169301761377, 1.34706781598061, // NOLINT
+ 1.96120532313878, 1.35471905449013, 1.23641771365403, 2.39750866789926, 2.06887486311147, 2.04350823837035, // NOLINT
+ 1.96735470687891, 1.18353784377297, 1.55169301761377, 2.06887486311147, 2.503913946461, 1.73844731158092, // NOLINT
+ 1.5153042667951, 1.28979625492894, 1.34706781598061, 2.04350823837035, 1.73844731158092, 2.15326088526198; // NOLINT
RelativePose3DStampedConstraint expected("test", position1, orientation1, position2, orientation2, delta, cov);
@@ -347,9 +347,3 @@ TEST(RelativePose3DStampedConstraint, Serialization)
EXPECT_MATRIX_EQ(expected.delta(), actual.delta());
EXPECT_MATRIX_EQ(expected.sqrtInformation(), actual.sqrtInformation());
}
-
-int main(int argc, char **argv)
-{
- testing::InitGoogleTest(&argc, argv);
- return RUN_ALL_TESTS();
-}
diff --git a/fuse_constraints/test/test_uuid_ordering.cpp b/fuse_constraints/test/test_uuid_ordering.cpp
index 4e3077db8..650a0bf80 100644
--- a/fuse_constraints/test/test_uuid_ordering.cpp
+++ b/fuse_constraints/test/test_uuid_ordering.cpp
@@ -131,9 +131,3 @@ TEST(UuidOrdering, Exists)
EXPECT_TRUE(order.exists(uuid3));
EXPECT_FALSE(order.exists(uuid4));
}
-
-int main(int argc, char **argv)
-{
- testing::InitGoogleTest(&argc, argv);
- return RUN_ALL_TESTS();
-}
diff --git a/fuse_constraints/test/test_variable_constraints.cpp b/fuse_constraints/test/test_variable_constraints.cpp
index bcedc2121..cde42e6ef 100644
--- a/fuse_constraints/test/test_variable_constraints.cpp
+++ b/fuse_constraints/test/test_variable_constraints.cpp
@@ -131,9 +131,3 @@ TEST(VariableConstraints, InsertOrphanVariable)
EXPECT_TRUE(actual.empty());
}
-
-int main(int argc, char **argv)
-{
- testing::InitGoogleTest(&argc, argv);
- return RUN_ALL_TESTS();
-}