gtsam 4.1.1
gtsam
dataset.h
Go to the documentation of this file.
1/* ----------------------------------------------------------------------------
2
3 * GTSAM Copyright 2010, Georgia Tech Research Corporation,
4 * Atlanta, Georgia 30332-0415
5 * All Rights Reserved
6 * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
7
8 * See LICENSE for the license information
9
10 * -------------------------------------------------------------------------- */
11
21#pragma once
22
33#include <gtsam/base/Testable.h>
34#include <gtsam/base/types.h>
35
36#include <boost/smart_ptr/shared_ptr.hpp>
37#include <string>
38#include <utility> // for pair
39#include <vector>
40#include <iosfwd>
41#include <map>
42
43namespace gtsam {
44
56GTSAM_EXPORT std::string findExampleDataFile(const std::string& name);
57
62GTSAM_EXPORT std::string createRewrittenFileName(const std::string& name);
63
71};
72
75 KernelFunctionTypeNONE, KernelFunctionTypeHUBER, KernelFunctionTypeTUKEY
76};
77
84template <typename T>
85GTSAM_EXPORT std::map<size_t, T> parseVariables(const std::string &filename,
86 size_t maxIndex = 0);
87
94template <typename T>
95GTSAM_EXPORT std::vector<BinaryMeasurement<T>>
96parseMeasurements(const std::string &filename,
97 const noiseModel::Diagonal::shared_ptr &model = nullptr,
98 size_t maxIndex = 0);
99
104template <typename T>
105GTSAM_EXPORT std::vector<typename BetweenFactor<T>::shared_ptr>
106parseFactors(const std::string &filename,
107 const noiseModel::Diagonal::shared_ptr &model = nullptr,
108 size_t maxIndex = 0);
109
111typedef std::pair<size_t, Pose2> IndexedPose;
112typedef std::pair<size_t, Point2> IndexedLandmark;
113typedef std::pair<std::pair<size_t, size_t>, Pose2> IndexedEdge;
114
120GTSAM_EXPORT boost::optional<IndexedPose> parseVertexPose(std::istream& is,
121 const std::string& tag);
122
128GTSAM_EXPORT boost::optional<IndexedLandmark> parseVertexLandmark(std::istream& is,
129 const std::string& tag);
130
136GTSAM_EXPORT boost::optional<IndexedEdge> parseEdge(std::istream& is,
137 const std::string& tag);
138
143 std::pair<NonlinearFactorGraph::shared_ptr, Values::shared_ptr>;
144
152GTSAM_EXPORT GraphAndValues load2D(
153 std::pair<std::string, SharedNoiseModel> dataset, size_t maxIndex = 0,
154 bool addNoise = false,
155 bool smart = true, //
156 NoiseFormat noiseFormat = NoiseFormatAUTO,
157 KernelFunctionType kernelFunctionType = KernelFunctionTypeNONE);
158
170GTSAM_EXPORT GraphAndValues load2D(const std::string& filename,
171 SharedNoiseModel model = SharedNoiseModel(), size_t maxIndex = 0, bool addNoise =
172 false, bool smart = true, NoiseFormat noiseFormat = NoiseFormatAUTO, //
173 KernelFunctionType kernelFunctionType = KernelFunctionTypeNONE);
174
176GTSAM_EXPORT GraphAndValues load2D_robust(const std::string& filename,
177 const noiseModel::Base::shared_ptr& model, size_t maxIndex = 0);
178
180GTSAM_EXPORT void save2D(const NonlinearFactorGraph& graph,
181 const Values& config, const noiseModel::Diagonal::shared_ptr model,
182 const std::string& filename);
183
192GTSAM_EXPORT GraphAndValues readG2o(const std::string& g2oFile, const bool is3D = false,
193 KernelFunctionType kernelFunctionType = KernelFunctionTypeNONE);
194
207GTSAM_EXPORT void writeG2o(const NonlinearFactorGraph& graph,
208 const Values& estimate, const std::string& filename);
209
211GTSAM_EXPORT GraphAndValues load3D(const std::string& filename);
212
214typedef std::pair<size_t, Point2> SfmMeasurement;
215
217typedef std::pair<size_t, size_t> SiftIndex;
218
220struct SfmTrack {
221 SfmTrack(float r = 0, float g = 0, float b = 0): p(0,0,0), r(r), g(g), b(b) {}
222 SfmTrack(const gtsam::Point3& pt, float r = 0, float g = 0, float b = 0) : p(pt), r(r), g(g), b(b) {}
223
225 float r, g, b;
226 std::vector<SfmMeasurement> measurements;
227 std::vector<SiftIndex> siftIndices;
228
230 const Point3 rgb() const { return Point3(r, g, b); }
231
233 size_t number_measurements() const {
234 return measurements.size();
235 }
237 SfmMeasurement measurement(size_t idx) const {
238 return measurements[idx];
239 }
241 SiftIndex siftIndex(size_t idx) const {
242 return siftIndices[idx];
243 }
245 const Point3& point3() const {
246 return p;
247 }
249 void add_measurement(size_t idx, const gtsam::Point2& m) {
250 measurements.emplace_back(idx, m);
251 }
252
255 template<class ARCHIVE>
256 void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
257 ar & BOOST_SERIALIZATION_NVP(p);
258 ar & BOOST_SERIALIZATION_NVP(r);
259 ar & BOOST_SERIALIZATION_NVP(g);
260 ar & BOOST_SERIALIZATION_NVP(b);
261 ar & BOOST_SERIALIZATION_NVP(measurements);
262 ar & BOOST_SERIALIZATION_NVP(siftIndices);
263 }
264
266 bool equals(const SfmTrack &sfmTrack, double tol = 1e-9) const {
267 // check the 3D point
268 if (!p.isApprox(sfmTrack.p)) {
269 return false;
270 }
271
272 // check the RGB values
273 if (r!=sfmTrack.r || g!=sfmTrack.g || b!=sfmTrack.b) {
274 return false;
275 }
276
277 // compare size of vectors for measurements and siftIndices
278 if (number_measurements() != sfmTrack.number_measurements() ||
279 siftIndices.size() != sfmTrack.siftIndices.size()) {
280 return false;
281 }
282
283 // compare measurements (order sensitive)
284 for (size_t idx = 0; idx < number_measurements(); ++idx) {
286 SfmMeasurement otherMeasurement = sfmTrack.measurements[idx];
287
288 if (measurement.first != otherMeasurement.first ||
289 !measurement.second.isApprox(otherMeasurement.second)) {
290 return false;
291 }
292 }
293
294 // compare sift indices (order sensitive)
295 for (size_t idx = 0; idx < siftIndices.size(); ++idx) {
296 SiftIndex index = siftIndices[idx];
297 SiftIndex otherIndex = sfmTrack.siftIndices[idx];
298
299 if (index.first != otherIndex.first ||
300 index.second != otherIndex.second) {
301 return false;
302 }
303 }
304
305 return true;
306 }
307
309 void print(const std::string& s = "") const {
310 std::cout << "Track with " << measurements.size();
311 std::cout << " measurements of point " << p << std::endl;
312 }
313};
314
315/* ************************************************************************* */
317template<>
318struct traits<SfmTrack> : public Testable<SfmTrack> {
319};
320
321
324
326struct SfmData {
327 std::vector<SfmCamera> cameras;
328 std::vector<SfmTrack> tracks;
329 size_t number_cameras() const {
330 return cameras.size();
331 }
333 size_t number_tracks() const {
334 return tracks.size();
335 }
337 SfmCamera camera(size_t idx) const {
338 return cameras[idx];
339 }
341 SfmTrack track(size_t idx) const {
342 return tracks[idx];
343 }
345 void add_track(const SfmTrack& t) {
346 tracks.push_back(t);
347 }
349 void add_camera(const SfmCamera& cam) {
350 cameras.push_back(cam);
351 }
352
355 template<class Archive>
356 void serialize(Archive & ar, const unsigned int /*version*/) {
357 ar & BOOST_SERIALIZATION_NVP(cameras);
358 ar & BOOST_SERIALIZATION_NVP(tracks);
359 }
360
364
366 bool equals(const SfmData &sfmData, double tol = 1e-9) const {
367 // check number of cameras and tracks
368 if (number_cameras() != sfmData.number_cameras() ||
369 number_tracks() != sfmData.number_tracks()) {
370 return false;
371 }
372
373 // check each camera
374 for (size_t i = 0; i < number_cameras(); ++i) {
375 if (!camera(i).equals(sfmData.camera(i), tol)) {
376 return false;
377 }
378 }
379
380 // check each track
381 for (size_t j = 0; j < number_tracks(); ++j) {
382 if (!track(j).equals(sfmData.track(j), tol)) {
383 return false;
384 }
385 }
386
387 return true;
388 }
389
391 void print(const std::string& s = "") const {
392 std::cout << "Number of cameras = " << number_cameras() << std::endl;
393 std::cout << "Number of tracks = " << number_tracks() << std::endl;
394 }
395};
396
397/* ************************************************************************* */
399template<>
400struct traits<SfmData> : public Testable<SfmData> {
401};
402
410GTSAM_EXPORT bool readBundler(const std::string& filename, SfmData &data);
411
419GTSAM_EXPORT bool readBAL(const std::string& filename, SfmData &data);
420
427GTSAM_EXPORT SfmData readBal(const std::string& filename);
428
436GTSAM_EXPORT bool writeBAL(const std::string& filename, SfmData &data);
437
449GTSAM_EXPORT bool writeBALfromValues(const std::string& filename,
450 const SfmData &data, Values& values);
451
460GTSAM_EXPORT Pose3 openGL2gtsam(const Rot3& R, double tx, double ty, double tz);
461
470GTSAM_EXPORT Pose3 gtsam2openGL(const Rot3& R, double tx, double ty, double tz);
471
477GTSAM_EXPORT Pose3 gtsam2openGL(const Pose3& PoseGTSAM);
478
484GTSAM_EXPORT Values initialCamerasEstimate(const SfmData& db);
485
491GTSAM_EXPORT Values initialCamerasAndPointsEstimate(const SfmData& db);
492
493// Wrapper-friendly versions of parseFactors<Pose2> and parseFactors<Pose2>
494using BetweenFactorPose2s = std::vector<BetweenFactor<Pose2>::shared_ptr>;
495GTSAM_EXPORT BetweenFactorPose2s
496parse2DFactors(const std::string &filename,
497 const noiseModel::Diagonal::shared_ptr &model = nullptr,
498 size_t maxIndex = 0);
499
500using BetweenFactorPose3s = std::vector<BetweenFactor<Pose3>::shared_ptr>;
501GTSAM_EXPORT BetweenFactorPose3s
502parse3DFactors(const std::string &filename,
503 const noiseModel::Diagonal::shared_ptr &model = nullptr,
504 size_t maxIndex = 0);
505
506using BinaryMeasurementsUnit3 = std::vector<BinaryMeasurement<Unit3>>;
507#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V41
508inline boost::optional<IndexedPose> parseVertex(std::istream &is,
509 const std::string &tag) {
510 return parseVertexPose(is, tag);
511}
512
513GTSAM_EXPORT std::map<size_t, Pose3> parse3DPoses(const std::string &filename,
514 size_t maxIndex = 0);
515
516GTSAM_EXPORT std::map<size_t, Point3>
517parse3DLandmarks(const std::string &filename, size_t maxIndex = 0);
518
519#endif
520} // namespace gtsam
Typedefs for easier changing of types.
Concept check for values that can be used in unit tests.
Base class for all pinhole cameras.
Calibration used by Bundler.
3D Pose
2D Pose
A non-templated config holding any types of Manifold-group elements.
Factor Graph consisting of non-linear factors.
Binary measurement represents a measurement between two keys in a graph. A binary measurement is simi...
Global functions in a separate testing namespace.
Definition: chartTesting.h:28
std::pair< size_t, size_t > SiftIndex
Sift index for SfmTrack.
Definition: dataset.h:217
bool readBundler(const string &filename, SfmData &data)
This function parses a bundler output file and stores the data into a SfmData structure.
Definition: dataset.cpp:986
GraphAndValues load2D(const string &filename, SharedNoiseModel model, size_t maxIndex, bool addNoise, bool smart, NoiseFormat noiseFormat, KernelFunctionType kernelFunctionType)
Load TORO/G2O style graph files.
Definition: dataset.cpp:500
GTSAM_EXPORT std::map< size_t, T > parseVariables(const std::string &filename, size_t maxIndex=0)
Parse variables in a line-based text format (like g2o) into a map.
void writeG2o(const NonlinearFactorGraph &graph, const Values &estimate, const string &filename)
This function writes a g2o file from NonlinearFactorGraph and a Values structure.
Definition: dataset.cpp:630
std::pair< size_t, Pose2 > IndexedPose
Return type for auxiliary functions.
Definition: dataset.h:111
Vector2 Point2
As of GTSAM 4, in order to make GTSAM more lean, it is now possible to just typedef Point2 to Vector2...
Definition: Point2.h:27
SfmData readBal(const string &filename)
This function parses a "Bundle Adjustment in the Large" (BAL) file and returns the data as a SfmData ...
Definition: dataset.cpp:1133
bool writeBALfromValues(const string &filename, const SfmData &data, Values &values)
This function writes a "Bundle Adjustment in the Large" (BAL) file from a SfmData structure and a val...
Definition: dataset.cpp:1216
GraphAndValues readG2o(const string &g2oFile, const bool is3D, KernelFunctionType kernelFunctionType)
This function parses a g2o file and stores the measurements into a NonlinearFactorGraph and the initi...
Definition: dataset.cpp:615
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)
Parse BetweenFactors in a line-based text format (like g2o) into a vector of shared pointers.
KernelFunctionType
Robust kernel type to wrap around quadratic noise model.
Definition: dataset.h:74
NoiseFormat
Indicates how noise parameters are stored in file.
Definition: dataset.h:65
@ NoiseFormatGRAPH
default: toro-style order, but covariance matrix !
Definition: dataset.h:68
@ NoiseFormatAUTO
Try to guess covariance matrix layout.
Definition: dataset.h:70
@ NoiseFormatTORO
Information matrix, but inf_ff inf_fs inf_ss inf_rr inf_fr inf_sr.
Definition: dataset.h:67
@ NoiseFormatCOV
Covariance matrix C11, C12, C13, C22, C23, C33.
Definition: dataset.h:69
@ NoiseFormatG2O
Information matrix I11, I12, I13, I22, I23, I33.
Definition: dataset.h:66
boost::optional< IndexedLandmark > parseVertexLandmark(istream &is, const string &tag)
Parse G2O landmark vertex "id x y".
Definition: dataset.cpp:188
std::pair< size_t, Point2 > SfmMeasurement
A measurement with its camera index.
Definition: dataset.h:214
Vector3 Point3
As of GTSAM 4, in order to make GTSAM more lean, it is now possible to just typedef Point3 to Vector3...
Definition: Point3.h:35
Pose3 gtsam2openGL(const Rot3 &R, double tx, double ty, double tz)
This function converts a GTSAM camera pose to an openGL camera pose.
Definition: dataset.cpp:972
noiseModel::Base::shared_ptr SharedNoiseModel
Note, deliberately not in noiseModel namespace.
Definition: NoiseModel.h:736
Values initialCamerasAndPointsEstimate(const SfmData &db)
This function creates initial values for cameras and points from db.
Definition: dataset.cpp:1284
GraphAndValues load2D_robust(const string &filename, const noiseModel::Base::shared_ptr &model, size_t maxIndex)
Definition: dataset.cpp:575
boost::optional< IndexedEdge > parseEdge(istream &is, const string &tag)
Parse TORO/G2O edge "id1 id2 x y yaw".
Definition: dataset.cpp:294
std::pair< NonlinearFactorGraph::shared_ptr, Values::shared_ptr > GraphAndValues
Return type for load functions, which return a graph and initial values.
Definition: dataset.h:143
boost::optional< IndexedPose > parseVertexPose(istream &is, const string &tag)
Parse TORO/G2O vertex "id x y yaw".
Definition: dataset.cpp:168
GraphAndValues load3D(const string &filename)
Load TORO 3D Graph.
Definition: dataset.cpp:924
PinholeCamera< Cal3Bundler > SfmCamera
Define the structure for the camera poses.
Definition: dataset.h:323
void save2D(const NonlinearFactorGraph &graph, const Values &config, const noiseModel::Diagonal::shared_ptr model, const string &filename)
save 2d graph
Definition: dataset.cpp:582
Values initialCamerasEstimate(const SfmData &db)
This function creates initial values for cameras from db.
Definition: dataset.cpp:1276
string createRewrittenFileName(const string &name)
Creates a temporary file name that needs to be ignored in .gitingnore for checking read-write opratio...
Definition: dataset.cpp:100
Pose3 openGL2gtsam(const Rot3 &R, double tx, double ty, double tz)
This function converts an openGL camera pose to an GTSAM camera pose.
Definition: dataset.cpp:963
bool writeBAL(const string &filename, SfmData &data)
This function writes a "Bundle Adjustment in the Large" (BAL) file from a SfmData structure.
Definition: dataset.cpp:1140
string findExampleDataFile(const string &name)
Find the full path to an example dataset distributed with gtsam.
Definition: dataset.cpp:65
bool readBAL(const string &filename, SfmData &data)
This function parses a "Bundle Adjustment in the Large" (BAL) file and stores the data into a SfmData...
Definition: dataset.cpp:1073
A manifold defines a space in which there is a notion of a linear tangent space that can be centered ...
Definition: concepts.h:30
A helper that implements the traits interface for GTSAM types.
Definition: Testable.h:151
Definition: PinholeCamera.h:33
bool equals(const Base &camera, double tol=1e-9) const
assert equality up to a tolerance
Definition: PinholeCamera.h:145
Definition: Pose2.h:36
Definition: Pose3.h:37
Definition: Rot3.h:59
A non-linear factor graph is a graph of non-Gaussian, i.e.
Definition: NonlinearFactorGraph.h:78
A non-templated config holding any types of Manifold-group elements.
Definition: Values.h:63
Define the structure for the 3D points.
Definition: dataset.h:220
std::vector< SfmMeasurement > measurements
The 2D image projections (id,(u,v))
Definition: dataset.h:226
void print(const std::string &s="") const
print
Definition: dataset.h:309
float b
RGB color of the 3D point.
Definition: dataset.h:225
void add_measurement(size_t idx, const gtsam::Point2 &m)
Add measurement (camera_idx, Point2) to track.
Definition: dataset.h:249
size_t number_measurements() const
Total number of measurements in this track.
Definition: dataset.h:233
SfmMeasurement measurement(size_t idx) const
Get the measurement (camera index, Point2) at pose index idx
Definition: dataset.h:237
const Point3 rgb() const
Get RGB values describing 3d point.
Definition: dataset.h:230
bool equals(const SfmTrack &sfmTrack, double tol=1e-9) const
assert equality up to a tolerance
Definition: dataset.h:266
SiftIndex siftIndex(size_t idx) const
Get the SIFT feature index corresponding to the measurement at idx
Definition: dataset.h:241
friend class boost::serialization::access
Serialization function.
Definition: dataset.h:254
const Point3 & point3() const
Get 3D point.
Definition: dataset.h:245
Point3 p
3D position of the point
Definition: dataset.h:224
Define the structure for SfM data.
Definition: dataset.h:326
SfmCamera camera(size_t idx) const
The camera pose at frame index idx
Definition: dataset.h:337
void add_camera(const SfmCamera &cam)
Add a camera to SfmData.
Definition: dataset.h:349
void print(const std::string &s="") const
print
Definition: dataset.h:391
size_t number_tracks() const
The number of reconstructed 3D points.
Definition: dataset.h:333
friend class boost::serialization::access
Serialization function.
Definition: dataset.h:354
std::vector< SfmCamera > cameras
Set of cameras.
Definition: dataset.h:327
void add_track(const SfmTrack &t)
Add a track to SfmData.
Definition: dataset.h:345
bool equals(const SfmData &sfmData, double tol=1e-9) const
assert equality up to a tolerance
Definition: dataset.h:366
std::vector< SfmTrack > tracks
Sparse set of points.
Definition: dataset.h:328
SfmTrack track(size_t idx) const
The track formed by series of landmark measurements.
Definition: dataset.h:341
Convenience functions for serializing data structures via boost.serialization.