Better wrap of load
parent
1cc67754d3
commit
8e2f8a87eb
|
@ -167,10 +167,11 @@ GTSAM_EXPORT GraphAndValues load2D(
|
||||||
* @param kernelFunctionType whether to wrap the noise model in a robust kernel
|
* @param kernelFunctionType whether to wrap the noise model in a robust kernel
|
||||||
* @return graph and initial values
|
* @return graph and initial values
|
||||||
*/
|
*/
|
||||||
GTSAM_EXPORT GraphAndValues load2D(const std::string& filename,
|
GTSAM_EXPORT GraphAndValues
|
||||||
SharedNoiseModel model = SharedNoiseModel(), size_t maxIndex = 0, bool addNoise =
|
load2D(const std::string& filename, SharedNoiseModel model = SharedNoiseModel(),
|
||||||
false, bool smart = true, NoiseFormat noiseFormat = NoiseFormatAUTO, //
|
size_t maxIndex = 0, bool addNoise = false, bool smart = true,
|
||||||
KernelFunctionType kernelFunctionType = KernelFunctionTypeNONE);
|
NoiseFormat noiseFormat = NoiseFormatAUTO, //
|
||||||
|
KernelFunctionType kernelFunctionType = KernelFunctionTypeNONE);
|
||||||
|
|
||||||
/** save 2d graph */
|
/** save 2d graph */
|
||||||
GTSAM_EXPORT void save2D(const NonlinearFactorGraph& graph,
|
GTSAM_EXPORT void save2D(const NonlinearFactorGraph& graph,
|
||||||
|
@ -185,8 +186,9 @@ GTSAM_EXPORT void save2D(const NonlinearFactorGraph& graph,
|
||||||
* @param kernelFunctionType whether to wrap the noise model in a robust kernel
|
* @param kernelFunctionType whether to wrap the noise model in a robust kernel
|
||||||
* @return graph and initial values
|
* @return graph and initial values
|
||||||
*/
|
*/
|
||||||
GTSAM_EXPORT GraphAndValues readG2o(const std::string& g2oFile, const bool is3D = false,
|
GTSAM_EXPORT GraphAndValues
|
||||||
KernelFunctionType kernelFunctionType = KernelFunctionTypeNONE);
|
readG2o(const std::string& g2oFile, const bool is3D = false,
|
||||||
|
KernelFunctionType kernelFunctionType = KernelFunctionTypeNONE);
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief This function writes a g2o file from
|
* @brief This function writes a g2o file from
|
||||||
|
|
|
@ -253,17 +253,27 @@ bool writeBAL(string filename, gtsam::SfmData& data);
|
||||||
gtsam::Values initialCamerasEstimate(const gtsam::SfmData& db);
|
gtsam::Values initialCamerasEstimate(const gtsam::SfmData& db);
|
||||||
gtsam::Values initialCamerasAndPointsEstimate(const gtsam::SfmData& db);
|
gtsam::Values initialCamerasAndPointsEstimate(const gtsam::SfmData& db);
|
||||||
|
|
||||||
pair<gtsam::NonlinearFactorGraph*, gtsam::Values*> load2D(
|
enum NoiseFormat {
|
||||||
string filename, gtsam::noiseModel::Diagonal* model, int maxIndex,
|
NoiseFormatG2O,
|
||||||
bool addNoise, bool smart);
|
NoiseFormatTORO,
|
||||||
pair<gtsam::NonlinearFactorGraph*, gtsam::Values*> load2D(
|
NoiseFormatGRAPH,
|
||||||
string filename, gtsam::noiseModel::Diagonal* model, int maxIndex,
|
NoiseFormatCOV,
|
||||||
bool addNoise);
|
NoiseFormatAUTO
|
||||||
pair<gtsam::NonlinearFactorGraph*, gtsam::Values*> load2D(
|
};
|
||||||
string filename, gtsam::noiseModel::Diagonal* model, int maxIndex);
|
|
||||||
pair<gtsam::NonlinearFactorGraph*, gtsam::Values*> load2D(
|
enum KernelFunctionType {
|
||||||
string filename, gtsam::noiseModel::Diagonal* model);
|
KernelFunctionTypeNONE,
|
||||||
pair<gtsam::NonlinearFactorGraph*, gtsam::Values*> load2D(string filename);
|
KernelFunctionTypeHUBER,
|
||||||
|
KernelFunctionTypeTUKEY
|
||||||
|
};
|
||||||
|
|
||||||
|
std::pair<gtsam::NonlinearFactorGraph*, gtsam::Values*> load2D(
|
||||||
|
string filename, gtsam::noiseModel::Diagonal* model = nullptr,
|
||||||
|
size_t maxIndex = 0, bool addNoise = false, bool smart = true,
|
||||||
|
gtsam::NoiseFormat noiseFormat = gtsam::NoiseFormatAUTO,
|
||||||
|
gtsam::KernelFunctionType kernelFunctionType =
|
||||||
|
gtsam::KernelFunctionTypeNONE);
|
||||||
|
|
||||||
void save2D(const gtsam::NonlinearFactorGraph& graph,
|
void save2D(const gtsam::NonlinearFactorGraph& graph,
|
||||||
const gtsam::Values& config, gtsam::noiseModel::Diagonal* model,
|
const gtsam::Values& config, gtsam::noiseModel::Diagonal* model,
|
||||||
string filename);
|
string filename);
|
||||||
|
@ -290,9 +300,10 @@ gtsam::BetweenFactorPose3s parse3DFactors(string filename);
|
||||||
|
|
||||||
pair<gtsam::NonlinearFactorGraph*, gtsam::Values*> load3D(string filename);
|
pair<gtsam::NonlinearFactorGraph*, gtsam::Values*> load3D(string filename);
|
||||||
|
|
||||||
pair<gtsam::NonlinearFactorGraph*, gtsam::Values*> readG2o(string filename);
|
pair<gtsam::NonlinearFactorGraph*, gtsam::Values*> readG2o(
|
||||||
pair<gtsam::NonlinearFactorGraph*, gtsam::Values*> readG2o(string filename,
|
string filename, const bool is3D = false,
|
||||||
bool is3D);
|
gtsam::KernelFunctionType kernelFunctionType =
|
||||||
|
gtsam::KernelFunctionTypeNONE);
|
||||||
void writeG2o(const gtsam::NonlinearFactorGraph& graph,
|
void writeG2o(const gtsam::NonlinearFactorGraph& graph,
|
||||||
const gtsam::Values& estimate, string filename);
|
const gtsam::Values& estimate, string filename);
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue