|
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) |
|
string | gtsam::createRewrittenFileName (const string &name) |
|
boost::shared_ptr< Sampler > | gtsam::createSampler (const SharedNoiseModel &model) |
|
string | gtsam::findExampleDataFile (const 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...
|
|
GraphAndValues | gtsam::load2D (const string &filename, SharedNoiseModel model, size_t maxIndex, bool addNoise, bool smart, NoiseFormat noiseFormat, KernelFunctionType kernelFunctionType) |
|
GraphAndValues | gtsam::load2D (pair< string, SharedNoiseModel > dataset, size_t maxIndex, bool addNoise, bool smart, NoiseFormat noiseFormat, KernelFunctionType kernelFunctionType) |
|
GraphAndValues | gtsam::load2D_robust (const string &filename, const noiseModel::Base::shared_ptr &model, size_t maxIndex) |
|
GraphAndValues | gtsam::load3D (const 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...
|
|
Rot3 | gtsam::openGLFixedRotation () |
|
istream & | gtsam::operator>> (istream &is, Quaternion &q) |
|
istream & | gtsam::operator>> (istream &is, Rot3 &R) |
|
istream & | gtsam::operator>> (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) |
|
boost::optional< IndexedEdge > | gtsam::parseEdge (istream &is, const string &tag) |
|
template<> |
std::vector< BetweenFactor< Pose2 >::shared_ptr > | gtsam::parseFactors< Pose2 > (const std::string &filename, const noiseModel::Diagonal::shared_ptr &model, size_t maxIndex) |
|
template<> |
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 string &filename, Parser< T > parse) |
|
template<> |
std::vector< BinaryMeasurement< Pose2 > > | gtsam::parseMeasurements (const std::string &filename, const noiseModel::Diagonal::shared_ptr &model, size_t maxIndex) |
|
template<> |
std::vector< BinaryMeasurement< Rot2 > > | gtsam::parseMeasurements (const std::string &filename, const noiseModel::Diagonal::shared_ptr &model, size_t maxIndex) |
|
template<> |
std::vector< BinaryMeasurement< Pose3 > > | gtsam::parseMeasurements (const std::string &filename, const noiseModel::Diagonal::shared_ptr &model, size_t maxIndex) |
|
template<> |
std::vector< BinaryMeasurement< Rot3 > > | gtsam::parseMeasurements (const std::string &filename, const noiseModel::Diagonal::shared_ptr &model, size_t maxIndex) |
|
template<typename T > |
map< size_t, T > | gtsam::parseToMap (const string &filename, Parser< pair< size_t, T >> parse, size_t maxIndex) |
|
template<typename T > |
static vector< T > | gtsam::parseToVector (const string &filename, Parser< T > parse) |
|
template<> |
std::map< size_t, Point2 > | gtsam::parseVariables< Point2 > (const std::string &filename, size_t maxIndex) |
|
template<> |
std::map< size_t, Point3 > | gtsam::parseVariables< Point3 > (const std::string &filename, size_t maxIndex) |
|
template<> |
std::map< size_t, Pose2 > | gtsam::parseVariables< Pose2 > (const std::string &filename, size_t maxIndex) |
|
template<> |
std::map< size_t, Pose3 > | gtsam::parseVariables< Pose3 > (const std::string &filename, size_t maxIndex) |
|
boost::optional< IndexedLandmark > | gtsam::parseVertexLandmark (istream &is, const string &tag) |
|
boost::optional< pair< size_t, Point3 > > | gtsam::parseVertexPoint3 (istream &is, const string &tag) |
|
boost::optional< IndexedPose > | gtsam::parseVertexPose (istream &is, const string &tag) |
|
boost::optional< pair< size_t, Pose3 > > | gtsam::parseVertexPose3 (istream &is, const string &tag) |
|
bool | gtsam::readBAL (const string &filename, SfmData &data) |
| This function parses a "Bundle Adjustment in the Large" (BAL) file and stores the data into a SfmData structure. More...
|
|
SfmData | gtsam::readBal (const 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...
|
|
bool | gtsam::readBundler (const string &filename, SfmData &data) |
| This function parses a bundler output file and stores the data into a SfmData structure. More...
|
|
GraphAndValues | gtsam::readG2o (const string &g2oFile, const bool is3D, KernelFunctionType kernelFunctionType) |
| 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 string &filename) |
|
bool | gtsam::writeBAL (const string &filename, SfmData &data) |
| This function writes a "Bundle Adjustment in the Large" (BAL) file from a SfmData structure. More...
|
|
bool | gtsam::writeBALfromValues (const 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...
|
|
void | gtsam::writeG2o (const NonlinearFactorGraph &graph, const Values &estimate, const string &filename) |
| This function writes a g2o file from NonlinearFactorGraph and a Values structure. More...
|
|
utility functions for loading datasets
- Date
- Jan 22, 2010
- Author
- Kai Ni
-
Luca Carlone
-
Frank Dellaert
-
Varun Agrawal
Definition in file dataset.cpp.