gtsam  4.0.0
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 
19 #pragma once
20 
24 #include <gtsam/geometry/Point2.h>
25 #include <gtsam/geometry/Point3.h>
26 #include <gtsam/geometry/Pose3.h>
27 #include <gtsam/geometry/Rot3.h>
29 #include <gtsam/nonlinear/Values.h>
31 #include <gtsam/base/types.h>
32 
33 #include <boost/smart_ptr/shared_ptr.hpp>
34 #include <string>
35 #include <utility> // for pair
36 #include <vector>
37 #include <iosfwd>
38 #include <map>
39 
40 namespace gtsam {
41 
53 GTSAM_EXPORT std::string findExampleDataFile(const std::string& name);
54 
59 GTSAM_EXPORT std::string createRewrittenFileName(const std::string& name);
60 
68 };
69 
72  KernelFunctionTypeNONE, KernelFunctionTypeHUBER, KernelFunctionTypeTUKEY
73 };
74 
76 typedef std::pair<Key, Pose2> IndexedPose;
77 typedef std::pair<std::pair<Key, Key>, Pose2> IndexedEdge;
78 
84 GTSAM_EXPORT boost::optional<IndexedPose> parseVertex(std::istream& is,
85  const std::string& tag);
86 
92 GTSAM_EXPORT boost::optional<IndexedEdge> parseEdge(std::istream& is,
93  const std::string& tag);
94 
96 typedef std::pair<NonlinearFactorGraph::shared_ptr, Values::shared_ptr> GraphAndValues;
97 
105 GTSAM_EXPORT GraphAndValues load2D(
106  std::pair<std::string, SharedNoiseModel> dataset, int maxID = 0,
107  bool addNoise = false,
108  bool smart = true, //
109  NoiseFormat noiseFormat = NoiseFormatAUTO,
110  KernelFunctionType kernelFunctionType = KernelFunctionTypeNONE);
111 
123 GTSAM_EXPORT GraphAndValues load2D(const std::string& filename,
124  SharedNoiseModel model = SharedNoiseModel(), Key maxID = 0, bool addNoise =
125  false, bool smart = true, NoiseFormat noiseFormat = NoiseFormatAUTO, //
126  KernelFunctionType kernelFunctionType = KernelFunctionTypeNONE);
127 
129 GTSAM_EXPORT GraphAndValues load2D_robust(const std::string& filename,
130  noiseModel::Base::shared_ptr& model, int maxID = 0);
131 
133 GTSAM_EXPORT void save2D(const NonlinearFactorGraph& graph,
134  const Values& config, const noiseModel::Diagonal::shared_ptr model,
135  const std::string& filename);
136 
145 GTSAM_EXPORT GraphAndValues readG2o(const std::string& g2oFile, const bool is3D = false,
146  KernelFunctionType kernelFunctionType = KernelFunctionTypeNONE);
147 
155 GTSAM_EXPORT void writeG2o(const NonlinearFactorGraph& graph,
156  const Values& estimate, const std::string& filename);
157 
159 using BetweenFactorPose3s = std::vector<gtsam::BetweenFactor<Pose3>::shared_ptr>;
160 GTSAM_EXPORT BetweenFactorPose3s parse3DFactors(const std::string& filename);
161 
163 GTSAM_EXPORT std::map<Key, Pose3> parse3DPoses(const std::string& filename);
164 
166 GTSAM_EXPORT GraphAndValues load3D(const std::string& filename);
167 
169 typedef std::pair<size_t, Point2> SfM_Measurement;
170 
172 typedef std::pair<size_t, size_t> SIFT_Index;
173 
175 struct SfM_Track {
176  SfM_Track():p(0,0,0) {}
178  float r, g, b;
179  std::vector<SfM_Measurement> measurements;
180  std::vector<SIFT_Index> siftIndices;
181  size_t number_measurements() const {
182  return measurements.size();
183  }
184 };
185 
188 
190 struct SfM_data {
191  std::vector<SfM_Camera> cameras;
192  std::vector<SfM_Track> tracks;
193  size_t number_cameras() const {
194  return cameras.size();
195  }
196  size_t number_tracks() const {
197  return tracks.size();
198  }
199 };
200 
208 GTSAM_EXPORT bool readBundler(const std::string& filename, SfM_data &data);
209 
217 GTSAM_EXPORT bool readBAL(const std::string& filename, SfM_data &data);
218 
226 GTSAM_EXPORT bool writeBAL(const std::string& filename, SfM_data &data);
227 
239 GTSAM_EXPORT bool writeBALfromValues(const std::string& filename,
240  const SfM_data &data, Values& values);
241 
250 GTSAM_EXPORT Pose3 openGL2gtsam(const Rot3& R, double tx, double ty, double tz);
251 
260 GTSAM_EXPORT Pose3 gtsam2openGL(const Rot3& R, double tx, double ty, double tz);
261 
267 GTSAM_EXPORT Pose3 gtsam2openGL(const Pose3& PoseGTSAM);
268 
274 GTSAM_EXPORT Values initialCamerasEstimate(const SfM_data& db);
275 
281 GTSAM_EXPORT Values initialCamerasAndPointsEstimate(const SfM_data& db);
282 
283 } // namespace gtsam
A non-templated config holding any types of Manifold-group elements.
Definition: Values.h:70
Calibration used by Bundler.
Define the structure for the 3D points.
Definition: dataset.h:175
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:427
boost::optional< IndexedEdge > parseEdge(istream &is, const string &tag)
Parse TORO/G2O edge "id1 id2 x y yaw".
Definition: dataset.cpp:207
default: toro-style order, but covariance matrix !
Definition: dataset.h:65
string findExampleDataFile(const string &name)
Find the full path to an example dataset distributed with gtsam.
Definition: dataset.cpp:55
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:626
Definition: PinholeCamera.h:33
std::pair< size_t, Point2 > SfM_Measurement
A measurement with its camera index.
Definition: dataset.h:169
Definition: Point3.h:45
std::pair< Key, Pose2 > IndexedPose
Return type for auxiliary functions.
Definition: dataset.h:76
Try to guess covariance matrix layout.
Definition: dataset.h:67
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:57
Covariance matrix C11, C12, C13, C22, C23, C33.
Definition: dataset.h:66
void save2D(const NonlinearFactorGraph &graph, const Values &config, const noiseModel::Diagonal::shared_ptr model, const string &filename)
save 2d graph
Definition: dataset.cpp:379
bool readBAL(const string &filename, SfM_data &data)
This function parses a "Bundle Adjustment in the Large" (BAL) file and stores the data into a SfM_dat...
Definition: dataset.cpp:736
2D Point
GraphAndValues load2D(pair< string, SharedNoiseModel > dataset, int maxID, bool addNoise, bool smart, NoiseFormat noiseFormat, KernelFunctionType kernelFunctionType)
Load TORO 2D Graph.
Definition: dataset.cpp:104
boost::optional< IndexedPose > parseVertex(istream &is, const string &tag)
Parse TORO/G2O vertex "id x y yaw".
Definition: dataset.cpp:195
Base class for all pinhole cameras.
Factor Graph Constsiting of non-linear factors.
Define the structure for SfM data.
Definition: dataset.h:190
GraphAndValues load3D(const string &filename)
Load TORO 3D Graph.
Definition: dataset.cpp:596
std::pair< NonlinearFactorGraph::shared_ptr, Values::shared_ptr > GraphAndValues
Return type for load functions.
Definition: dataset.h:96
KernelFunctionType
Robust kernel type to wrap around quadratic noise model.
Definition: dataset.h:71
size_t number_cameras() const
The number of camera poses.
Definition: dataset.h:193
std::vector< gtsam::BetweenFactor< Pose3 >::shared_ptr > BetweenFactorPose3s
Parse edges in 3D TORO graph file into a set of BetweenFactors.
Definition: dataset.h:159
Definition: Pose2.h:36
3D Pose
A non-templated config holding any types of Manifold-group elements.
3D Point
A non-linear factor graph is a graph of non-Gaussian, i.e.
Definition: NonlinearFactorGraph.h:77
3D rotation represented as a rotation matrix or quaternion
std::vector< SfM_Track > tracks
Sparse set of points.
Definition: dataset.h:192
PinholeCamera< Cal3Bundler > SfM_Camera
Define the structure for the camera poses.
Definition: dataset.h:187
GraphAndValues load2D_robust(const string &filename, noiseModel::Base::shared_ptr &model, int maxID)
Definition: dataset.cpp:373
float b
RGB color of the 3D point.
Definition: dataset.h:178
size_t number_tracks() const
The number of reconstructed 3D points.
Definition: dataset.h:196
Global functions in a separate testing namespace.
Definition: chartTesting.h:28
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:635
noiseModel::Base::shared_ptr SharedNoiseModel
Note, deliberately not in noiseModel namespace.
Definition: NoiseModel.h:1072
Point3 p
3D position of the point
Definition: dataset.h:177
std::pair< size_t, size_t > SIFT_Index
SfM_Track.
Definition: dataset.h:172
Information matrix I11, I12, I13, I22, I23, I33.
Definition: dataset.h:63
bool writeBALfromValues(const string &filename, const SfM_data &data, Values &values)
This function writes a "Bundle Adjustment in the Large" (BAL) file from a SfM_data structure and a va...
Definition: dataset.cpp:869
Values initialCamerasAndPointsEstimate(const SfM_data &db)
This function creates initial values for cameras and points from db.
Definition: dataset.cpp:936
Values initialCamerasEstimate(const SfM_data &db)
This function creates initial values for cameras from db.
Definition: dataset.cpp:928
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:412
Information matrix, but inf_ff inf_fs inf_ss inf_rr inf_fr inf_sr.
Definition: dataset.h:64
bool writeBAL(const string &filename, SfM_data &data)
This function writes a "Bundle Adjustment in the Large" (BAL) file from a SfM_data structure.
Definition: dataset.cpp:796
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:88
std::map< Key, Pose3 > parse3DPoses(const string &filename)
Parse vertices in 3D TORO graph file into a map of Pose3s.
Definition: dataset.cpp:514
bool readBundler(const string &filename, SfM_data &data)
This function parses a bundler output file and stores the data into a SfM_data structure.
Definition: dataset.cpp:649
std::vector< SfM_Measurement > measurements
The 2D image projections (id,(u,v))
Definition: dataset.h:179
Typedefs for easier changing of types.
NoiseFormat
Indicates how noise parameters are stored in file.
Definition: dataset.h:62
std::vector< SfM_Camera > cameras
Set of cameras.
Definition: dataset.h:191