75 KernelFunctionTypeNONE, KernelFunctionTypeHUBER, KernelFunctionTypeTUKEY
85 GTSAM_EXPORT std::map<size_t, T>
parseVariables(
const std::string &filename,
95 GTSAM_EXPORT std::vector<BinaryMeasurement<T>>
97 const noiseModel::Diagonal::shared_ptr &model =
nullptr,
104 template <
typename T>
105 GTSAM_EXPORT std::vector<typename BetweenFactor<T>::shared_ptr>
107 const noiseModel::Diagonal::shared_ptr &model =
nullptr,
108 size_t maxIndex = 0);
112 typedef std::pair<size_t, Point2> IndexedLandmark;
113 typedef std::pair<std::pair<size_t, size_t>,
Pose2> IndexedEdge;
120 GTSAM_EXPORT std::optional<IndexedPose>
parseVertexPose(std::istream& is,
121 const std::string& tag);
129 const std::string& tag);
136 GTSAM_EXPORT std::optional<IndexedEdge>
parseEdge(std::istream& is,
137 const std::string& tag);
143 std::pair<NonlinearFactorGraph::shared_ptr, Values::shared_ptr>;
153 std::pair<std::string, SharedNoiseModel> dataset,
size_t maxIndex = 0,
154 bool addNoise =
false,
172 size_t maxIndex = 0,
bool addNoise =
false,
bool smart =
true,
178 const Values& config,
const noiseModel::Diagonal::shared_ptr model,
179 const std::string& filename);
190 readG2o(
const std::string& g2oFile,
const bool is3D =
false,
206 const Values& estimate,
const std::string& filename);
212 using BetweenFactorPose2s = std::vector<BetweenFactor<Pose2>::shared_ptr>;
213 GTSAM_EXPORT BetweenFactorPose2s
214 parse2DFactors(
const std::string &filename,
215 const noiseModel::Diagonal::shared_ptr &model =
nullptr,
216 size_t maxIndex = 0);
218 using BetweenFactorPose3s = std::vector<BetweenFactor<Pose3>::shared_ptr>;
219 GTSAM_EXPORT BetweenFactorPose3s
220 parse3DFactors(
const std::string &filename,
221 const noiseModel::Diagonal::shared_ptr &model =
nullptr,
222 size_t maxIndex = 0);
224 using BinaryMeasurementsUnit3 = std::vector<BinaryMeasurement<Unit3>>;
225 using BinaryMeasurementsPoint3 = std::vector<BinaryMeasurement<Point3>>;
226 using BinaryMeasurementsRot3 = std::vector<BinaryMeasurement<Rot3>>;
std::pair< NonlinearFactorGraph::shared_ptr, Values::shared_ptr > GraphAndValues
Definition: dataset.h:143
Typedefs for easier changing of types.
default: toro-style order, but covariance matrix !
Definition: dataset.h:68
Concept check for values that can be used in unit tests.
A non-templated config holding any types of Manifold-group elements.
Factor Graph consisting of non-linear factors.
KernelFunctionType
Robust kernel type to wrap around quadratic noise model.
Definition: dataset.h:74
std::pair< size_t, Pose2 > IndexedPose
Return type for auxiliary functions.
Definition: dataset.h:111
GTSAM_EXPORT std::vector< BinaryMeasurement< T > > parseMeasurements(const std::string &filename, const noiseModel::Diagonal::shared_ptr &model=nullptr, size_t maxIndex=0)
Try to guess covariance matrix layout.
Definition: dataset.h:70
GTSAM_EXPORT std::string createRewrittenFileName(const std::string &name)
NoiseFormat
Indicates how noise parameters are stored in file.
Definition: dataset.h:65
Base class for all pinhole cameras.
Information matrix, but inf_ff inf_fs inf_ss inf_rr inf_fr inf_sr.
Definition: dataset.h:67
Data structure for dealing with Structure from Motion data.
GTSAM_EXPORT GraphAndValues load3D(const std::string &filename)
Load TORO 3D Graph.
GTSAM_EXPORT void save2D(const NonlinearFactorGraph &graph, const Values &config, const noiseModel::Diagonal::shared_ptr model, const std::string &filename)
GTSAM_EXPORT GraphAndValues load2D(std::pair< std::string, SharedNoiseModel > dataset, size_t maxIndex=0, bool addNoise=false, bool smart=true, NoiseFormat noiseFormat=NoiseFormatAUTO, KernelFunctionType kernelFunctionType=KernelFunctionTypeNONE)
Definition: NonlinearFactorGraph.h:55
GTSAM_EXPORT std::optional< IndexedPose > parseVertexPose(std::istream &is, const std::string &tag)
GTSAM_EXPORT GraphAndValues readG2o(const std::string &g2oFile, const bool is3D=false, KernelFunctionType kernelFunctionType=KernelFunctionTypeNONE)
This function parses a g2o file and stores the measurements into a NonlinearFactorGraph and the initi...
Definition: chartTesting.h:28
Covariance matrix C11, C12, C13, C22, C23, C33.
Definition: dataset.h:69
Information matrix I11, I12, I13, I22, I23, I33.
Definition: dataset.h:66
GTSAM_EXPORT std::map< size_t, T > parseVariables(const std::string &filename, size_t maxIndex=0)
GTSAM_EXPORT void writeG2o(const NonlinearFactorGraph &graph, const Values &estimate, const std::string &filename)
This function writes a g2o file from NonlinearFactorGraph and a Values structure. ...
GTSAM_EXPORT std::optional< IndexedLandmark > parseVertexLandmark(std::istream &is, const std::string &tag)
Binary measurement represents a measurement between two keys in a graph. A binary measurement is simi...
Calibration used by Bundler.
GTSAM_EXPORT std::optional< IndexedEdge > parseEdge(std::istream &is, const std::string &tag)
GTSAM_EXPORT std::vector< typename BetweenFactor< T >::shared_ptr > parseFactors(const std::string &filename, const noiseModel::Diagonal::shared_ptr &model=nullptr, size_t maxIndex=0)
noiseModel::Base::shared_ptr SharedNoiseModel
Definition: NoiseModel.h:741
GTSAM_EXPORT std::string findExampleDataFile(const std::string &name)