diff --git a/gtsam/base/tests/testMatrix.cpp b/gtsam/base/tests/testMatrix.cpp index 02984b8c1..4c8808722 100644 --- a/gtsam/base/tests/testMatrix.cpp +++ b/gtsam/base/tests/testMatrix.cpp @@ -44,7 +44,7 @@ TEST(Matrix, constructor_data ) EQUALITY(A,B); } -//#ifndef __QNX__ + /* ************************************************************************* */ TEST(Matrix, Matrix_ ) { diff --git a/gtsam/nonlinear/tests/testSerializationNonlinear.cpp b/gtsam/nonlinear/tests/testSerializationNonlinear.cpp index a96ede430..566aee672 100644 --- a/gtsam/nonlinear/tests/testSerializationNonlinear.cpp +++ b/gtsam/nonlinear/tests/testSerializationNonlinear.cpp @@ -32,6 +32,7 @@ using namespace std; using namespace gtsam; using namespace gtsam::serializationTestHelpers; + /* ************************************************************************* */ // Create GUIDs for Noisemodels BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Diagonal, "gtsam_noiseModel_Diagonal") diff --git a/gtsam/slam/tests/testEssentialMatrixFactor.cpp b/gtsam/slam/tests/testEssentialMatrixFactor.cpp index 15de253cd..11558e38e 100644 --- a/gtsam/slam/tests/testEssentialMatrixFactor.cpp +++ b/gtsam/slam/tests/testEssentialMatrixFactor.cpp @@ -64,12 +64,10 @@ TEST(EssentialMatrixFactor, testData) { EXPECT(assert_equal(Point2(0, 0), pA(0), 1e-8)); EXPECT(assert_equal(Point2(0, 0.1), pB(0), 1e-8)); EXPECT(assert_equal(Point2(0, -1), pA(4), 1e-8)); - #ifndef __QNX__ //Floating Point Error EXPECT(assert_equal(Point2(-1, 0.2), pB(4), 1e-8)); // Check homogeneous version EXPECT(assert_equal(Vector3(-1, 0.2, 1), vB(4), 1e-8)); - #endif // Check epipolar constraint for (size_t i = 0; i < 5; i++) diff --git a/gtsam/slam/tests/testSerializationDataset.cpp b/gtsam/slam/tests/testSerializationDataset.cpp index 9c8142c31..dcac3d47e 100644 --- a/gtsam/slam/tests/testSerializationDataset.cpp +++ b/gtsam/slam/tests/testSerializationDataset.cpp @@ -33,10 +33,8 @@ TEST(dataSet, sfmDataSerialization) { SfmData mydata = SfmData::FromBalFile(filename); // round-trip equality check on serialization and subsequent deserialization - #ifndef __QNX__ //Floating Point Issue EXPECT(equalsObj(mydata)); EXPECT(equalsXML(mydata)); - #endif EXPECT(equalsBinary(mydata)); } @@ -49,10 +47,8 @@ TEST(dataSet, sfmTrackSerialization) { SfmTrack track = mydata.track(0); // round-trip equality check on serialization and subsequent deserialization - #ifndef __QNX__ //Floating Point Issue EXPECT(equalsObj(track)); EXPECT(equalsXML(track)); - #endif EXPECT(equalsBinary(track)); } diff --git a/gtsam_unstable/discrete/tests/testScheduler.cpp b/gtsam_unstable/discrete/tests/testScheduler.cpp index 731b8b3b3..ab3a0df05 100644 --- a/gtsam_unstable/discrete/tests/testScheduler.cpp +++ b/gtsam_unstable/discrete/tests/testScheduler.cpp @@ -140,11 +140,7 @@ TEST(schedulingExample, test) { /* ************************************************************************* */ TEST(schedulingExample, smallFromFile) { -<<<<<<< HEAD - #ifndef __QNX__ -======= #if !defined(__QNX__) ->>>>>>> 93f463ddbf8e990e6dccc622fcb8ecb67f21549a string path(TOPSRCDIR "/gtsam_unstable/discrete/examples/"); #else string path(""); //Same Directory diff --git a/gtsam_unstable/partition/tests/testFindSeparator.cpp b/gtsam_unstable/partition/tests/testFindSeparator.cpp index 7575e6154..f425be8c7 100644 --- a/gtsam_unstable/partition/tests/testFindSeparator.cpp +++ b/gtsam_unstable/partition/tests/testFindSeparator.cpp @@ -105,19 +105,11 @@ TEST ( Partition, edgePartitionByMetis2 ) graph.push_back(std::make_shared(2, 3, 2, NODE_POSE_3D, NODE_POSE_3D, 20)); graph.push_back(std::make_shared(3, 4, 3, NODE_POSE_3D, NODE_POSE_3D, 1)); //QNX Testing: fix tiebreaker to match -<<<<<<< HEAD - #ifndef __QNX__ - std::vector keys{0, 1, 2, 3, 4}; - #else - //Anything where 2 is before 0 will work. - std::vector keys{2, 0, 1, 3, 4}; -======= #if !defined(__QNX__) std::vector keys{0, 1, 2, 3, 4}; #else //Anything where 2 is before 0 will work. std::vector keys{2, 0, 3, 1, 4}; ->>>>>>> 93f463ddbf8e990e6dccc622fcb8ecb67f21549a #endif WorkSpace workspace(6); diff --git a/tests/testSerializationSlam.cpp b/tests/testSerializationSlam.cpp index ed4c9e246..c4170b108 100644 --- a/tests/testSerializationSlam.cpp +++ b/tests/testSerializationSlam.cpp @@ -634,7 +634,7 @@ TEST(SubgraphSolver, Solves) { KeyInfo keyInfo(Ab); std::map lambda; system.build(Ab, keyInfo, lambda); - + // Create a perturbed (non-zero) RHS const auto xbar = system.Rc1().optimize(); // merely for use in zero below auto values_y = VectorValues::Zero(xbar);