Go to the documentation of this file.
95 GTSAM_EXPORT std::vector<BinaryMeasurement<T>>
104 template <
typename T>
105 GTSAM_EXPORT std::vector<typename BetweenFactor<T>::shared_ptr>
108 size_t maxIndex = 0);
120 GTSAM_EXPORT std::optional<IndexedPose>
parseVertexPose(std::istream& is,
121 const std::string& tag);
129 const std::string& tag);
136 GTSAM_EXPORT std::optional<IndexedEdge>
parseEdge(std::istream& is,
137 const std::string& tag);
143 std::pair<NonlinearFactorGraph::shared_ptr, Values::shared_ptr>;
153 std::pair<std::string, SharedNoiseModel>
dataset,
size_t maxIndex = 0,
154 bool addNoise =
false,
172 size_t maxIndex = 0,
bool addNoise =
false,
bool smart =
true,
190 readG2o(
const std::string& g2oFile,
const bool is3D =
false,
216 size_t maxIndex = 0);
222 size_t maxIndex = 0);
@ NoiseFormatTORO
Information matrix, but inf_ff inf_fs inf_ss inf_rr inf_fr inf_sr.
std::vector< BinaryMeasurement< Unit3 > > BinaryMeasurementsUnit3
GTSAM_EXPORT std::string createRewrittenFileName(const std::string &name)
Annotation for function names.
std::pair< NonlinearFactorGraph::shared_ptr, Values::shared_ptr > GraphAndValues
std::pair< size_t, Pose2 > IndexedPose
Return type for auxiliary functions.
@ NoiseFormatGRAPH
default: toro-style order, but covariance matrix !
@ NoiseFormatCOV
Covariance matrix C11, C12, C13, C22, C23, C33.
std::pair< size_t, Point2 > IndexedLandmark
Typedefs for easier changing of types.
Concept check for values that can be used in unit tests.
@ NoiseFormatG2O
Information matrix I11, I12, I13, I22, I23, I33.
BetweenFactorPose3s parse3DFactors(const std::string &filename, const noiseModel::Diagonal::shared_ptr &model, size_t maxIndex)
GraphAndValues readG2o(const std::string &g2oFile, const bool is3D, KernelFunctionType kernelFunctionType)
This function parses a g2o file and stores the measurements into a NonlinearFactorGraph and the initi...
std::vector< BinaryMeasurement< Point3 > > BinaryMeasurementsPoint3
std::pair< std::pair< size_t, size_t >, Pose2 > IndexedEdge
NoiseFormat
Indicates how noise parameters are stored in file.
std::optional< IndexedPose > parseVertexPose(std::istream &is, const std::string &tag)
@ KernelFunctionTypeHUBER
Base class for all pinhole cameras.
KernelFunctionType
Robust kernel type to wrap around quadratic noise model.
GTSAM_EXPORT std::vector< typename BetweenFactor< T >::shared_ptr > parseFactors(const std::string &filename, const noiseModel::Diagonal::shared_ptr &model=nullptr, size_t maxIndex=0)
noiseModel::Base::shared_ptr SharedNoiseModel
noiseModel::Diagonal::shared_ptr model
BetweenFactorPose2s parse2DFactors(const std::string &filename, const noiseModel::Diagonal::shared_ptr &model, size_t maxIndex)
Data structure for dealing with Structure from Motion data.
GraphAndValues load2D(const std::string &filename, SharedNoiseModel model, size_t maxIndex, bool addNoise, bool smart, NoiseFormat noiseFormat, KernelFunctionType kernelFunctionType)
std::vector< BetweenFactor< Pose3 >::shared_ptr > BetweenFactorPose3s
@ KernelFunctionTypeTUKEY
Factor Graph consisting of non-linear factors.
Binary measurement represents a measurement between two keys in a graph. A binary measurement is simi...
void save2D(const NonlinearFactorGraph &graph, const Values &config, const noiseModel::Diagonal::shared_ptr model, const std::string &filename)
std::shared_ptr< Diagonal > shared_ptr
std::vector< BetweenFactor< Pose2 >::shared_ptr > BetweenFactorPose2s
static std::map< timestep_t, std::vector< stereo_meas_t > > dataset
std::optional< IndexedEdge > parseEdge(std::istream &is, const std::string &tag)
GTSAM_EXPORT std::string findExampleDataFile(const std::string &name)
NonlinearFactorGraph graph
GTSAM_EXPORT std::map< size_t, T > parseVariables(const std::string &filename, size_t maxIndex=0)
GraphAndValues load3D(const std::string &filename)
Load TORO 3D Graph.
GTSAM_EXPORT std::vector< BinaryMeasurement< Pose2 > > parseMeasurements(const std::string &filename, const noiseModel::Diagonal::shared_ptr &model, size_t maxIndex)
@ NoiseFormatAUTO
Try to guess covariance matrix layout.
std::optional< IndexedLandmark > parseVertexLandmark(std::istream &is, const std::string &tag)
Calibration used by Bundler.
std::vector< BinaryMeasurement< Rot3 > > BinaryMeasurementsRot3
A non-templated config holding any types of Manifold-group elements.
void writeG2o(const NonlinearFactorGraph &graph, const Values &estimate, const std::string &filename)
This function writes a g2o file from NonlinearFactorGraph and a Values structure.
gtsam
Author(s):
autogenerated on Fri Nov 1 2024 03:32:22