2010-10-14 12:54:38 +08:00
|
|
|
/* ----------------------------------------------------------------------------
|
|
|
|
|
|
2016-02-11 09:48:52 +08:00
|
|
|
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
2010-10-14 12:54:38 +08:00
|
|
|
* Atlanta, Georgia 30332-0415
|
|
|
|
|
* All Rights Reserved
|
|
|
|
|
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
|
|
|
|
|
|
|
|
|
* See LICENSE for the license information
|
|
|
|
|
|
|
|
|
|
* -------------------------------------------------------------------------- */
|
|
|
|
|
|
2011-10-14 11:23:14 +08:00
|
|
|
/**
|
|
|
|
|
* @file dataset.h
|
|
|
|
|
* @date Jan 22, 2010
|
2020-03-07 07:31:30 +08:00
|
|
|
* @author Ni Kai
|
|
|
|
|
* @author Luca Carlone
|
|
|
|
|
* @author Varun Agrawal
|
2011-10-14 11:23:14 +08:00
|
|
|
* @brief utility functions for loading datasets
|
2010-01-23 04:18:40 +08:00
|
|
|
*/
|
|
|
|
|
|
|
|
|
|
#pragma once
|
|
|
|
|
|
2019-03-14 13:25:06 +08:00
|
|
|
#include <gtsam/slam/BetweenFactor.h>
|
2013-10-18 09:25:16 +08:00
|
|
|
#include <gtsam/geometry/Cal3Bundler.h>
|
2013-10-18 09:25:13 +08:00
|
|
|
#include <gtsam/geometry/PinholeCamera.h>
|
2020-08-13 07:41:56 +08:00
|
|
|
#include <gtsam/geometry/Pose2.h>
|
2015-06-08 11:24:45 +08:00
|
|
|
#include <gtsam/geometry/Pose3.h>
|
|
|
|
|
#include <gtsam/nonlinear/NonlinearFactorGraph.h>
|
|
|
|
|
#include <gtsam/nonlinear/Values.h>
|
|
|
|
|
#include <gtsam/linear/NoiseModel.h>
|
|
|
|
|
#include <gtsam/base/types.h>
|
2012-07-28 03:02:11 +08:00
|
|
|
|
2015-06-08 11:24:45 +08:00
|
|
|
#include <boost/smart_ptr/shared_ptr.hpp>
|
2012-06-04 02:20:48 +08:00
|
|
|
#include <string>
|
2015-06-08 11:24:45 +08:00
|
|
|
#include <utility> // for pair
|
|
|
|
|
#include <vector>
|
2017-08-08 15:39:22 +08:00
|
|
|
#include <iosfwd>
|
2019-03-14 13:25:06 +08:00
|
|
|
#include <map>
|
2010-01-23 04:18:40 +08:00
|
|
|
|
2012-06-04 02:20:48 +08:00
|
|
|
namespace gtsam {
|
2010-01-23 04:18:40 +08:00
|
|
|
|
2013-10-18 09:25:13 +08:00
|
|
|
/**
|
|
|
|
|
* Find the full path to an example dataset distributed with gtsam. The name
|
|
|
|
|
* may be specified with or without a file extension - if no extension is
|
2014-06-01 03:53:41 +08:00
|
|
|
* given, this function first looks for the .graph extension, then .txt. We
|
2013-10-18 09:25:13 +08:00
|
|
|
* first check the gtsam source tree for the file, followed by the installed
|
|
|
|
|
* example dataset location. Both the source tree and installed locations
|
|
|
|
|
* are obtained from CMake during compilation.
|
|
|
|
|
* @return The full path and filename to the requested dataset.
|
|
|
|
|
* @throw std::invalid_argument if no matching file could be found using the
|
|
|
|
|
* search process described above.
|
|
|
|
|
*/
|
|
|
|
|
GTSAM_EXPORT std::string findExampleDataFile(const std::string& name);
|
2014-06-01 03:53:41 +08:00
|
|
|
|
|
|
|
|
/**
|
2014-06-01 04:13:29 +08:00
|
|
|
* Creates a temporary file name that needs to be ignored in .gitingnore
|
|
|
|
|
* for checking read-write oprations
|
2014-06-01 03:53:41 +08:00
|
|
|
*/
|
|
|
|
|
GTSAM_EXPORT std::string createRewrittenFileName(const std::string& name);
|
2012-08-28 23:00:50 +08:00
|
|
|
|
2014-06-01 09:57:29 +08:00
|
|
|
/// Indicates how noise parameters are stored in file
|
|
|
|
|
enum NoiseFormat {
|
2014-06-01 23:46:23 +08:00
|
|
|
NoiseFormatG2O, ///< Information matrix I11, I12, I13, I22, I23, I33
|
|
|
|
|
NoiseFormatTORO, ///< Information matrix, but inf_ff inf_fs inf_ss inf_rr inf_fr inf_sr
|
2014-06-01 10:42:14 +08:00
|
|
|
NoiseFormatGRAPH, ///< default: toro-style order, but covariance matrix !
|
2014-10-23 05:49:18 +08:00
|
|
|
NoiseFormatCOV, ///< Covariance matrix C11, C12, C13, C22, C23, C33
|
|
|
|
|
NoiseFormatAUTO ///< Try to guess covariance matrix layout
|
2014-06-01 09:57:29 +08:00
|
|
|
};
|
|
|
|
|
|
2014-06-01 23:46:23 +08:00
|
|
|
/// Robust kernel type to wrap around quadratic noise model
|
2014-06-01 09:57:29 +08:00
|
|
|
enum KernelFunctionType {
|
2014-06-01 23:46:23 +08:00
|
|
|
KernelFunctionTypeNONE, KernelFunctionTypeHUBER, KernelFunctionTypeTUKEY
|
2014-06-01 09:57:29 +08:00
|
|
|
};
|
|
|
|
|
|
2018-05-14 15:39:36 +08:00
|
|
|
/// Return type for auxiliary functions
|
|
|
|
|
typedef std::pair<Key, Pose2> IndexedPose;
|
2020-07-11 14:52:34 +08:00
|
|
|
typedef std::pair<Key, Point2> IndexedLandmark;
|
2018-05-14 15:39:36 +08:00
|
|
|
typedef std::pair<std::pair<Key, Key>, Pose2> IndexedEdge;
|
|
|
|
|
|
2020-07-25 00:37:58 +08:00
|
|
|
#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V41
|
2018-05-14 15:39:36 +08:00
|
|
|
/**
|
|
|
|
|
* Parse TORO/G2O vertex "id x y yaw"
|
|
|
|
|
* @param is input stream
|
|
|
|
|
* @param tag string parsed from input stream, will only parse if vertex type
|
|
|
|
|
*/
|
|
|
|
|
GTSAM_EXPORT boost::optional<IndexedPose> parseVertex(std::istream& is,
|
|
|
|
|
const std::string& tag);
|
2020-07-25 00:37:58 +08:00
|
|
|
#endif
|
|
|
|
|
|
2018-05-14 15:39:36 +08:00
|
|
|
/**
|
|
|
|
|
* Parse TORO/G2O vertex "id x y yaw"
|
|
|
|
|
* @param is input stream
|
|
|
|
|
* @param tag string parsed from input stream, will only parse if vertex type
|
|
|
|
|
*/
|
2020-07-11 14:52:34 +08:00
|
|
|
GTSAM_EXPORT boost::optional<IndexedPose> parseVertexPose(std::istream& is,
|
2018-05-14 15:39:36 +08:00
|
|
|
const std::string& tag);
|
|
|
|
|
|
2020-07-11 14:52:34 +08:00
|
|
|
/**
|
|
|
|
|
* Parse G2O landmark vertex "id x y"
|
|
|
|
|
* @param is input stream
|
|
|
|
|
* @param tag string parsed from input stream, will only parse if vertex type
|
|
|
|
|
*/
|
|
|
|
|
|
|
|
|
|
GTSAM_EXPORT boost::optional<IndexedLandmark> parseVertexLandmark(std::istream& is,
|
2020-07-24 16:10:03 +08:00
|
|
|
const std::string& tag);
|
2018-05-14 15:39:36 +08:00
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
* Parse TORO/G2O edge "id1 id2 x y yaw"
|
|
|
|
|
* @param is input stream
|
|
|
|
|
* @param tag string parsed from input stream, will only parse if edge type
|
|
|
|
|
*/
|
|
|
|
|
GTSAM_EXPORT boost::optional<IndexedEdge> parseEdge(std::istream& is,
|
|
|
|
|
const std::string& tag);
|
|
|
|
|
|
2020-08-13 07:41:56 +08:00
|
|
|
using BetweenFactorPose2s =
|
|
|
|
|
std::vector<gtsam::BetweenFactor<Pose2>::shared_ptr>;
|
|
|
|
|
|
|
|
|
|
/// Parse edges in 2D g2o graph file into a set of BetweenFactors.
|
|
|
|
|
GTSAM_EXPORT BetweenFactorPose2s parse2DFactors(
|
|
|
|
|
const std::string &filename,
|
|
|
|
|
const noiseModel::Diagonal::shared_ptr &corruptingNoise = nullptr);
|
|
|
|
|
|
|
|
|
|
/// Parse vertices in 2D g2o graph file into a map of Pose2s.
|
|
|
|
|
GTSAM_EXPORT std::map<Key, Pose2> parse2DPoses(const std::string &filename,
|
|
|
|
|
Key maxNr = 0);
|
|
|
|
|
|
|
|
|
|
/// Parse landmarks in 2D g2o graph file into a map of Point2s.
|
|
|
|
|
GTSAM_EXPORT std::map<Key, Point2> parse2DLandmarks(const string &filename,
|
|
|
|
|
Key maxNr = 0);
|
|
|
|
|
|
2014-06-01 23:46:23 +08:00
|
|
|
/// Return type for load functions
|
2020-08-13 07:41:56 +08:00
|
|
|
using GraphAndValues =
|
|
|
|
|
std::pair<NonlinearFactorGraph::shared_ptr, Values::shared_ptr>;
|
2014-06-01 23:46:23 +08:00
|
|
|
|
2013-10-18 09:25:13 +08:00
|
|
|
/**
|
|
|
|
|
* Load TORO 2D Graph
|
|
|
|
|
* @param dataset/model pair as constructed by [dataset]
|
2020-08-13 07:41:56 +08:00
|
|
|
* @param maxNr if non-zero cut out vertices >= maxNr
|
2013-10-18 09:25:13 +08:00
|
|
|
* @param addNoise add noise to the edges
|
|
|
|
|
* @param smart try to reduce complexity of covariance to cheapest model
|
|
|
|
|
*/
|
2014-06-01 23:46:23 +08:00
|
|
|
GTSAM_EXPORT GraphAndValues load2D(
|
2020-08-13 07:41:56 +08:00
|
|
|
std::pair<std::string, SharedNoiseModel> dataset, Key maxNr = 0,
|
2014-06-01 09:57:29 +08:00
|
|
|
bool addNoise = false,
|
|
|
|
|
bool smart = true, //
|
2014-10-23 05:49:18 +08:00
|
|
|
NoiseFormat noiseFormat = NoiseFormatAUTO,
|
2014-06-01 23:46:23 +08:00
|
|
|
KernelFunctionType kernelFunctionType = KernelFunctionTypeNONE);
|
2013-10-18 09:25:13 +08:00
|
|
|
|
|
|
|
|
/**
|
2014-06-01 23:46:23 +08:00
|
|
|
* Load TORO/G2O style graph files
|
2013-10-18 09:25:13 +08:00
|
|
|
* @param filename
|
|
|
|
|
* @param model optional noise model to use instead of one specified by file
|
2020-08-13 07:41:56 +08:00
|
|
|
* @param maxNr if non-zero cut out vertices >= maxNr
|
2013-10-18 09:25:13 +08:00
|
|
|
* @param addNoise add noise to the edges
|
|
|
|
|
* @param smart try to reduce complexity of covariance to cheapest model
|
2014-06-01 23:46:23 +08:00
|
|
|
* @param noiseFormat how noise parameters are stored
|
|
|
|
|
* @param kernelFunctionType whether to wrap the noise model in a robust kernel
|
|
|
|
|
* @return graph and initial values
|
2013-10-18 09:25:13 +08:00
|
|
|
*/
|
2014-06-01 23:46:23 +08:00
|
|
|
GTSAM_EXPORT GraphAndValues load2D(const std::string& filename,
|
2020-08-13 07:41:56 +08:00
|
|
|
SharedNoiseModel model = SharedNoiseModel(), Key maxNr = 0, bool addNoise =
|
2014-10-23 05:49:18 +08:00
|
|
|
false, bool smart = true, NoiseFormat noiseFormat = NoiseFormatAUTO, //
|
2014-06-01 23:46:23 +08:00
|
|
|
KernelFunctionType kernelFunctionType = KernelFunctionTypeNONE);
|
2013-10-18 09:25:13 +08:00
|
|
|
|
2014-06-01 23:46:23 +08:00
|
|
|
/// @deprecated load2D now allows for arbitrary models and wrapping a robust kernel
|
|
|
|
|
GTSAM_EXPORT GraphAndValues load2D_robust(const std::string& filename,
|
2020-08-13 07:41:56 +08:00
|
|
|
noiseModel::Base::shared_ptr& model, Key maxNr = 0);
|
2013-10-18 09:25:13 +08:00
|
|
|
|
|
|
|
|
/** save 2d graph */
|
2014-06-01 07:01:54 +08:00
|
|
|
GTSAM_EXPORT void save2D(const NonlinearFactorGraph& graph,
|
|
|
|
|
const Values& config, const noiseModel::Diagonal::shared_ptr model,
|
|
|
|
|
const std::string& filename);
|
2013-10-18 09:25:13 +08:00
|
|
|
|
2014-06-01 23:46:23 +08:00
|
|
|
/**
|
|
|
|
|
* @brief This function parses a g2o file and stores the measurements into a
|
|
|
|
|
* NonlinearFactorGraph and the initial guess in a Values structure
|
2014-08-19 08:40:52 +08:00
|
|
|
* @param filename The name of the g2o file\
|
|
|
|
|
* @param is3D indicates if the file describes a 2D or 3D problem
|
2014-06-01 23:46:23 +08:00
|
|
|
* @param kernelFunctionType whether to wrap the noise model in a robust kernel
|
|
|
|
|
* @return graph and initial values
|
|
|
|
|
*/
|
2014-08-19 08:40:52 +08:00
|
|
|
GTSAM_EXPORT GraphAndValues readG2o(const std::string& g2oFile, const bool is3D = false,
|
2014-06-01 23:46:23 +08:00
|
|
|
KernelFunctionType kernelFunctionType = KernelFunctionTypeNONE);
|
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
* @brief This function writes a g2o file from
|
|
|
|
|
* NonlinearFactorGraph and a Values structure
|
|
|
|
|
* @param filename The name of the g2o file to write
|
|
|
|
|
* @param graph NonlinearFactor graph storing the measurements
|
|
|
|
|
* @param estimate Values
|
|
|
|
|
*/
|
|
|
|
|
GTSAM_EXPORT void writeG2o(const NonlinearFactorGraph& graph,
|
|
|
|
|
const Values& estimate, const std::string& filename);
|
|
|
|
|
|
2019-03-14 12:58:22 +08:00
|
|
|
/// Parse edges in 3D TORO graph file into a set of BetweenFactors.
|
2019-03-14 13:25:06 +08:00
|
|
|
using BetweenFactorPose3s = std::vector<gtsam::BetweenFactor<Pose3>::shared_ptr>;
|
2020-08-13 07:41:56 +08:00
|
|
|
GTSAM_EXPORT BetweenFactorPose3s parse3DFactors(
|
|
|
|
|
const std::string &filename,
|
|
|
|
|
const noiseModel::Diagonal::shared_ptr &corruptingNoise = nullptr,
|
|
|
|
|
Key maxNr = 0);
|
2019-03-14 12:58:22 +08:00
|
|
|
|
2020-07-11 14:52:34 +08:00
|
|
|
/// Parse vertices in 3D TORO/g2o graph file into a map of Pose3s.
|
2020-08-13 07:41:56 +08:00
|
|
|
GTSAM_EXPORT std::map<Key, Pose3> parse3DPoses(const std::string &filename,
|
|
|
|
|
Key maxNr = 0);
|
2019-03-14 12:58:22 +08:00
|
|
|
|
2020-07-11 14:52:34 +08:00
|
|
|
/// Parse landmarks in 3D g2o graph file into a map of Point3s.
|
2020-08-13 07:41:56 +08:00
|
|
|
GTSAM_EXPORT std::map<Key, Point3> parse3DLandmarks(const std::string &filename,
|
|
|
|
|
Key maxNr = 0);
|
2020-07-11 14:52:34 +08:00
|
|
|
|
2019-03-14 12:58:22 +08:00
|
|
|
/// Load TORO 3D Graph
|
2014-08-19 08:40:52 +08:00
|
|
|
GTSAM_EXPORT GraphAndValues load3D(const std::string& filename);
|
2013-10-18 09:25:13 +08:00
|
|
|
|
|
|
|
|
/// A measurement with its camera index
|
2020-03-07 06:59:09 +08:00
|
|
|
typedef std::pair<size_t, Point2> SfmMeasurement;
|
2013-10-18 09:25:13 +08:00
|
|
|
|
2020-03-07 06:59:09 +08:00
|
|
|
/// SfmTrack
|
|
|
|
|
typedef std::pair<size_t, size_t> SiftIndex;
|
2015-04-11 22:28:44 +08:00
|
|
|
|
2013-10-18 09:25:13 +08:00
|
|
|
/// Define the structure for the 3D points
|
2020-03-07 06:59:09 +08:00
|
|
|
struct SfmTrack {
|
|
|
|
|
SfmTrack(): p(0,0,0) {}
|
2014-06-01 07:01:54 +08:00
|
|
|
Point3 p; ///< 3D position of the point
|
|
|
|
|
float r, g, b; ///< RGB color of the 3D point
|
2020-03-07 06:59:09 +08:00
|
|
|
std::vector<SfmMeasurement> measurements; ///< The 2D image projections (id,(u,v))
|
|
|
|
|
std::vector<SiftIndex> siftIndices;
|
2020-03-07 02:22:29 +08:00
|
|
|
/// Total number of measurements in this track
|
2014-06-01 07:01:54 +08:00
|
|
|
size_t number_measurements() const {
|
|
|
|
|
return measurements.size();
|
|
|
|
|
}
|
2020-03-07 02:22:29 +08:00
|
|
|
/// Get the measurement (camera index, Point2) at pose index `idx`
|
2020-03-07 06:59:09 +08:00
|
|
|
SfmMeasurement measurement(size_t idx) const {
|
2020-03-04 10:41:44 +08:00
|
|
|
return measurements[idx];
|
|
|
|
|
}
|
2020-03-07 02:22:29 +08:00
|
|
|
/// Get the SIFT feature index corresponding to the measurement at `idx`
|
2020-03-07 06:59:09 +08:00
|
|
|
SiftIndex siftIndex(size_t idx) const {
|
2020-03-04 10:41:44 +08:00
|
|
|
return siftIndices[idx];
|
|
|
|
|
}
|
2013-10-18 09:25:13 +08:00
|
|
|
};
|
|
|
|
|
|
|
|
|
|
/// Define the structure for the camera poses
|
2020-03-07 06:59:09 +08:00
|
|
|
typedef PinholeCamera<Cal3Bundler> SfmCamera;
|
2013-10-18 09:25:13 +08:00
|
|
|
|
|
|
|
|
/// Define the structure for SfM data
|
2020-03-07 06:59:09 +08:00
|
|
|
struct SfmData {
|
|
|
|
|
std::vector<SfmCamera> cameras; ///< Set of cameras
|
|
|
|
|
std::vector<SfmTrack> tracks; ///< Sparse set of points
|
2014-06-01 07:01:54 +08:00
|
|
|
size_t number_cameras() const {
|
|
|
|
|
return cameras.size();
|
2020-03-07 02:22:29 +08:00
|
|
|
}
|
|
|
|
|
/// The number of reconstructed 3D points
|
2014-06-01 07:01:54 +08:00
|
|
|
size_t number_tracks() const {
|
|
|
|
|
return tracks.size();
|
2020-03-07 02:22:29 +08:00
|
|
|
}
|
|
|
|
|
/// The camera pose at frame index `idx`
|
2020-03-07 06:59:09 +08:00
|
|
|
SfmCamera camera(size_t idx) const {
|
2020-03-04 10:41:44 +08:00
|
|
|
return cameras[idx];
|
|
|
|
|
}
|
2020-03-07 02:22:29 +08:00
|
|
|
/// The track formed by series of landmark measurements
|
2020-03-07 06:59:09 +08:00
|
|
|
SfmTrack track(size_t idx) const {
|
2020-03-04 10:41:44 +08:00
|
|
|
return tracks[idx];
|
|
|
|
|
}
|
2013-10-18 09:25:13 +08:00
|
|
|
};
|
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
* @brief This function parses a bundler output file and stores the data into a
|
2020-03-07 06:59:09 +08:00
|
|
|
* SfmData structure
|
2013-10-18 09:25:16 +08:00
|
|
|
* @param filename The name of the bundler file
|
2013-10-18 09:25:13 +08:00
|
|
|
* @param data SfM structure where the data is stored
|
|
|
|
|
* @return true if the parsing was successful, false otherwise
|
|
|
|
|
*/
|
2020-03-07 06:59:09 +08:00
|
|
|
GTSAM_EXPORT bool readBundler(const std::string& filename, SfmData &data);
|
2013-10-18 09:25:13 +08:00
|
|
|
|
2013-10-18 09:25:16 +08:00
|
|
|
/**
|
|
|
|
|
* @brief This function parses a "Bundle Adjustment in the Large" (BAL) file and stores the data into a
|
2020-03-07 06:59:09 +08:00
|
|
|
* SfmData structure
|
2013-10-18 09:25:16 +08:00
|
|
|
* @param filename The name of the BAL file
|
|
|
|
|
* @param data SfM structure where the data is stored
|
|
|
|
|
* @return true if the parsing was successful, false otherwise
|
|
|
|
|
*/
|
2020-03-07 06:59:09 +08:00
|
|
|
GTSAM_EXPORT bool readBAL(const std::string& filename, SfmData &data);
|
2010-01-23 04:18:40 +08:00
|
|
|
|
2013-10-18 14:17:04 +08:00
|
|
|
/**
|
|
|
|
|
* @brief This function writes a "Bundle Adjustment in the Large" (BAL) file from a
|
2020-03-07 06:59:09 +08:00
|
|
|
* SfmData structure
|
2013-10-18 14:17:04 +08:00
|
|
|
* @param filename The name of the BAL file to write
|
|
|
|
|
* @param data SfM structure where the data is stored
|
|
|
|
|
* @return true if the parsing was successful, false otherwise
|
|
|
|
|
*/
|
2020-03-07 06:59:09 +08:00
|
|
|
GTSAM_EXPORT bool writeBAL(const std::string& filename, SfmData &data);
|
2013-10-18 14:17:04 +08:00
|
|
|
|
2013-10-20 04:28:20 +08:00
|
|
|
/**
|
|
|
|
|
* @brief This function writes a "Bundle Adjustment in the Large" (BAL) file from a
|
2020-03-07 06:59:09 +08:00
|
|
|
* SfmData structure and a value structure (measurements are the same as the SfM input data,
|
2013-10-20 04:28:20 +08:00
|
|
|
* while camera poses and values are read from Values)
|
|
|
|
|
* @param filename The name of the BAL file to write
|
|
|
|
|
* @param data SfM structure where the data is stored
|
2014-01-25 06:36:41 +08:00
|
|
|
* @param values structure where the graph values are stored (values can be either Pose3 or PinholeCamera<Cal3Bundler> for the
|
|
|
|
|
* cameras, and should be Point3 for the 3D points). Note that the current version
|
|
|
|
|
* assumes that the keys are "x1" for pose 1 (or "c1" for camera 1) and "l1" for landmark 1
|
2013-10-20 04:28:20 +08:00
|
|
|
* @return true if the parsing was successful, false otherwise
|
|
|
|
|
*/
|
2014-06-01 07:01:54 +08:00
|
|
|
GTSAM_EXPORT bool writeBALfromValues(const std::string& filename,
|
2020-03-07 06:59:09 +08:00
|
|
|
const SfmData &data, Values& values);
|
2013-10-20 04:28:20 +08:00
|
|
|
|
2013-10-18 14:17:04 +08:00
|
|
|
/**
|
|
|
|
|
* @brief This function converts an openGL camera pose to an GTSAM camera pose
|
|
|
|
|
* @param R rotation in openGL
|
|
|
|
|
* @param tx x component of the translation in openGL
|
|
|
|
|
* @param ty y component of the translation in openGL
|
|
|
|
|
* @param tz z component of the translation in openGL
|
|
|
|
|
* @return Pose3 in GTSAM format
|
|
|
|
|
*/
|
2013-10-27 01:10:36 +08:00
|
|
|
GTSAM_EXPORT Pose3 openGL2gtsam(const Rot3& R, double tx, double ty, double tz);
|
2013-10-18 14:17:04 +08:00
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
* @brief This function converts a GTSAM camera pose to an openGL camera pose
|
|
|
|
|
* @param R rotation in GTSAM
|
|
|
|
|
* @param tx x component of the translation in GTSAM
|
|
|
|
|
* @param ty y component of the translation in GTSAM
|
|
|
|
|
* @param tz z component of the translation in GTSAM
|
|
|
|
|
* @return Pose3 in openGL format
|
|
|
|
|
*/
|
2013-10-27 01:10:36 +08:00
|
|
|
GTSAM_EXPORT Pose3 gtsam2openGL(const Rot3& R, double tx, double ty, double tz);
|
2013-10-18 14:17:04 +08:00
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
* @brief This function converts a GTSAM camera pose to an openGL camera pose
|
|
|
|
|
* @param PoseGTSAM pose in GTSAM format
|
|
|
|
|
* @return Pose3 in openGL format
|
|
|
|
|
*/
|
2013-10-27 01:10:36 +08:00
|
|
|
GTSAM_EXPORT Pose3 gtsam2openGL(const Pose3& PoseGTSAM);
|
2013-10-18 14:17:04 +08:00
|
|
|
|
2014-02-21 04:37:17 +08:00
|
|
|
/**
|
|
|
|
|
* @brief This function creates initial values for cameras from db
|
2020-03-07 06:59:09 +08:00
|
|
|
* @param SfmData
|
2014-02-21 04:37:17 +08:00
|
|
|
* @return Values
|
|
|
|
|
*/
|
2020-03-07 06:59:09 +08:00
|
|
|
GTSAM_EXPORT Values initialCamerasEstimate(const SfmData& db);
|
2014-02-21 04:37:17 +08:00
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
* @brief This function creates initial values for cameras and points from db
|
2020-03-07 06:59:09 +08:00
|
|
|
* @param SfmData
|
2014-02-21 04:37:17 +08:00
|
|
|
* @return Values
|
|
|
|
|
*/
|
2020-03-07 06:59:09 +08:00
|
|
|
GTSAM_EXPORT Values initialCamerasAndPointsEstimate(const SfmData& db);
|
2014-02-21 04:37:17 +08:00
|
|
|
|
2020-07-23 05:32:25 +08:00
|
|
|
} // namespace gtsam
|