From 30644e9590be33c75c23a11c74d0935920343a0b Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Sun, 2 Jun 2019 17:55:47 -0400 Subject: [PATCH] Fix file handling (removed absolute paths) --- .../examples/SmartRangeExample_plaza1.cpp | 30 ++++++++----------- .../examples/SmartRangeExample_plaza2.cpp | 23 +++++++------- 2 files changed, 24 insertions(+), 29 deletions(-) diff --git a/gtsam_unstable/examples/SmartRangeExample_plaza1.cpp b/gtsam_unstable/examples/SmartRangeExample_plaza1.cpp index 0ee601d26..17f21cf9a 100644 --- a/gtsam_unstable/examples/SmartRangeExample_plaza1.cpp +++ b/gtsam_unstable/examples/SmartRangeExample_plaza1.cpp @@ -10,7 +10,7 @@ * -------------------------------------------------------------------------- */ /** - * @file SmartRangeExample_plaza2.cpp + * @file SmartRangeExample_plaza1.cpp * @brief A 2D Range SLAM example * @date June 20, 2013 * @author FRank Dellaert @@ -42,6 +42,9 @@ #include #include +// To find data files, we can use `findExampleDataFile`, declared here: +#include + // Standard headers, added last, so we know headers above work on their own #include #include @@ -59,10 +62,9 @@ namespace NM = gtsam::noiseModel; typedef pair TimedOdometry; list readOdometry() { list odometryList; - ifstream is("/Users/dellaert/borg/gtsam/examples/Data/Plaza1_DR.txt"); - if (!is) - throw runtime_error( - "/Users/dellaert/borg/gtsam/examples/Data/Plaza1_DR.txt file not found"); + string drFile = findExampleDataFile("Plaza1_DR.txt"); + ifstream is(drFile); + if (!is) throw runtime_error("Plaza1_DR.txt file not found"); while (is) { double t, distance_traveled, delta_heading; @@ -79,10 +81,9 @@ list readOdometry() { typedef boost::tuple RangeTriple; vector readTriples() { vector triples; - ifstream is("/Users/dellaert/borg/gtsam/examples/Data/Plaza1_TD.txt"); - if (!is) - throw runtime_error( - "/Users/dellaert/borg/gtsam/examples/Data/Plaza1_TD.txt file not found"); + string tdFile = findExampleDataFile("Plaza1_TD.txt"); + ifstream is(tdFile); + if (!is) throw runtime_error("Plaza1_TD.txt file not found"); while (is) { double t, sender, receiver, range; @@ -98,8 +99,6 @@ int main(int argc, char** argv) { // load Plaza1 data list odometry = readOdometry(); -// size_t M = odometry.size(); - vector triples = readTriples(); size_t K = triples.size(); @@ -130,10 +129,8 @@ int main(int argc, char** argv) { NonlinearFactorGraph newFactors; newFactors.push_back(PriorFactor(0, pose0, priorNoise)); - ofstream os2( - "/Users/dellaert/borg/gtsam/gtsam_unstable/examples/rangeResultLM.txt"); - ofstream os3( - "/Users/dellaert/borg/gtsam/gtsam_unstable/examples/rangeResultSR.txt"); + ofstream os2("rangeResultLM.txt"); + ofstream os3("rangeResultSR.txt"); // initialize points (Gaussian) Values initial; @@ -254,8 +251,7 @@ int main(int argc, char** argv) { // Write result to file Values result = isam.calculateEstimate(); - ofstream os( - "/Users/dellaert/borg/gtsam/gtsam_unstable/examples/rangeResult.txt"); + ofstream os("rangeResult.txt"); for(const Values::ConstFiltered::KeyValuePair& it: result.filter()) os << it.key << "\t" << it.value.x() << "\t" << it.value.y() << "\t" << it.value.theta() << endl; diff --git a/gtsam_unstable/examples/SmartRangeExample_plaza2.cpp b/gtsam_unstable/examples/SmartRangeExample_plaza2.cpp index 5f33a215b..a83eb06ac 100644 --- a/gtsam_unstable/examples/SmartRangeExample_plaza2.cpp +++ b/gtsam_unstable/examples/SmartRangeExample_plaza2.cpp @@ -41,6 +41,9 @@ #include #include +// To find data files, we can use `findExampleDataFile`, declared here: +#include + // Standard headers, added last, so we know headers above work on their own #include #include @@ -58,10 +61,9 @@ namespace NM = gtsam::noiseModel; typedef pair TimedOdometry; list readOdometry() { list odometryList; - ifstream is("/Users/dellaert/borg/gtsam/examples/Data/Plaza1_DR.txt"); - if (!is) - throw runtime_error( - "/Users/dellaert/borg/gtsam/examples/Data/Plaza1_DR.txt file not found"); + string drFile = findExampleDataFile("Plaza2_DR.txt"); + ifstream is(drFile); + if (!is) throw runtime_error("Plaza2_DR.txt file not found"); while (is) { double t, distance_traveled, delta_heading; @@ -78,10 +80,9 @@ list readOdometry() { typedef boost::tuple RangeTriple; vector readTriples() { vector triples; - ifstream is("/Users/dellaert/borg/gtsam/examples/Data/Plaza1_TD.txt"); - if (!is) - throw runtime_error( - "/Users/dellaert/borg/gtsam/examples/Data/Plaza1_TD.txt file not found"); + string tdFile = findExampleDataFile("Plaza2_TD.txt"); + ifstream is(tdFile); + if (!is) throw runtime_error("Plaza2_TD.txt file not found"); while (is) { double t, sender, receiver, range; @@ -201,13 +202,11 @@ int main(int argc, char** argv) { // Write result to file Values result = isam.calculateEstimate(); - ofstream os2( - "/Users/dellaert/borg/gtsam/gtsam_unstable/examples/rangeResultLM.txt"); + ofstream os2("rangeResultLM.txt"); for(const Values::ConstFiltered::KeyValuePair& it: result.filter()) os2 << it.key << "\t" << it.value.x() << "\t" << it.value.y() << "\t1" << endl; - ofstream os( - "/Users/dellaert/borg/gtsam/gtsam_unstable/examples/rangeResult.txt"); + ofstream os("rangeResult.txt"); for(const Values::ConstFiltered::KeyValuePair& it: result.filter()) os << it.key << "\t" << it.value.x() << "\t" << it.value.y() << "\t" << it.value.theta() << endl;