change from addtogroup to ingroup
parent
fd839e71b6
commit
55ae901d45
|
@ -78,6 +78,8 @@ using Weights = Eigen::Matrix<double, 1, -1>; /* 1xN vector */
|
||||||
* @tparam M Size of the identity matrix.
|
* @tparam M Size of the identity matrix.
|
||||||
* @param w The weights of the polynomial.
|
* @param w The weights of the polynomial.
|
||||||
* @return Mx(M*N) kronecker product [w(0)*I, w(1)*I, ..., w(N-1)*I]
|
* @return Mx(M*N) kronecker product [w(0)*I, w(1)*I, ..., w(N-1)*I]
|
||||||
|
*
|
||||||
|
* @ingroup Basis
|
||||||
*/
|
*/
|
||||||
template <size_t M>
|
template <size_t M>
|
||||||
Matrix kroneckerProductIdentity(const Weights& w) {
|
Matrix kroneckerProductIdentity(const Weights& w) {
|
||||||
|
@ -90,7 +92,10 @@ Matrix kroneckerProductIdentity(const Weights& w) {
|
||||||
return result;
|
return result;
|
||||||
}
|
}
|
||||||
|
|
||||||
/// CRTP Base class for function bases
|
/**
|
||||||
|
* CRTP Base class for function bases
|
||||||
|
* @ingroup Basis
|
||||||
|
*/
|
||||||
template <typename DERIVED>
|
template <typename DERIVED>
|
||||||
class Basis {
|
class Basis {
|
||||||
public:
|
public:
|
||||||
|
|
|
@ -32,6 +32,8 @@ namespace gtsam {
|
||||||
*
|
*
|
||||||
* Example, degree 8 Chebyshev polynomial measured at x=0.5:
|
* Example, degree 8 Chebyshev polynomial measured at x=0.5:
|
||||||
* EvaluationFactor<Chebyshev2> factor(key, measured, model, 8, 0.5);
|
* EvaluationFactor<Chebyshev2> factor(key, measured, model, 8, 0.5);
|
||||||
|
*
|
||||||
|
* @ingroup Basis
|
||||||
*/
|
*/
|
||||||
template <class BASIS>
|
template <class BASIS>
|
||||||
class EvaluationFactor : public FunctorizedFactor<double, Vector> {
|
class EvaluationFactor : public FunctorizedFactor<double, Vector> {
|
||||||
|
@ -86,6 +88,8 @@ class EvaluationFactor : public FunctorizedFactor<double, Vector> {
|
||||||
*
|
*
|
||||||
* @param BASIS: The basis class to use e.g. Chebyshev2
|
* @param BASIS: The basis class to use e.g. Chebyshev2
|
||||||
* @param M: Size of the evaluated state vector.
|
* @param M: Size of the evaluated state vector.
|
||||||
|
*
|
||||||
|
* @ingroup Basis
|
||||||
*/
|
*/
|
||||||
template <class BASIS, int M>
|
template <class BASIS, int M>
|
||||||
class VectorEvaluationFactor
|
class VectorEvaluationFactor
|
||||||
|
@ -149,6 +153,8 @@ class VectorEvaluationFactor
|
||||||
* VectorComponentFactor<BASIS, P> controlPrior(key, measured, model,
|
* VectorComponentFactor<BASIS, P> controlPrior(key, measured, model,
|
||||||
* N, i, t, a, b);
|
* N, i, t, a, b);
|
||||||
* where N is the degree and i is the component index.
|
* where N is the degree and i is the component index.
|
||||||
|
*
|
||||||
|
* @ingroup Basis
|
||||||
*/
|
*/
|
||||||
template <class BASIS, size_t P>
|
template <class BASIS, size_t P>
|
||||||
class VectorComponentFactor
|
class VectorComponentFactor
|
||||||
|
|
|
@ -16,7 +16,7 @@
|
||||||
*/
|
*/
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @addtogroup geometry
|
* @ingroup geometry
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
@ -63,7 +63,7 @@ void calibrateJacobians(const Cal& calibration, const Point2& pn,
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief Common base class for all calibration models.
|
* @brief Common base class for all calibration models.
|
||||||
* @addtogroup geometry
|
* @ingroup geometry
|
||||||
* \nosubgrouping
|
* \nosubgrouping
|
||||||
*/
|
*/
|
||||||
class GTSAM_EXPORT Cal3 {
|
class GTSAM_EXPORT Cal3 {
|
||||||
|
|
|
@ -26,7 +26,7 @@ namespace gtsam {
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief Calibration used by Bundler
|
* @brief Calibration used by Bundler
|
||||||
* @addtogroup geometry
|
* @ingroup geometry
|
||||||
* \nosubgrouping
|
* \nosubgrouping
|
||||||
*/
|
*/
|
||||||
class GTSAM_EXPORT Cal3Bundler : public Cal3 {
|
class GTSAM_EXPORT Cal3Bundler : public Cal3 {
|
||||||
|
|
|
@ -29,7 +29,7 @@ namespace gtsam {
|
||||||
* @brief Calibration of a camera with radial distortion that also supports
|
* @brief Calibration of a camera with radial distortion that also supports
|
||||||
* Lie-group behaviors for optimization.
|
* Lie-group behaviors for optimization.
|
||||||
* \sa Cal3DS2_Base
|
* \sa Cal3DS2_Base
|
||||||
* @addtogroup geometry
|
* @ingroup geometry
|
||||||
* \nosubgrouping
|
* \nosubgrouping
|
||||||
*/
|
*/
|
||||||
class GTSAM_EXPORT Cal3DS2 : public Cal3DS2_Base {
|
class GTSAM_EXPORT Cal3DS2 : public Cal3DS2_Base {
|
||||||
|
|
|
@ -27,7 +27,7 @@ namespace gtsam {
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief Calibration of a camera with radial distortion
|
* @brief Calibration of a camera with radial distortion
|
||||||
* @addtogroup geometry
|
* @ingroup geometry
|
||||||
* \nosubgrouping
|
* \nosubgrouping
|
||||||
*
|
*
|
||||||
* Uses same distortionmodel as OpenCV, with
|
* Uses same distortionmodel as OpenCV, with
|
||||||
|
|
|
@ -30,7 +30,7 @@ namespace gtsam {
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief Calibration of a fisheye camera
|
* @brief Calibration of a fisheye camera
|
||||||
* @addtogroup geometry
|
* @ingroup geometry
|
||||||
* \nosubgrouping
|
* \nosubgrouping
|
||||||
*
|
*
|
||||||
* Uses same distortionmodel as OpenCV, with
|
* Uses same distortionmodel as OpenCV, with
|
||||||
|
|
|
@ -18,7 +18,7 @@
|
||||||
*/
|
*/
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @addtogroup geometry
|
* @ingroup geometry
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
@ -30,7 +30,7 @@ namespace gtsam {
|
||||||
/**
|
/**
|
||||||
* @brief Calibration of a omni-directional camera with mirror + lens radial
|
* @brief Calibration of a omni-directional camera with mirror + lens radial
|
||||||
* distortion
|
* distortion
|
||||||
* @addtogroup geometry
|
* @ingroup geometry
|
||||||
* \nosubgrouping
|
* \nosubgrouping
|
||||||
*
|
*
|
||||||
* Similar to Cal3DS2, does distortion but has additional mirror parameter xi
|
* Similar to Cal3DS2, does distortion but has additional mirror parameter xi
|
||||||
|
|
|
@ -16,7 +16,7 @@
|
||||||
*/
|
*/
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @addtogroup geometry
|
* @ingroup geometry
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
@ -28,7 +28,7 @@ namespace gtsam {
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief The most common 5DOF 3D->2D calibration
|
* @brief The most common 5DOF 3D->2D calibration
|
||||||
* @addtogroup geometry
|
* @ingroup geometry
|
||||||
* \nosubgrouping
|
* \nosubgrouping
|
||||||
*/
|
*/
|
||||||
class GTSAM_EXPORT Cal3_S2 : public Cal3 {
|
class GTSAM_EXPORT Cal3_S2 : public Cal3 {
|
||||||
|
|
|
@ -24,7 +24,7 @@ namespace gtsam {
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief The most common 5DOF 3D->2D calibration, stereo version
|
* @brief The most common 5DOF 3D->2D calibration, stereo version
|
||||||
* @addtogroup geometry
|
* @ingroup geometry
|
||||||
* \nosubgrouping
|
* \nosubgrouping
|
||||||
*/
|
*/
|
||||||
class GTSAM_EXPORT Cal3_S2Stereo : public Cal3_S2 {
|
class GTSAM_EXPORT Cal3_S2Stereo : public Cal3_S2 {
|
||||||
|
|
|
@ -46,7 +46,7 @@ private:
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* A pinhole camera class that has a Pose3, functions as base class for all pinhole cameras
|
* A pinhole camera class that has a Pose3, functions as base class for all pinhole cameras
|
||||||
* @addtogroup geometry
|
* @ingroup geometry
|
||||||
* \nosubgrouping
|
* \nosubgrouping
|
||||||
*/
|
*/
|
||||||
class GTSAM_EXPORT PinholeBase {
|
class GTSAM_EXPORT PinholeBase {
|
||||||
|
@ -241,7 +241,7 @@ private:
|
||||||
* A Calibrated camera class [R|-R't], calibration K=I.
|
* A Calibrated camera class [R|-R't], calibration K=I.
|
||||||
* If calibration is known, it is more computationally efficient
|
* If calibration is known, it is more computationally efficient
|
||||||
* to calibrate the measurements rather than try to predict in pixels.
|
* to calibrate the measurements rather than try to predict in pixels.
|
||||||
* @addtogroup geometry
|
* @ingroup geometry
|
||||||
* \nosubgrouping
|
* \nosubgrouping
|
||||||
*/
|
*/
|
||||||
class GTSAM_EXPORT CalibratedCamera: public PinholeBase {
|
class GTSAM_EXPORT CalibratedCamera: public PinholeBase {
|
||||||
|
|
|
@ -38,7 +38,7 @@ GTSAM_EXPORT Line3 transformTo(const Pose3 &wTc, const Line3 &wL,
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* A 3D line (R,a,b) : (Rot3,Scalar,Scalar)
|
* A 3D line (R,a,b) : (Rot3,Scalar,Scalar)
|
||||||
* @addtogroup geometry
|
* @ingroup geometry
|
||||||
* \nosubgrouping
|
* \nosubgrouping
|
||||||
*/
|
*/
|
||||||
class GTSAM_EXPORT Line3 {
|
class GTSAM_EXPORT Line3 {
|
||||||
|
|
|
@ -26,7 +26,7 @@ namespace gtsam {
|
||||||
/**
|
/**
|
||||||
* A pinhole camera class that has a Pose3 and a Calibration.
|
* A pinhole camera class that has a Pose3 and a Calibration.
|
||||||
* Use PinholePose if you will not be optimizing for Calibration
|
* Use PinholePose if you will not be optimizing for Calibration
|
||||||
* @addtogroup geometry
|
* @ingroup geometry
|
||||||
* \nosubgrouping
|
* \nosubgrouping
|
||||||
*/
|
*/
|
||||||
template<typename Calibration>
|
template<typename Calibration>
|
||||||
|
|
|
@ -27,7 +27,7 @@ namespace gtsam {
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* A pinhole camera class that has a Pose3 and a *fixed* Calibration.
|
* A pinhole camera class that has a Pose3 and a *fixed* Calibration.
|
||||||
* @addtogroup geometry
|
* @ingroup geometry
|
||||||
* \nosubgrouping
|
* \nosubgrouping
|
||||||
*/
|
*/
|
||||||
template<typename CALIBRATION>
|
template<typename CALIBRATION>
|
||||||
|
@ -236,7 +236,7 @@ public:
|
||||||
* A pinhole camera class that has a Pose3 and a *fixed* Calibration.
|
* A pinhole camera class that has a Pose3 and a *fixed* Calibration.
|
||||||
* Instead of using this class, one might consider calibrating the measurements
|
* Instead of using this class, one might consider calibrating the measurements
|
||||||
* and using CalibratedCamera, which would then be faster.
|
* and using CalibratedCamera, which would then be faster.
|
||||||
* @addtogroup geometry
|
* @ingroup geometry
|
||||||
* \nosubgrouping
|
* \nosubgrouping
|
||||||
*/
|
*/
|
||||||
template<typename CALIBRATION>
|
template<typename CALIBRATION>
|
||||||
|
|
|
@ -30,7 +30,7 @@ namespace gtsam {
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* A 2D pose (Point2,Rot2)
|
* A 2D pose (Point2,Rot2)
|
||||||
* @addtogroup geometry
|
* @ingroup geometry
|
||||||
* \nosubgrouping
|
* \nosubgrouping
|
||||||
*/
|
*/
|
||||||
class Pose2: public LieGroup<Pose2, 3> {
|
class Pose2: public LieGroup<Pose2, 3> {
|
||||||
|
|
|
@ -31,7 +31,7 @@ class Pose2;
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* A 3D pose (R,t) : (Rot3,Point3)
|
* A 3D pose (R,t) : (Rot3,Point3)
|
||||||
* @addtogroup geometry
|
* @ingroup geometry
|
||||||
* \nosubgrouping
|
* \nosubgrouping
|
||||||
*/
|
*/
|
||||||
class GTSAM_EXPORT Pose3: public LieGroup<Pose3, 6> {
|
class GTSAM_EXPORT Pose3: public LieGroup<Pose3, 6> {
|
||||||
|
|
|
@ -30,7 +30,7 @@ namespace gtsam {
|
||||||
/**
|
/**
|
||||||
* Rotation matrix
|
* Rotation matrix
|
||||||
* NOTE: the angle theta is in radians unless explicitly stated
|
* NOTE: the angle theta is in radians unless explicitly stated
|
||||||
* @addtogroup geometry
|
* @ingroup geometry
|
||||||
* \nosubgrouping
|
* \nosubgrouping
|
||||||
*/
|
*/
|
||||||
class GTSAM_EXPORT Rot2 : public LieGroup<Rot2, 1> {
|
class GTSAM_EXPORT Rot2 : public LieGroup<Rot2, 1> {
|
||||||
|
|
|
@ -53,7 +53,7 @@ namespace gtsam {
|
||||||
* @brief Rot3 is a 3D rotation represented as a rotation matrix if the
|
* @brief Rot3 is a 3D rotation represented as a rotation matrix if the
|
||||||
* preprocessor symbol GTSAM_USE_QUATERNIONS is not defined, or as a quaternion
|
* preprocessor symbol GTSAM_USE_QUATERNIONS is not defined, or as a quaternion
|
||||||
* if it is defined.
|
* if it is defined.
|
||||||
* @addtogroup geometry
|
* @ingroup geometry
|
||||||
*/
|
*/
|
||||||
class GTSAM_EXPORT Rot3 : public LieGroup<Rot3, 3> {
|
class GTSAM_EXPORT Rot3 : public LieGroup<Rot3, 3> {
|
||||||
private:
|
private:
|
||||||
|
|
|
@ -34,7 +34,7 @@ namespace gtsam {
|
||||||
* Empty calibration. Only needed to play well with other cameras
|
* Empty calibration. Only needed to play well with other cameras
|
||||||
* (e.g., when templating functions wrt cameras), since other cameras
|
* (e.g., when templating functions wrt cameras), since other cameras
|
||||||
* have constuctors in the form ‘camera(pose,calibration)’
|
* have constuctors in the form ‘camera(pose,calibration)’
|
||||||
* @addtogroup geometry
|
* @ingroup geometry
|
||||||
* \nosubgrouping
|
* \nosubgrouping
|
||||||
*/
|
*/
|
||||||
class GTSAM_EXPORT EmptyCal {
|
class GTSAM_EXPORT EmptyCal {
|
||||||
|
@ -64,7 +64,7 @@ class GTSAM_EXPORT EmptyCal {
|
||||||
/**
|
/**
|
||||||
* A spherical camera class that has a Pose3 and measures bearing vectors.
|
* A spherical camera class that has a Pose3 and measures bearing vectors.
|
||||||
* The camera has an ‘Empty’ calibration and the only 6 dof are the pose
|
* The camera has an ‘Empty’ calibration and the only 6 dof are the pose
|
||||||
* @addtogroup geometry
|
* @ingroup geometry
|
||||||
* \nosubgrouping
|
* \nosubgrouping
|
||||||
*/
|
*/
|
||||||
class GTSAM_EXPORT SphericalCamera {
|
class GTSAM_EXPORT SphericalCamera {
|
||||||
|
|
|
@ -42,7 +42,7 @@ private:
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* A stereo camera class, parameterize by left camera pose and stereo calibration
|
* A stereo camera class, parameterize by left camera pose and stereo calibration
|
||||||
* @addtogroup geometry
|
* @ingroup geometry
|
||||||
*/
|
*/
|
||||||
class GTSAM_EXPORT StereoCamera {
|
class GTSAM_EXPORT StereoCamera {
|
||||||
|
|
||||||
|
|
|
@ -26,7 +26,7 @@ namespace gtsam {
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* A 2D stereo point, v will be same for rectified images
|
* A 2D stereo point, v will be same for rectified images
|
||||||
* @addtogroup geometry
|
* @ingroup geometry
|
||||||
* \nosubgrouping
|
* \nosubgrouping
|
||||||
*/
|
*/
|
||||||
class GTSAM_EXPORT StereoPoint2 {
|
class GTSAM_EXPORT StereoPoint2 {
|
||||||
|
|
|
@ -29,7 +29,7 @@ namespace gtsam {
|
||||||
* - measurement is direction of gravity in body frame bF
|
* - measurement is direction of gravity in body frame bF
|
||||||
* - reference is direction of gravity in navigation frame nG
|
* - reference is direction of gravity in navigation frame nG
|
||||||
* This factor will give zero error if nRb * bF == nG
|
* This factor will give zero error if nRb * bF == nG
|
||||||
* @addtogroup Navigation
|
* @ingroup navigation
|
||||||
*/
|
*/
|
||||||
class AttitudeFactor {
|
class AttitudeFactor {
|
||||||
|
|
||||||
|
@ -74,7 +74,7 @@ public:
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Version of AttitudeFactor for Rot3
|
* Version of AttitudeFactor for Rot3
|
||||||
* @addtogroup Navigation
|
* @ingroup navigation
|
||||||
*/
|
*/
|
||||||
class GTSAM_EXPORT Rot3AttitudeFactor: public NoiseModelFactor1<Rot3>, public AttitudeFactor {
|
class GTSAM_EXPORT Rot3AttitudeFactor: public NoiseModelFactor1<Rot3>, public AttitudeFactor {
|
||||||
|
|
||||||
|
@ -147,7 +147,7 @@ template<> struct traits<Rot3AttitudeFactor> : public Testable<Rot3AttitudeFacto
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Version of AttitudeFactor for Pose3
|
* Version of AttitudeFactor for Pose3
|
||||||
* @addtogroup Navigation
|
* @ingroup navigation
|
||||||
*/
|
*/
|
||||||
class GTSAM_EXPORT Pose3AttitudeFactor: public NoiseModelFactor1<Pose3>,
|
class GTSAM_EXPORT Pose3AttitudeFactor: public NoiseModelFactor1<Pose3>,
|
||||||
public AttitudeFactor {
|
public AttitudeFactor {
|
||||||
|
|
|
@ -29,7 +29,7 @@ namespace gtsam {
|
||||||
* Model with a slowly moving bias to capture differences
|
* Model with a slowly moving bias to capture differences
|
||||||
* between the height and the standard atmosphere
|
* between the height and the standard atmosphere
|
||||||
* https://www.grc.nasa.gov/www/k-12/airplane/atmosmet.html
|
* https://www.grc.nasa.gov/www/k-12/airplane/atmosmet.html
|
||||||
* @addtogroup Navigation
|
* @ingroup navigation
|
||||||
*/
|
*/
|
||||||
class GTSAM_EXPORT BarometricFactor : public NoiseModelFactor2<Pose3, double> {
|
class GTSAM_EXPORT BarometricFactor : public NoiseModelFactor2<Pose3, double> {
|
||||||
private:
|
private:
|
||||||
|
|
|
@ -123,7 +123,7 @@ public:
|
||||||
* it is received from the IMU) so as to avoid costly integration at time of
|
* it is received from the IMU) so as to avoid costly integration at time of
|
||||||
* factor construction.
|
* factor construction.
|
||||||
*
|
*
|
||||||
* @ingroup SLAM
|
* @ingroup navigation
|
||||||
*/
|
*/
|
||||||
class GTSAM_EXPORT PreintegratedCombinedMeasurements : public PreintegrationType {
|
class GTSAM_EXPORT PreintegratedCombinedMeasurements : public PreintegrationType {
|
||||||
|
|
||||||
|
@ -252,7 +252,7 @@ public:
|
||||||
* the correlation between the bias uncertainty and the preintegrated
|
* the correlation between the bias uncertainty and the preintegrated
|
||||||
* measurements uncertainty.
|
* measurements uncertainty.
|
||||||
*
|
*
|
||||||
* @ingroup SLAM
|
* @ingroup navigation
|
||||||
*/
|
*/
|
||||||
class GTSAM_EXPORT CombinedImuFactor: public NoiseModelFactor6<Pose3, Vector3, Pose3,
|
class GTSAM_EXPORT CombinedImuFactor: public NoiseModelFactor6<Pose3, Vector3, Pose3,
|
||||||
Vector3, imuBias::ConstantBias, imuBias::ConstantBias> {
|
Vector3, imuBias::ConstantBias, imuBias::ConstantBias> {
|
||||||
|
|
|
@ -30,7 +30,7 @@ namespace gtsam {
|
||||||
* NED: North-East-Down navigation frame at some local origin
|
* NED: North-East-Down navigation frame at some local origin
|
||||||
* ECEF: Earth-centered Earth-fixed, origin at Earth's center
|
* ECEF: Earth-centered Earth-fixed, origin at Earth's center
|
||||||
* See Farrell08book or e.g. http://www.dirsig.org/docs/new/coordinates.html
|
* See Farrell08book or e.g. http://www.dirsig.org/docs/new/coordinates.html
|
||||||
* @addtogroup Navigation
|
* @ingroup navigation
|
||||||
*/
|
*/
|
||||||
class GTSAM_EXPORT GPSFactor: public NoiseModelFactor1<Pose3> {
|
class GTSAM_EXPORT GPSFactor: public NoiseModelFactor1<Pose3> {
|
||||||
|
|
||||||
|
@ -108,7 +108,7 @@ private:
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Version of GPSFactor for NavState
|
* Version of GPSFactor for NavState
|
||||||
* @addtogroup Navigation
|
* @ingroup navigation
|
||||||
*/
|
*/
|
||||||
class GTSAM_EXPORT GPSFactor2: public NoiseModelFactor1<NavState> {
|
class GTSAM_EXPORT GPSFactor2: public NoiseModelFactor1<NavState> {
|
||||||
|
|
||||||
|
|
|
@ -46,7 +46,7 @@ namespace gtsam {
|
||||||
i.e w_aZb is the unit translation from a to b expressed in the world
|
i.e w_aZb is the unit translation from a to b expressed in the world
|
||||||
coordinate frame. The weights for the edges are obtained by projecting the
|
coordinate frame. The weights for the edges are obtained by projecting the
|
||||||
unit translations in a projection direction.
|
unit translations in a projection direction.
|
||||||
@addtogroup SFM
|
@ingroup sfm
|
||||||
*/
|
*/
|
||||||
class GTSAM_EXPORT MFAS {
|
class GTSAM_EXPORT MFAS {
|
||||||
public:
|
public:
|
||||||
|
|
|
@ -34,7 +34,7 @@ typedef PinholeCamera<Cal3Bundler> SfmCamera;
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief SfmData stores a bunch of SfmTracks
|
* @brief SfmData stores a bunch of SfmTracks
|
||||||
* @addtogroup sfm
|
* @ingroup sfm
|
||||||
*/
|
*/
|
||||||
struct GTSAM_EXPORT SfmData {
|
struct GTSAM_EXPORT SfmData {
|
||||||
std::vector<SfmCamera> cameras; ///< Set of cameras
|
std::vector<SfmCamera> cameras; ///< Set of cameras
|
||||||
|
|
|
@ -36,7 +36,7 @@ typedef std::pair<size_t, size_t> SiftIndex;
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief An SfmTrack stores SfM measurements grouped in a track
|
* @brief An SfmTrack stores SfM measurements grouped in a track
|
||||||
* @addtogroup sfm
|
* @ingroup sfm
|
||||||
*/
|
*/
|
||||||
struct GTSAM_EXPORT SfmTrack {
|
struct GTSAM_EXPORT SfmTrack {
|
||||||
Point3 p; ///< 3D position of the point
|
Point3 p; ///< 3D position of the point
|
||||||
|
|
|
@ -35,7 +35,7 @@ namespace gtsam {
|
||||||
* ambient world coordinate frame:
|
* ambient world coordinate frame:
|
||||||
* normalized(Tb - Ta) - w_aZb.point3()
|
* normalized(Tb - Ta) - w_aZb.point3()
|
||||||
*
|
*
|
||||||
* @addtogroup SFM
|
* @ingroup sfm
|
||||||
*
|
*
|
||||||
*
|
*
|
||||||
*/
|
*/
|
||||||
|
|
Loading…
Reference in New Issue