Removed dataset function from gtsam (moved to CitySLAM, see previous commit)

release/4.3a0
Richard Roberts 2012-07-28 16:01:49 +00:00
parent d95ca7857b
commit 32f9ea526d
2 changed files with 0 additions and 57 deletions

View File

@ -31,54 +31,6 @@ using namespace std;
namespace gtsam {
/* ************************************************************************* */
pair<string, boost::optional<SharedDiagonal> > dataset(const string& dataset,
const string& user_path) {
string path = user_path, set = dataset;
boost::optional<SharedDiagonal> null_model;
boost::optional<SharedDiagonal> identity(noiseModel::Unit::Create(3));
boost::optional<SharedDiagonal> small(
noiseModel::Diagonal::Variances(
gtsam::Vector_(3, 0.0001, 0.0001, 0.0003)));
if (path.empty())
path = string(getenv("HOME")) + "/data";
if (set.empty())
set = string(getenv("DATASET"));
if (set == "intel")
return make_pair(path + "/Intel/intel.graph", null_model);
if (set == "intel-gfs")
return make_pair(path + "/Intel/intel.gfs.graph", null_model);
if (set == "Killian-gfs")
return make_pair(path + "/Killian/Killian.gfs.graph", null_model);
if (set == "Killian")
return make_pair(path + "/Killian/Killian.graph", small);
if (set == "Killian-noised")
return make_pair(path + "/Killian/Killian-noised.graph", null_model);
if (set == "3")
return make_pair(path + "/TORO/w3-odom.graph", identity);
if (set == "100")
return make_pair(path + "/TORO/w100-odom.graph", identity);
if (set == "10K")
return make_pair(path + "/TORO/w10000-odom.graph", identity);
if (set == "10K2")
return make_pair(path + "/hogman/data/2D/w10000.graph",
noiseModel::Diagonal::Variances(gtsam::Vector_(3, 0.1, 0.1, 0.05)));
if (set == "Eiffel100")
return make_pair(path + "/TORO/w100-Eiffel.graph", identity);
if (set == "Eiffel10K")
return make_pair(path + "/TORO/w10000-Eiffel.graph", identity);
if (set == "olson")
return make_pair(path + "/Olson/olson06icra.graph", null_model);
if (set == "victoria")
return make_pair(path + "/VictoriaPark/victoria_park.graph", null_model);
if (set == "beijing")
return make_pair(path + "/Beijing/beijingData_trips.graph", null_model);
return make_pair("unknown", null_model);
}
/* ************************************************************************* */
pair<NonlinearFactorGraph::shared_ptr, Values::shared_ptr> load2D(
pair<string, boost::optional<noiseModel::Diagonal::shared_ptr> > dataset,

View File

@ -24,15 +24,6 @@
#include <string>
namespace gtsam {
/**
* Construct dataset filename from short name
* Currently has "Killian" "intel.gfs", "10K", etc...
* @param filename
* @param optional dataset, if empty will try to getenv $DATASET
* @param optional path, if empty will try to getenv $HOME
*/
std::pair<std::string, boost::optional<gtsam::SharedDiagonal> >
dataset(const std::string& dataset = "", const std::string& path = "");
/**
* Load TORO 2D Graph