diff --git a/gtsam/slam/dataset.cpp b/gtsam/slam/dataset.cpp index db85c65bf..607819cc7 100644 --- a/gtsam/slam/dataset.cpp +++ b/gtsam/slam/dataset.cpp @@ -163,7 +163,7 @@ static SharedNoiseModel readNoiseModel(ifstream& is, bool smart, } /* ************************************************************************* */ -GraphAndValues load2D(const string& filename, SharedNoiseModel model, int maxID, +GraphAndValues load2D(const string& filename, SharedNoiseModel model, Key maxID, bool addNoise, bool smart, NoiseFormat noiseFormat, KernelFunctionType kernelFunctionType) { @@ -211,7 +211,7 @@ GraphAndValues load2D(const string& filename, SharedNoiseModel model, int maxID, } // Parse the pose constraints - int id1, id2; + Key id1, id2; bool haveLandmark = false; while (!is.eof()) { if (!(is >> tag)) diff --git a/gtsam/slam/dataset.h b/gtsam/slam/dataset.h index c27419a6e..09a5baac7 100644 --- a/gtsam/slam/dataset.h +++ b/gtsam/slam/dataset.h @@ -94,7 +94,7 @@ GTSAM_EXPORT GraphAndValues load2D( * @return graph and initial values */ GTSAM_EXPORT GraphAndValues load2D(const std::string& filename, - SharedNoiseModel model = SharedNoiseModel(), int maxID = 0, bool addNoise = + SharedNoiseModel model = SharedNoiseModel(), Key maxID = 0, bool addNoise = false, bool smart = true, NoiseFormat noiseFormat = NoiseFormatGRAPH, // KernelFunctionType kernelFunctionType = KernelFunctionTypeNONE);