From 330fbd730eacad915a43384edce3a35d86cfd35b Mon Sep 17 00:00:00 2001 From: Luca Date: Fri, 22 Aug 2014 10:40:16 -0400 Subject: [PATCH] fix failing unit test (mac) --- examples/Data/pose3example-offdiagonal.txt | 2 +- gtsam/slam/dataset.cpp | 10 +++++----- 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/examples/Data/pose3example-offdiagonal.txt b/examples/Data/pose3example-offdiagonal.txt index c3eb883a4..08ca2e1d1 100644 --- a/examples/Data/pose3example-offdiagonal.txt +++ b/examples/Data/pose3example-offdiagonal.txt @@ -1,3 +1,3 @@ VERTEX_SE3:QUAT 0 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 1.000000 VERTEX_SE3:QUAT 1 1.001367 0.015390 0.004948 0.190253 0.283162 -0.392318 0.854230 -EDGE_SE3:QUAT 0 1 1.001367 0.015390 0.004948 0.190253 0.283162 -0.392318 0.854230 10000.000000 1.000000 1.000000 1.000000 1.000000 1.000000 10000.000000 2.000000 2.000000 2.000000 2.000000 10000.000000 3.000000 3.000000 3.000000 10000.000000 4.000000 4.000000 10000.000000 5.000000 10000.000000 \ No newline at end of file +EDGE_SE3:QUAT 0 1 1.001367 0.015390 0.004948 0.190253 0.283162 -0.392318 0.854230 10000.000000 1.000000 1.000000 1.000000 1.000000 1.000000 10000.000000 2.000000 2.000000 2.000000 2.000000 10000.000000 3.000000 3.000000 3.000000 10000.000000 4.000000 4.000000 10000.000000 5.000000 10000.0000 \ No newline at end of file diff --git a/gtsam/slam/dataset.cpp b/gtsam/slam/dataset.cpp index 7d06ad0cf..65519cbf1 100644 --- a/gtsam/slam/dataset.cpp +++ b/gtsam/slam/dataset.cpp @@ -177,7 +177,7 @@ GraphAndValues load2D(const string& filename, SharedNoiseModel model, int maxID, string tag; // load the poses - while (is) { + while (!is.eof()) { if (!(is >> tag)) break; @@ -213,7 +213,7 @@ GraphAndValues load2D(const string& filename, SharedNoiseModel model, int maxID, // Parse the pose constraints int id1, id2; bool haveLandmark = false; - while (is) { + while (!is.eof()) { if (!(is >> tag)) break; @@ -455,12 +455,12 @@ GraphAndValues load3D(const string& filename) { ifstream is(filename.c_str()); if (!is) - throw invalid_argument("load2D: can not find file " + filename); + throw invalid_argument("load3D: can not find file " + filename); Values::shared_ptr initial(new Values); NonlinearFactorGraph::shared_ptr graph(new NonlinearFactorGraph); - while (is) { + while (!is.eof()) { char buf[LINESIZE]; is.getline(buf, LINESIZE); istringstream ls(buf); @@ -487,7 +487,7 @@ GraphAndValues load3D(const string& filename) { is.clear(); /* clears the end-of-file and error flags */ is.seekg(0, ios::beg); - while (is) { + while (!is.eof()) { char buf[LINESIZE]; is.getline(buf, LINESIZE); istringstream ls(buf);