Namespaces | Typedefs | Enumerations | Functions
dataset.h File Reference

utility functions for loading datasets More...

#include <gtsam/sfm/BinaryMeasurement.h>
#include <gtsam/slam/BetweenFactor.h>
#include <gtsam/sfm/SfmData.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/Testable.h>
#include <gtsam/base/types.h>
#include <string>
#include <utility>
#include <vector>
#include <iosfwd>
#include <map>
#include <optional>
Include dependency graph for dataset.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Namespaces

 gtsam
 traits
 

Typedefs

using gtsam::BetweenFactorPose2s = list
 
using gtsam::BetweenFactorPose3s = list
 
using gtsam::BinaryMeasurementsPoint3 = list
 
using gtsam::BinaryMeasurementsRot3 = list
 
using gtsam::BinaryMeasurementsUnit3 = list
 
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...
 

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)
 
GraphAndValues gtsam::load2D (const std::string &filename, SharedNoiseModel model, size_t maxIndex, bool addNoise, bool smart, NoiseFormat noiseFormat, KernelFunctionType kernelFunctionType)
 
GraphAndValues gtsam::load2D (std::pair< std::string, SharedNoiseModel > dataset, size_t maxIndex, bool addNoise, bool smart, NoiseFormat noiseFormat, KernelFunctionType kernelFunctionType)
 
GraphAndValues gtsam::load3D (const std::string &filename)
 Load TORO 3D Graph. 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)
 
std::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, Tgtsam::parseVariables (const std::string &filename, size_t maxIndex=0)
 
std::optional< IndexedLandmark > gtsam::parseVertexLandmark (std::istream &is, const std::string &tag)
 
std::optional< IndexedPose > gtsam::parseVertexPose (std::istream &is, const std::string &tag)
 
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::save2D (const NonlinearFactorGraph &graph, const Values &config, const noiseModel::Diagonal::shared_ptr model, const std::string &filename)
 
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...
 

Detailed Description

utility functions for loading datasets

Date
Jan 22, 2010
Author
Ni Kai
Luca Carlone
Varun Agrawal

Definition in file dataset.h.



gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:40:48