gtsam  4.0.0
gtsam
dataset.h File Reference

utility functions for loading datasets More...

Go to the source code of this file.

Classes

struct  gtsam::SfM_Track
 Define the structure for the 3D points. More...
 
struct  gtsam::SfM_data
 Define the structure for SfM data. More...
 

Namespaces

 gtsam
 Global functions in a separate testing namespace.
 

Typedefs

typedef std::pair< Key, Pose2 > gtsam::IndexedPose
 Return type for auxiliary functions.
 
typedef std::pair< std::pair< Key, Key >, Pose2 > gtsam::IndexedEdge
 
typedef std::pair< NonlinearFactorGraph::shared_ptr, Values::shared_ptr > gtsam::GraphAndValues
 Return type for load functions.
 
using gtsam::BetweenFactorPose3s = std::vector< gtsam::BetweenFactor< Pose3 >::shared_ptr >
 Parse edges in 3D TORO graph file into a set of BetweenFactors.
 
typedef std::pair< size_t, Point2 > gtsam::SfM_Measurement
 A measurement with its camera index.
 
typedef std::pair< size_t, size_t > gtsam::SIFT_Index
 SfM_Track.
 
typedef PinholeCamera< Cal3Bundler > gtsam::SfM_Camera
 Define the structure for the camera poses.
 

Enumerations

enum  gtsam::NoiseFormat {
  gtsam::NoiseFormatG2O, gtsam::NoiseFormatTORO, gtsam::NoiseFormatGRAPH, gtsam::NoiseFormatCOV,
  gtsam::NoiseFormatAUTO
}
 Indicates how noise parameters are stored in file. More...
 
enum  gtsam::KernelFunctionType { KernelFunctionTypeNONE, KernelFunctionTypeHUBER, KernelFunctionTypeTUKEY }
 Robust kernel type to wrap around quadratic noise model.
 

Functions

string gtsam::findExampleDataFile (const std::string &name)
 Find the full path to an example dataset distributed with gtsam. More...
 
string gtsam::createRewrittenFileName (const std::string &name)
 Creates a temporary file name that needs to be ignored in .gitingnore for checking read-write oprations.
 
boost::optional< IndexedPose > gtsam::parseVertex (std::istream &is, const std::string &tag)
 Parse TORO/G2O vertex "id x y yaw". More...
 
boost::optional< IndexedEdge > gtsam::parseEdge (std::istream &is, const std::string &tag)
 Parse TORO/G2O edge "id1 id2 x y yaw". More...
 
GTSAM_EXPORT GraphAndValues gtsam::load2D (std::pair< std::string, SharedNoiseModel > dataset, int maxID=0, bool addNoise=false, bool smart=true, NoiseFormat noiseFormat=NoiseFormatAUTO, KernelFunctionType kernelFunctionType=KernelFunctionTypeNONE)
 Load TORO 2D Graph. More...
 
GraphAndValues gtsam::load2D (const std::string &filename, SharedNoiseModel model=SharedNoiseModel(), Key maxID=0, bool addNoise=false, bool smart=true, NoiseFormat noiseFormat=NoiseFormatAUTO, KernelFunctionType kernelFunctionType=KernelFunctionTypeNONE)
 Load TORO/G2O style graph files. More...
 
GraphAndValues gtsam::load2D_robust (const string &filename, noiseModel::Base::shared_ptr &model, int maxID)
 
void gtsam::save2D (const NonlinearFactorGraph &graph, const Values &config, const noiseModel::Diagonal::shared_ptr model, const std::string &filename)
 save 2d graph
 
GraphAndValues gtsam::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 initial guess in a Values structure. More...
 
void gtsam::writeG2o (const NonlinearFactorGraph &graph, const Values &estimate, const std::string &filename)
 This function writes a g2o file from NonlinearFactorGraph and a Values structure. More...
 
BetweenFactorPose3s gtsam::parse3DFactors (const string &filename)
 
std::map< Key, Pose3 > gtsam::parse3DPoses (const std::string &filename)
 Parse vertices in 3D TORO graph file into a map of Pose3s.
 
GraphAndValues gtsam::load3D (const std::string &filename)
 Load TORO 3D Graph.
 
bool gtsam::readBundler (const std::string &filename, SfM_data &data)
 This function parses a bundler output file and stores the data into a SfM_data structure. More...
 
bool gtsam::readBAL (const std::string &filename, SfM_data &data)
 This function parses a "Bundle Adjustment in the Large" (BAL) file and stores the data into a SfM_data structure. More...
 
bool gtsam::writeBAL (const std::string &filename, SfM_data &data)
 This function writes a "Bundle Adjustment in the Large" (BAL) file from a SfM_data structure. More...
 
bool gtsam::writeBALfromValues (const std::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 value structure (measurements are the same as the SfM input data, while camera poses and values are read from Values) More...
 
Pose3 gtsam::openGL2gtsam (const Rot3 &R, double tx, double ty, double tz)
 This function converts an openGL camera pose to an GTSAM camera pose. More...
 
Pose3 gtsam::gtsam2openGL (const Rot3 &R, double tx, double ty, double tz)
 This function converts a GTSAM camera pose to an openGL camera pose. More...
 
Pose3 gtsam::gtsam2openGL (const Pose3 &PoseGTSAM)
 This function converts a GTSAM camera pose to an openGL camera pose. More...
 
Values gtsam::initialCamerasEstimate (const SfM_data &db)
 This function creates initial values for cameras from db. More...
 
Values gtsam::initialCamerasAndPointsEstimate (const SfM_data &db)
 This function creates initial values for cameras and points from db. More...
 

Detailed Description

utility functions for loading datasets

Date
Jan 22, 2010
Author
nikai, Luca Carlone