33 #include <boost/smart_ptr/shared_ptr.hpp> 72 KernelFunctionTypeNONE, KernelFunctionTypeHUBER, KernelFunctionTypeTUKEY
77 typedef std::pair<std::pair<Key, Key>,
Pose2> IndexedEdge;
84 GTSAM_EXPORT boost::optional<IndexedPose>
parseVertex(std::istream& is,
85 const std::string& tag);
92 GTSAM_EXPORT boost::optional<IndexedEdge>
parseEdge(std::istream& is,
93 const std::string& tag);
96 typedef std::pair<NonlinearFactorGraph::shared_ptr, Values::shared_ptr>
GraphAndValues;
106 std::pair<std::string, SharedNoiseModel> dataset,
int maxID = 0,
107 bool addNoise =
false,
130 noiseModel::Base::shared_ptr& model,
int maxID = 0);
134 const Values& config,
const noiseModel::Diagonal::shared_ptr model,
135 const std::string& filename);
156 const Values& estimate,
const std::string& filename);
163 GTSAM_EXPORT std::map<Key, Pose3>
parse3DPoses(
const std::string& filename);
180 std::vector<SIFT_Index> siftIndices;
181 size_t number_measurements()
const {
208 GTSAM_EXPORT
bool readBundler(
const std::string& filename, SfM_data &data);
217 GTSAM_EXPORT
bool readBAL(
const std::string& filename, SfM_data &data);
226 GTSAM_EXPORT
bool writeBAL(
const std::string& filename, SfM_data &data);
240 const SfM_data &data, Values& values);
250 GTSAM_EXPORT Pose3
openGL2gtsam(
const Rot3& R,
double tx,
double ty,
double tz);
260 GTSAM_EXPORT Pose3
gtsam2openGL(
const Rot3& R,
double tx,
double ty,
double tz);
267 GTSAM_EXPORT Pose3
gtsam2openGL(
const Pose3& PoseGTSAM);
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
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
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
A non-templated config holding any types of Manifold-group elements.
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