utility functions for loading datasets More...
#include <gtsam/sfm/BinaryMeasurement.h>
#include <gtsam/slam/BetweenFactor.h>
#include <gtsam/geometry/Cal3Bundler.h>
#include <gtsam/geometry/PinholeCamera.h>
#include <gtsam/geometry/Pose2.h>
#include <gtsam/geometry/Pose3.h>
#include <gtsam/nonlinear/NonlinearFactorGraph.h>
#include <gtsam/nonlinear/Values.h>
#include <gtsam/linear/NoiseModel.h>
#include <gtsam/base/serialization.h>
#include <gtsam/base/Testable.h>
#include <gtsam/base/types.h>
#include <boost/smart_ptr/shared_ptr.hpp>
#include <string>
#include <utility>
#include <vector>
#include <iosfwd>
#include <map>
Go to the source code of this file.
Classes | |
struct | gtsam::SfmData |
Define the structure for SfM data. More... | |
struct | gtsam::SfmTrack |
Define the structure for the 3D points. More... | |
struct | gtsam::traits< SfmData > |
traits More... | |
struct | gtsam::traits< SfmTrack > |
traits More... | |
Namespaces | |
gtsam | |
traits | |
Typedefs | |
using | gtsam::BetweenFactorPose2s = std::vector< BetweenFactor< Pose2 >::shared_ptr > |
using | gtsam::BetweenFactorPose3s = std::vector< BetweenFactor< Pose3 >::shared_ptr > |
using | gtsam::BinaryMeasurementsUnit3 = std::vector< BinaryMeasurement< Unit3 >> |
using | gtsam::GraphAndValues = std::pair< NonlinearFactorGraph::shared_ptr, Values::shared_ptr > |
typedef std::pair< std::pair< size_t, size_t >, Pose2 > | gtsam::IndexedEdge |
typedef std::pair< size_t, Point2 > | gtsam::IndexedLandmark |
typedef std::pair< size_t, Pose2 > | gtsam::IndexedPose |
Return type for auxiliary functions. More... | |
typedef PinholeCamera< Cal3Bundler > | gtsam::SfmCamera |
Define the structure for the camera poses. More... | |
typedef std::pair< size_t, Point2 > | gtsam::SfmMeasurement |
A measurement with its camera index. More... | |
typedef std::pair< size_t, size_t > | gtsam::SiftIndex |
Sift index for SfmTrack. More... | |
Enumerations | |
enum | gtsam::KernelFunctionType { gtsam::KernelFunctionTypeNONE, gtsam::KernelFunctionTypeHUBER, gtsam::KernelFunctionTypeTUKEY } |
Robust kernel type to wrap around quadratic noise model. More... | |
enum | gtsam::NoiseFormat { gtsam::NoiseFormatG2O, gtsam::NoiseFormatTORO, gtsam::NoiseFormatGRAPH, gtsam::NoiseFormatCOV, gtsam::NoiseFormatAUTO } |
Indicates how noise parameters are stored in file. More... | |
Functions | |
GTSAM_EXPORT std::string | gtsam::createRewrittenFileName (const std::string &name) |
GTSAM_EXPORT std::string | gtsam::findExampleDataFile (const std::string &name) |
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::initialCamerasAndPointsEstimate (const SfmData &db) |
This function creates initial values for cameras and points from db. More... | |
Values | gtsam::initialCamerasEstimate (const SfmData &db) |
This function creates initial values for cameras from db. More... | |
GTSAM_EXPORT GraphAndValues | gtsam::load2D (std::pair< std::string, SharedNoiseModel > dataset, size_t maxIndex=0, bool addNoise=false, bool smart=true, NoiseFormat noiseFormat=NoiseFormatAUTO, KernelFunctionType kernelFunctionType=KernelFunctionTypeNONE) |
GTSAM_EXPORT GraphAndValues | gtsam::load2D (const std::string &filename, SharedNoiseModel model=SharedNoiseModel(), size_t maxIndex=0, bool addNoise=false, bool smart=true, NoiseFormat noiseFormat=NoiseFormatAUTO, KernelFunctionType kernelFunctionType=KernelFunctionTypeNONE) |
GTSAM_EXPORT GraphAndValues | gtsam::load2D_robust (const std::string &filename, const noiseModel::Base::shared_ptr &model, size_t maxIndex=0) |
GTSAM_EXPORT GraphAndValues | gtsam::load3D (const std::string &filename) |
Load TORO 3D Graph. 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... | |
BetweenFactorPose2s | gtsam::parse2DFactors (const std::string &filename, const noiseModel::Diagonal::shared_ptr &model, size_t maxIndex) |
BetweenFactorPose3s | gtsam::parse3DFactors (const std::string &filename, const noiseModel::Diagonal::shared_ptr &model, size_t maxIndex) |
GTSAM_EXPORT boost::optional< IndexedEdge > | gtsam::parseEdge (std::istream &is, const std::string &tag) |
template<typename T > | |
GTSAM_EXPORT std::vector< typename BetweenFactor< T >::shared_ptr > | gtsam::parseFactors (const std::string &filename, const noiseModel::Diagonal::shared_ptr &model=nullptr, size_t maxIndex=0) |
template<typename T > | |
GTSAM_EXPORT std::vector< BinaryMeasurement< T > > | gtsam::parseMeasurements (const std::string &filename, const noiseModel::Diagonal::shared_ptr &model=nullptr, size_t maxIndex=0) |
template<typename T > | |
GTSAM_EXPORT std::map< size_t, T > | gtsam::parseVariables (const std::string &filename, size_t maxIndex=0) |
GTSAM_EXPORT boost::optional< IndexedLandmark > | gtsam::parseVertexLandmark (std::istream &is, const std::string &tag) |
GTSAM_EXPORT boost::optional< IndexedPose > | gtsam::parseVertexPose (std::istream &is, const std::string &tag) |
GTSAM_EXPORT bool | gtsam::readBAL (const std::string &filename, SfmData &data) |
This function parses a "Bundle Adjustment in the Large" (BAL) file and stores the data into a SfmData structure. More... | |
GTSAM_EXPORT SfmData | gtsam::readBal (const std::string &filename) |
This function parses a "Bundle Adjustment in the Large" (BAL) file and returns the data as a SfmData structure. Mainly used by wrapped code. More... | |
GTSAM_EXPORT bool | gtsam::readBundler (const std::string &filename, SfmData &data) |
This function parses a bundler output file and stores the data into a SfmData structure. More... | |
GTSAM_EXPORT 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... | |
GTSAM_EXPORT void | gtsam::save2D (const NonlinearFactorGraph &graph, const Values &config, const noiseModel::Diagonal::shared_ptr model, const std::string &filename) |
GTSAM_EXPORT bool | gtsam::writeBAL (const std::string &filename, SfmData &data) |
This function writes a "Bundle Adjustment in the Large" (BAL) file from a SfmData structure. More... | |
GTSAM_EXPORT bool | gtsam::writeBALfromValues (const std::string &filename, const SfmData &data, Values &values) |
This function writes a "Bundle Adjustment in the Large" (BAL) file from a SfmData structure and a value structure (measurements are the same as the SfM input data, while camera poses and values are read from Values) More... | |
GTSAM_EXPORT 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... | |