From c979a6f1364aeeac43c559bed956f6bcfdbb7199 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Wed, 16 Feb 2022 13:07:26 -0500 Subject: [PATCH] use anonymous namespace --- gtsam/geometry/tests/testPose2.cpp | 10 ++-------- gtsam/geometry/tests/testQuaternion.cpp | 10 ++-------- gtsam/geometry/tests/testRot2.cpp | 7 ++----- gtsam/geometry/tests/testRot3.cpp | 10 ++-------- gtsam/geometry/tests/testSO3.cpp | 16 ++-------------- gtsam/geometry/tests/testSO4.cpp | 21 ++------------------- 6 files changed, 12 insertions(+), 62 deletions(-) diff --git a/gtsam/geometry/tests/testPose2.cpp b/gtsam/geometry/tests/testPose2.cpp index c199a7af0..0df858aa8 100644 --- a/gtsam/geometry/tests/testPose2.cpp +++ b/gtsam/geometry/tests/testPose2.cpp @@ -796,16 +796,14 @@ TEST(Pose2, align_4) { } //****************************************************************************** -namespace pose2_example { +namespace { Pose2 id; Pose2 T1(M_PI / 4.0, Point2(sqrt(0.5), sqrt(0.5))); Pose2 T2(M_PI / 2.0, Point2(0.0, 2.0)); -} // namespace pose2_example +} // namespace //****************************************************************************** TEST(Pose2, Invariants) { - using namespace pose2_example; - EXPECT(check_group_invariants(id, id)); EXPECT(check_group_invariants(id, T1)); EXPECT(check_group_invariants(T2, id)); @@ -819,8 +817,6 @@ TEST(Pose2, Invariants) { //****************************************************************************** TEST(Pose2, LieGroupDerivatives) { - using namespace pose2_example; - CHECK_LIE_GROUP_DERIVATIVES(id, id); CHECK_LIE_GROUP_DERIVATIVES(id, T2); CHECK_LIE_GROUP_DERIVATIVES(T2, id); @@ -829,8 +825,6 @@ TEST(Pose2, LieGroupDerivatives) { //****************************************************************************** TEST(Pose2, ChartDerivatives) { - using namespace pose2_example; - CHECK_CHART_DERIVATIVES(id, id); CHECK_CHART_DERIVATIVES(id, T2); CHECK_CHART_DERIVATIVES(T2, id); diff --git a/gtsam/geometry/tests/testQuaternion.cpp b/gtsam/geometry/tests/testQuaternion.cpp index 88548d15e..281c71f7c 100644 --- a/gtsam/geometry/tests/testQuaternion.cpp +++ b/gtsam/geometry/tests/testQuaternion.cpp @@ -102,17 +102,15 @@ TEST(Quaternion , Inverse) { } //****************************************************************************** -namespace q_example { +namespace { Vector3 Q_z_axis(0, 0, 1); Q id(Eigen::AngleAxisd(0, Q_z_axis)); Q R1(Eigen::AngleAxisd(1, Q_z_axis)); Q R2(Eigen::AngleAxisd(2, Vector3(0, 1, 0))); -} // namespace q_example +} // namespace //****************************************************************************** TEST(Quaternion, Invariants) { - using namespace q_example; - EXPECT(check_group_invariants(id, id)); EXPECT(check_group_invariants(id, R1)); EXPECT(check_group_invariants(R2, id)); @@ -126,8 +124,6 @@ TEST(Quaternion, Invariants) { //****************************************************************************** TEST(Quaternion, LieGroupDerivatives) { - using namespace q_example; - CHECK_LIE_GROUP_DERIVATIVES(id, id); CHECK_LIE_GROUP_DERIVATIVES(id, R2); CHECK_LIE_GROUP_DERIVATIVES(R2, id); @@ -136,8 +132,6 @@ TEST(Quaternion, LieGroupDerivatives) { //****************************************************************************** TEST(Quaternion, ChartDerivatives) { - using namespace q_example; - CHECK_CHART_DERIVATIVES(id, id); CHECK_CHART_DERIVATIVES(id, R2); CHECK_CHART_DERIVATIVES(R2, id); diff --git a/gtsam/geometry/tests/testRot2.cpp b/gtsam/geometry/tests/testRot2.cpp index f08f3e2a5..5a087edcd 100644 --- a/gtsam/geometry/tests/testRot2.cpp +++ b/gtsam/geometry/tests/testRot2.cpp @@ -156,15 +156,14 @@ TEST( Rot2, relativeBearing ) } //****************************************************************************** -namespace rot2_example { +namespace { Rot2 id; Rot2 T1(0.1); Rot2 T2(0.2); -} // namespace rot2_example +} // namespace //****************************************************************************** TEST(Rot2, Invariants) { - using namespace rot2_example; EXPECT(check_group_invariants(id, id)); EXPECT(check_group_invariants(id, T1)); EXPECT(check_group_invariants(T2, id)); @@ -178,7 +177,6 @@ TEST(Rot2, Invariants) { //****************************************************************************** TEST(Rot2, LieGroupDerivatives) { - using namespace rot2_example; CHECK_LIE_GROUP_DERIVATIVES(id, id); CHECK_LIE_GROUP_DERIVATIVES(id, T2); CHECK_LIE_GROUP_DERIVATIVES(T2, id); @@ -187,7 +185,6 @@ TEST(Rot2, LieGroupDerivatives) { //****************************************************************************** TEST(Rot2, ChartDerivatives) { - using namespace rot2_example; CHECK_CHART_DERIVATIVES(id, id); CHECK_CHART_DERIVATIVES(id, T2); CHECK_CHART_DERIVATIVES(T2, id); diff --git a/gtsam/geometry/tests/testRot3.cpp b/gtsam/geometry/tests/testRot3.cpp index 537ec8f4f..1df342d57 100644 --- a/gtsam/geometry/tests/testRot3.cpp +++ b/gtsam/geometry/tests/testRot3.cpp @@ -640,16 +640,14 @@ TEST( Rot3, slerp) } //****************************************************************************** -namespace rot3_example { +namespace { Rot3 id; Rot3 T1(Rot3::AxisAngle(Vector3(0, 0, 1), 1)); Rot3 T2(Rot3::AxisAngle(Vector3(0, 1, 0), 2)); -} // namespace rot3_example +} // namespace //****************************************************************************** TEST(Rot3, Invariants) { - using namespace rot3_example; - EXPECT(check_group_invariants(id, id)); EXPECT(check_group_invariants(id, T1)); EXPECT(check_group_invariants(T2, id)); @@ -665,8 +663,6 @@ TEST(Rot3, Invariants) { //****************************************************************************** TEST(Rot3, LieGroupDerivatives) { - using namespace rot3_example; - CHECK_LIE_GROUP_DERIVATIVES(id, id); CHECK_LIE_GROUP_DERIVATIVES(id, T2); CHECK_LIE_GROUP_DERIVATIVES(T2, id); @@ -676,8 +672,6 @@ TEST(Rot3, LieGroupDerivatives) { //****************************************************************************** TEST(Rot3, ChartDerivatives) { - using namespace rot3_example; - if (ROT3_DEFAULT_COORDINATES_MODE == Rot3::EXPMAP) { CHECK_CHART_DERIVATIVES(id, id); CHECK_CHART_DERIVATIVES(id, T2); diff --git a/gtsam/geometry/tests/testSO3.cpp b/gtsam/geometry/tests/testSO3.cpp index 64d3e681d..96c1cce32 100644 --- a/gtsam/geometry/tests/testSO3.cpp +++ b/gtsam/geometry/tests/testSO3.cpp @@ -67,16 +67,15 @@ TEST(SO3, ClosestTo) { } //****************************************************************************** -namespace so3_example { +namespace { SO3 id; Vector3 z_axis(0, 0, 1), v2(1, 2, 0), v3(1, 2, 3); SO3 R1(Eigen::AngleAxisd(0.1, z_axis)); SO3 R2(Eigen::AngleAxisd(0.2, z_axis)); -} // namespace so3_example +} // namespace /* ************************************************************************* */ TEST(SO3, ChordalMean) { - using namespace so3_example; std::vector rotations = {R1, R1.inverse()}; EXPECT(assert_equal(SO3(), SO3::ChordalMean(rotations))); } @@ -84,7 +83,6 @@ TEST(SO3, ChordalMean) { //****************************************************************************** // Check that Hat specialization is equal to dynamic version TEST(SO3, Hat) { - using namespace so3_example; EXPECT(assert_equal(SO3::Hat(z_axis), SOn::Hat(z_axis))); EXPECT(assert_equal(SO3::Hat(v2), SOn::Hat(v2))); EXPECT(assert_equal(SO3::Hat(v3), SOn::Hat(v3))); @@ -93,7 +91,6 @@ TEST(SO3, Hat) { //****************************************************************************** // Check that Hat specialization is equal to dynamic version TEST(SO3, Vee) { - using namespace so3_example; auto X1 = SOn::Hat(z_axis), X2 = SOn::Hat(v2), X3 = SOn::Hat(v3); EXPECT(assert_equal(SO3::Vee(X1), SOn::Vee(X1))); EXPECT(assert_equal(SO3::Vee(X2), SOn::Vee(X2))); @@ -102,7 +99,6 @@ TEST(SO3, Vee) { //****************************************************************************** TEST(SO3, Local) { - using namespace so3_example; Vector3 expected(0, 0, 0.1); Vector3 actual = traits::Local(R1, R2); EXPECT(assert_equal((Vector)expected, actual)); @@ -110,7 +106,6 @@ TEST(SO3, Local) { //****************************************************************************** TEST(SO3, Retract) { - using namespace so3_example; Vector3 v(0, 0, 0.1); SO3 actual = traits::Retract(R1, v); EXPECT(assert_equal(R2, actual)); @@ -118,7 +113,6 @@ TEST(SO3, Retract) { //****************************************************************************** TEST(SO3, Logmap) { - using namespace so3_example; Vector3 expected(0, 0, 0.1); Vector3 actual = SO3::Logmap(R1.between(R2)); EXPECT(assert_equal((Vector)expected, actual)); @@ -126,7 +120,6 @@ TEST(SO3, Logmap) { //****************************************************************************** TEST(SO3, Expmap) { - using namespace so3_example; Vector3 v(0, 0, 0.1); SO3 actual = R1 * SO3::Expmap(v); EXPECT(assert_equal(R2, actual)); @@ -134,8 +127,6 @@ TEST(SO3, Expmap) { //****************************************************************************** TEST(SO3, Invariants) { - using namespace so3_example; - EXPECT(check_group_invariants(id, id)); EXPECT(check_group_invariants(id, R1)); EXPECT(check_group_invariants(R2, id)); @@ -149,7 +140,6 @@ TEST(SO3, Invariants) { //****************************************************************************** TEST(SO3, LieGroupDerivatives) { - using namespace so3_example; CHECK_LIE_GROUP_DERIVATIVES(id, id); CHECK_LIE_GROUP_DERIVATIVES(id, R2); CHECK_LIE_GROUP_DERIVATIVES(R2, id); @@ -158,7 +148,6 @@ TEST(SO3, LieGroupDerivatives) { //****************************************************************************** TEST(SO3, ChartDerivatives) { - using namespace so3_example; CHECK_CHART_DERIVATIVES(id, id); CHECK_CHART_DERIVATIVES(id, R2); CHECK_CHART_DERIVATIVES(R2, id); @@ -363,7 +352,6 @@ TEST(SO3, ApplyInvDexp) { //****************************************************************************** TEST(SO3, vec) { - using namespace so3_example; const Vector9 expected = Eigen::Map(R2.matrix().data()); Matrix actualH; const Vector9 actual = R2.vec(actualH); diff --git a/gtsam/geometry/tests/testSO4.cpp b/gtsam/geometry/tests/testSO4.cpp index 7379049c3..fa550723a 100644 --- a/gtsam/geometry/tests/testSO4.cpp +++ b/gtsam/geometry/tests/testSO4.cpp @@ -55,7 +55,7 @@ TEST(SO4, Random) { } //****************************************************************************** -namespace so4_example { +namespace { SO4 id; Vector6 v1 = (Vector(6) << 0, 0, 0, 0.1, 0, 0).finished(); SO4 Q1 = SO4::Expmap(v1); @@ -63,12 +63,10 @@ Vector6 v2 = (Vector(6) << 0.00, 0.00, 0.00, 0.01, 0.02, 0.03).finished(); SO4 Q2 = SO4::Expmap(v2); Vector6 v3 = (Vector(6) << 1, 2, 3, 4, 5, 6).finished(); SO4 Q3 = SO4::Expmap(v3); -} // namespace so4_example +} // namespace //****************************************************************************** TEST(SO4, Expmap) { - using namespace so4_example; - // If we do exponential map in SO(3) subgroup, topleft should be equal to R1. auto R1 = SO3::Expmap(v1.tail<3>()).matrix(); EXPECT((Q1.matrix().topLeftCorner<3, 3>().isApprox(R1))); @@ -91,7 +89,6 @@ TEST(SO4, Expmap) { //****************************************************************************** // Check that Hat specialization is equal to dynamic version TEST(SO4, Hat) { - using namespace so4_example; EXPECT(assert_equal(SO4::Hat(v1), SOn::Hat(v1))); EXPECT(assert_equal(SO4::Hat(v2), SOn::Hat(v2))); EXPECT(assert_equal(SO4::Hat(v3), SOn::Hat(v3))); @@ -100,7 +97,6 @@ TEST(SO4, Hat) { //****************************************************************************** // Check that Hat specialization is equal to dynamic version TEST(SO4, Vee) { - using namespace so4_example; auto X1 = SOn::Hat(v1), X2 = SOn::Hat(v2), X3 = SOn::Hat(v3); EXPECT(assert_equal(SO4::Vee(X1), SOn::Vee(X1))); EXPECT(assert_equal(SO4::Vee(X2), SOn::Vee(X2))); @@ -109,8 +105,6 @@ TEST(SO4, Vee) { //****************************************************************************** TEST(SO4, Retract) { - using namespace so4_example; - // Check that Cayley yields the same as Expmap for small values EXPECT(assert_equal(id.retract(v1 / 100), SO4::Expmap(v1 / 100))); EXPECT(assert_equal(id.retract(v2 / 100), SO4::Expmap(v2 / 100))); @@ -127,7 +121,6 @@ TEST(SO4, Retract) { //****************************************************************************** // Check that Cayley is identical to dynamic version TEST(SO4, Local) { - using namespace so4_example; EXPECT( assert_equal(id.localCoordinates(Q1), SOn(4).localCoordinates(SOn(Q1)))); EXPECT( @@ -140,8 +133,6 @@ TEST(SO4, Local) { //****************************************************************************** TEST(SO4, Invariants) { - using namespace so4_example; - EXPECT(check_group_invariants(id, id)); EXPECT(check_group_invariants(id, Q1)); EXPECT(check_group_invariants(Q2, id)); @@ -157,8 +148,6 @@ TEST(SO4, Invariants) { //****************************************************************************** TEST(SO4, compose) { - using namespace so4_example; - SO4 expected = Q1 * Q2; Matrix actualH1, actualH2; SO4 actual = Q1.compose(Q2, actualH1, actualH2); @@ -175,8 +164,6 @@ TEST(SO4, compose) { //****************************************************************************** TEST(SO4, vec) { - using namespace so4_example; - using Vector16 = SO4::VectorN2; const Vector16 expected = Eigen::Map(Q2.matrix().data()); Matrix actualH; @@ -189,8 +176,6 @@ TEST(SO4, vec) { //****************************************************************************** TEST(SO4, topLeft) { - using namespace so4_example; - const Matrix3 expected = Q3.matrix().topLeftCorner<3, 3>(); Matrix actualH; const Matrix3 actual = topLeft(Q3, actualH); @@ -204,8 +189,6 @@ TEST(SO4, topLeft) { //****************************************************************************** TEST(SO4, stiefel) { - using namespace so4_example; - const Matrix43 expected = Q3.matrix().leftCols<3>(); Matrix actualH; const Matrix43 actual = stiefel(Q3, actualH);