Use findExampleDataFile function to discover data file location

release/4.3a0
cbeall3 2014-06-12 16:23:41 -04:00
parent 12f19e8a7c
commit 140577406a
4 changed files with 9 additions and 9 deletions

View File

@ -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];

View File

@ -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

View File

@ -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];

View File

@ -40,6 +40,7 @@
#include <gtsam/slam/PriorFactor.h>
#include <gtsam/slam/BetweenFactor.h>
#include <gtsam/slam/RangeFactor.h>
#include <gtsam/slam/dataset.h>
// Standard headers, added last, so we know headers above work on their own
#include <boost/foreach.hpp>
@ -59,9 +60,8 @@ namespace NM = gtsam::noiseModel;
typedef pair<double, Pose2> TimedOdometry;
list<TimedOdometry> readOdometry() {
list<TimedOdometry> 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<TimedOdometry> readOdometry() {
typedef boost::tuple<double, size_t, double> RangeTriple;
vector<RangeTriple> readTriples() {
vector<RangeTriple> 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;