From 140577406afc3ba32d089cf2586e190d576444e9 Mon Sep 17 00:00:00 2001 From: cbeall3 Date: Thu, 12 Jun 2014 16:23:41 -0400 Subject: [PATCH] Use findExampleDataFile function to discover data file location --- examples/Pose2SLAMExample_g2o.cpp | 2 +- examples/Pose2SLAMExample_graph.cpp | 3 ++- examples/Pose2SLAMExample_lago.cpp | 2 +- examples/RangeISAMExample_plaza2.cpp | 11 +++++------ 4 files changed, 9 insertions(+), 9 deletions(-) diff --git a/examples/Pose2SLAMExample_g2o.cpp b/examples/Pose2SLAMExample_g2o.cpp index 3a4ee9cff..b46a53198 100644 --- a/examples/Pose2SLAMExample_g2o.cpp +++ b/examples/Pose2SLAMExample_g2o.cpp @@ -31,7 +31,7 @@ int main(const int argc, const char *argv[]) { // Read graph from file string g2oFile; if (argc < 2) - g2oFile = "../../examples/Data/noisyToyGraph.txt"; + g2oFile = findExampleDataFile("noisyToyGraph.txt"); else g2oFile = argv[1]; diff --git a/examples/Pose2SLAMExample_graph.cpp b/examples/Pose2SLAMExample_graph.cpp index 449144fef..86be74c75 100644 --- a/examples/Pose2SLAMExample_graph.cpp +++ b/examples/Pose2SLAMExample_graph.cpp @@ -32,7 +32,8 @@ int main (int argc, char** argv) { NonlinearFactorGraph::shared_ptr graph; Values::shared_ptr initial; SharedDiagonal model = noiseModel::Diagonal::Sigmas((Vector(3) << 0.05, 0.05, 5.0 * M_PI / 180.0)); - boost::tie(graph, initial) = load2D("../../examples/Data/w100.graph", model); + string graph_file = findExampleDataFile("w100.graph"); + boost::tie(graph, initial) = load2D(graph_file, model); initial->print("Initial estimate:\n"); // Add a Gaussian prior on first poses diff --git a/examples/Pose2SLAMExample_lago.cpp b/examples/Pose2SLAMExample_lago.cpp index 1f5d80d7b..bb434f3ce 100644 --- a/examples/Pose2SLAMExample_lago.cpp +++ b/examples/Pose2SLAMExample_lago.cpp @@ -32,7 +32,7 @@ int main(const int argc, const char *argv[]) { // Read graph from file string g2oFile; if (argc < 2) - g2oFile = "../../examples/Data/noisyToyGraph.txt"; + g2oFile = findExampleDataFile("noisyToyGraph.txt"); else g2oFile = argv[1]; diff --git a/examples/RangeISAMExample_plaza2.cpp b/examples/RangeISAMExample_plaza2.cpp index 29b02a271..252372f39 100644 --- a/examples/RangeISAMExample_plaza2.cpp +++ b/examples/RangeISAMExample_plaza2.cpp @@ -40,6 +40,7 @@ #include #include #include +#include // Standard headers, added last, so we know headers above work on their own #include @@ -59,9 +60,8 @@ namespace NM = gtsam::noiseModel; typedef pair TimedOdometry; list readOdometry() { list odometryList; - ifstream is("../../examples/Data/Plaza2_DR.txt"); - if (!is) - throw runtime_error("../../examples/Data/Plaza2_DR.txt file not found"); + string data_file = findExampleDataFile("Plaza2_DR.txt"); + ifstream is(data_file.c_str()); while (is) { double t, distance_traveled, delta_heading; @@ -78,9 +78,8 @@ list readOdometry() { typedef boost::tuple RangeTriple; vector readTriples() { vector triples; - ifstream is("../../examples/Data/Plaza2_TD.txt"); - if (!is) - throw runtime_error("../../examples/Data/Plaza2_TD.txt file not found"); + string data_file = findExampleDataFile("Plaza2_TD.txt"); + ifstream is(data_file.c_str()); while (is) { double t, sender, receiver, range;