Removed erroneous text
parent
77c5c574d3
commit
20d72d0639
|
@ -44,7 +44,7 @@ TEST(Matrix, constructor_data )
|
||||||
|
|
||||||
EQUALITY(A,B);
|
EQUALITY(A,B);
|
||||||
}
|
}
|
||||||
//#ifndef __QNX__
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
TEST(Matrix, Matrix_ )
|
TEST(Matrix, Matrix_ )
|
||||||
{
|
{
|
||||||
|
|
|
@ -32,6 +32,7 @@ using namespace std;
|
||||||
using namespace gtsam;
|
using namespace gtsam;
|
||||||
using namespace gtsam::serializationTestHelpers;
|
using namespace gtsam::serializationTestHelpers;
|
||||||
|
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
// Create GUIDs for Noisemodels
|
// Create GUIDs for Noisemodels
|
||||||
BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Diagonal, "gtsam_noiseModel_Diagonal")
|
BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Diagonal, "gtsam_noiseModel_Diagonal")
|
||||||
|
|
|
@ -64,12 +64,10 @@ TEST(EssentialMatrixFactor, testData) {
|
||||||
EXPECT(assert_equal(Point2(0, 0), pA(0), 1e-8));
|
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, 0.1), pB(0), 1e-8));
|
||||||
EXPECT(assert_equal(Point2(0, -1), pA(4), 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));
|
EXPECT(assert_equal(Point2(-1, 0.2), pB(4), 1e-8));
|
||||||
|
|
||||||
// Check homogeneous version
|
// Check homogeneous version
|
||||||
EXPECT(assert_equal(Vector3(-1, 0.2, 1), vB(4), 1e-8));
|
EXPECT(assert_equal(Vector3(-1, 0.2, 1), vB(4), 1e-8));
|
||||||
#endif
|
|
||||||
|
|
||||||
// Check epipolar constraint
|
// Check epipolar constraint
|
||||||
for (size_t i = 0; i < 5; i++)
|
for (size_t i = 0; i < 5; i++)
|
||||||
|
|
|
@ -33,10 +33,8 @@ TEST(dataSet, sfmDataSerialization) {
|
||||||
SfmData mydata = SfmData::FromBalFile(filename);
|
SfmData mydata = SfmData::FromBalFile(filename);
|
||||||
|
|
||||||
// round-trip equality check on serialization and subsequent deserialization
|
// round-trip equality check on serialization and subsequent deserialization
|
||||||
#ifndef __QNX__ //Floating Point Issue
|
|
||||||
EXPECT(equalsObj(mydata));
|
EXPECT(equalsObj(mydata));
|
||||||
EXPECT(equalsXML(mydata));
|
EXPECT(equalsXML(mydata));
|
||||||
#endif
|
|
||||||
EXPECT(equalsBinary(mydata));
|
EXPECT(equalsBinary(mydata));
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -49,10 +47,8 @@ TEST(dataSet, sfmTrackSerialization) {
|
||||||
SfmTrack track = mydata.track(0);
|
SfmTrack track = mydata.track(0);
|
||||||
|
|
||||||
// round-trip equality check on serialization and subsequent deserialization
|
// round-trip equality check on serialization and subsequent deserialization
|
||||||
#ifndef __QNX__ //Floating Point Issue
|
|
||||||
EXPECT(equalsObj(track));
|
EXPECT(equalsObj(track));
|
||||||
EXPECT(equalsXML(track));
|
EXPECT(equalsXML(track));
|
||||||
#endif
|
|
||||||
EXPECT(equalsBinary(track));
|
EXPECT(equalsBinary(track));
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -140,11 +140,7 @@ TEST(schedulingExample, test) {
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
TEST(schedulingExample, smallFromFile) {
|
TEST(schedulingExample, smallFromFile) {
|
||||||
<<<<<<< HEAD
|
|
||||||
#ifndef __QNX__
|
|
||||||
=======
|
|
||||||
#if !defined(__QNX__)
|
#if !defined(__QNX__)
|
||||||
>>>>>>> 93f463ddbf8e990e6dccc622fcb8ecb67f21549a
|
|
||||||
string path(TOPSRCDIR "/gtsam_unstable/discrete/examples/");
|
string path(TOPSRCDIR "/gtsam_unstable/discrete/examples/");
|
||||||
#else
|
#else
|
||||||
string path(""); //Same Directory
|
string path(""); //Same Directory
|
||||||
|
|
|
@ -105,19 +105,11 @@ TEST ( Partition, edgePartitionByMetis2 )
|
||||||
graph.push_back(std::make_shared<GenericFactor3D>(2, 3, 2, NODE_POSE_3D, NODE_POSE_3D, 20));
|
graph.push_back(std::make_shared<GenericFactor3D>(2, 3, 2, NODE_POSE_3D, NODE_POSE_3D, 20));
|
||||||
graph.push_back(std::make_shared<GenericFactor3D>(3, 4, 3, NODE_POSE_3D, NODE_POSE_3D, 1));
|
graph.push_back(std::make_shared<GenericFactor3D>(3, 4, 3, NODE_POSE_3D, NODE_POSE_3D, 1));
|
||||||
//QNX Testing: fix tiebreaker to match
|
//QNX Testing: fix tiebreaker to match
|
||||||
<<<<<<< HEAD
|
|
||||||
#ifndef __QNX__
|
|
||||||
std::vector<size_t> keys{0, 1, 2, 3, 4};
|
|
||||||
#else
|
|
||||||
//Anything where 2 is before 0 will work.
|
|
||||||
std::vector<size_t> keys{2, 0, 1, 3, 4};
|
|
||||||
=======
|
|
||||||
#if !defined(__QNX__)
|
#if !defined(__QNX__)
|
||||||
std::vector<size_t> keys{0, 1, 2, 3, 4};
|
std::vector<size_t> keys{0, 1, 2, 3, 4};
|
||||||
#else
|
#else
|
||||||
//Anything where 2 is before 0 will work.
|
//Anything where 2 is before 0 will work.
|
||||||
std::vector<size_t> keys{2, 0, 3, 1, 4};
|
std::vector<size_t> keys{2, 0, 3, 1, 4};
|
||||||
>>>>>>> 93f463ddbf8e990e6dccc622fcb8ecb67f21549a
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
WorkSpace workspace(6);
|
WorkSpace workspace(6);
|
||||||
|
|
Loading…
Reference in New Issue