Classes | Namespaces | Macros | Typedefs | Functions
dataset.cpp File Reference

utility functions for loading datasets More...

#include <gtsam/sam/BearingRangeFactor.h>
#include <gtsam/slam/BetweenFactor.h>
#include <gtsam/slam/dataset.h>
#include <gtsam/geometry/Point3.h>
#include <gtsam/geometry/Pose2.h>
#include <gtsam/geometry/Rot3.h>
#include <gtsam/nonlinear/NonlinearFactor.h>
#include <gtsam/nonlinear/Values-inl.h>
#include <gtsam/linear/Sampler.h>
#include <gtsam/inference/FactorGraph.h>
#include <gtsam/inference/Symbol.h>
#include <gtsam/base/GenericValue.h>
#include <gtsam/base/Lie.h>
#include <gtsam/base/Matrix.h>
#include <gtsam/base/Value.h>
#include <gtsam/base/Vector.h>
#include <gtsam/base/types.h>
#include <optional>
#include <cmath>
#include <fstream>
#include <iostream>
#include <stdexcept>
#include <string>
#include <filesystem>
Include dependency graph for dataset.cpp:

Go to the source code of this file.

Classes

struct  gtsam::ParseFactor< T >
 
struct  gtsam::ParseMeasurement< T >
 
struct  gtsam::ParseMeasurement< BearingRange2D >
 
struct  gtsam::ParseMeasurement< Pose2 >
 
struct  gtsam::ParseMeasurement< Pose3 >
 

Namespaces

 gtsam
 traits
 

Macros

#define LINESIZE   81920
 

Typedefs

using gtsam::BearingRange2D = BearingRange< Pose2, Point2 >
 
template<typename T >
using gtsam::Parser = std::function< std::optional< T >(std::istream &is, const std::string &tag)>
 

Functions

static BinaryMeasurement< Rot2 > gtsam::convert (const BinaryMeasurement< Pose2 > &p)
 
static BinaryMeasurement< Rot3 > gtsam::convert (const BinaryMeasurement< Pose3 > &p)
 
static SharedNoiseModel gtsam::createNoiseModel (const Vector6 &v, bool smart, NoiseFormat noiseFormat, KernelFunctionType kernelFunctionType)
 
GTSAM_EXPORT std::string gtsam::createRewrittenFileName (const std::string &name)
 
std::shared_ptr< Sampler > gtsam::createSampler (const SharedNoiseModel &model)
 
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::load2D_robust (const std::string &filename, const noiseModel::Base::shared_ptr &model, size_t maxIndex)
 
GraphAndValues gtsam::load3D (const std::string &filename)
 Load TORO 3D Graph. More...
 
std::istream & gtsam::operator>> (std::istream &is, Quaternion &q)
 
std::istream & gtsam::operator>> (std::istream &is, Rot3 &R)
 
std::istream & gtsam::operator>> (std::istream &is, Matrix6 &m)
 
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<>
GTSAM_EXPORT std::vector< BetweenFactor< Pose2 >::shared_ptr > gtsam::parseFactors< Pose2 > (const std::string &filename, const noiseModel::Diagonal::shared_ptr &model, size_t maxIndex)
 
template<>
GTSAM_EXPORT std::vector< BetweenFactor< Pose3 >::shared_ptr > gtsam::parseFactors< Pose3 > (const std::string &filename, const noiseModel::Diagonal::shared_ptr &model, size_t maxIndex)
 
template<typename T >
static void gtsam::parseLines (const std::string &filename, Parser< T > parse)
 
template<>
GTSAM_EXPORT std::vector< BinaryMeasurement< Pose2 > > gtsam::parseMeasurements (const std::string &filename, const noiseModel::Diagonal::shared_ptr &model, size_t maxIndex)
 
template<>
GTSAM_EXPORT std::vector< BinaryMeasurement< Rot2 > > gtsam::parseMeasurements (const std::string &filename, const noiseModel::Diagonal::shared_ptr &model, size_t maxIndex)
 
template<>
GTSAM_EXPORT std::vector< BinaryMeasurement< Pose3 > > gtsam::parseMeasurements (const std::string &filename, const noiseModel::Diagonal::shared_ptr &model, size_t maxIndex)
 
template<>
GTSAM_EXPORT std::vector< BinaryMeasurement< Rot3 > > gtsam::parseMeasurements (const std::string &filename, const noiseModel::Diagonal::shared_ptr &model, size_t maxIndex)
 
template<typename T >
std::map< size_t, Tgtsam::parseToMap (const std::string &filename, Parser< std::pair< size_t, T >> parse, size_t maxIndex)
 
template<typename T >
static std::vector< Tgtsam::parseToVector (const std::string &filename, Parser< T > parse)
 
template<>
GTSAM_EXPORT std::map< size_t, Point2 > gtsam::parseVariables< Point2 > (const std::string &filename, size_t maxIndex)
 
template<>
GTSAM_EXPORT std::map< size_t, Point3 > gtsam::parseVariables< Point3 > (const std::string &filename, size_t maxIndex)
 
template<>
GTSAM_EXPORT std::map< size_t, Pose2 > gtsam::parseVariables< Pose2 > (const std::string &filename, size_t maxIndex)
 
template<>
GTSAM_EXPORT std::map< size_t, Pose3gtsam::parseVariables< Pose3 > (const std::string &filename, size_t maxIndex)
 
std::optional< IndexedLandmark > gtsam::parseVertexLandmark (std::istream &is, const std::string &tag)
 
std::optional< std::pair< size_t, Point3 > > gtsam::parseVertexPoint3 (std::istream &is, const std::string &tag)
 
std::optional< IndexedPose > gtsam::parseVertexPose (std::istream &is, const std::string &tag)
 
std::optional< std::pair< size_t, Pose3 > > gtsam::parseVertexPose3 (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
Kai Ni
Luca Carlone
Frank Dellaert
Varun Agrawal

Definition in file dataset.cpp.

Macro Definition Documentation

◆ LINESIZE

#define LINESIZE   81920

Definition at line 65 of file dataset.cpp.



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