replace addtogroup with ingroup for the SLAM group
parent
a700c87504
commit
aef4ec8185
|
@ -11,4 +11,7 @@
|
||||||
|
|
||||||
@}
|
@}
|
||||||
|
|
||||||
*/
|
\defgroup SLAM Useful SLAM components
|
||||||
|
@{ @}
|
||||||
|
|
||||||
|
*/
|
||||||
|
|
|
@ -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.
|
||||||
*
|
*
|
||||||
* @addtogroup SLAM
|
* @ingroup SLAM
|
||||||
*/
|
*/
|
||||||
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.
|
||||||
*
|
*
|
||||||
* @addtogroup SLAM
|
* @ingroup SLAM
|
||||||
*/
|
*/
|
||||||
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> {
|
||||||
|
|
|
@ -66,7 +66,7 @@ typedef ManifoldPreintegration PreintegrationType;
|
||||||
* as soon as it is received from the IMU) so as to avoid costly integration
|
* as soon as it is received from the IMU) so as to avoid costly integration
|
||||||
* at time of factor construction.
|
* at time of factor construction.
|
||||||
*
|
*
|
||||||
* @addtogroup SLAM
|
* @ingroup SLAM
|
||||||
*/
|
*/
|
||||||
class GTSAM_EXPORT PreintegratedImuMeasurements: public PreintegrationType {
|
class GTSAM_EXPORT PreintegratedImuMeasurements: public PreintegrationType {
|
||||||
|
|
||||||
|
@ -165,7 +165,7 @@ public:
|
||||||
* (which are usually slowly varying quantities), which is up to the caller.
|
* (which are usually slowly varying quantities), which is up to the caller.
|
||||||
* See also CombinedImuFactor for a class that does this for you.
|
* See also CombinedImuFactor for a class that does this for you.
|
||||||
*
|
*
|
||||||
* @addtogroup SLAM
|
* @ingroup SLAM
|
||||||
*/
|
*/
|
||||||
class GTSAM_EXPORT ImuFactor: public NoiseModelFactor5<Pose3, Vector3, Pose3, Vector3,
|
class GTSAM_EXPORT ImuFactor: public NoiseModelFactor5<Pose3, Vector3, Pose3, Vector3,
|
||||||
imuBias::ConstantBias> {
|
imuBias::ConstantBias> {
|
||||||
|
@ -256,7 +256,7 @@ public:
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* ImuFactor2 is a ternary factor that uses NavStates rather than Pose/Velocity.
|
* ImuFactor2 is a ternary factor that uses NavStates rather than Pose/Velocity.
|
||||||
* @addtogroup SLAM
|
* @ingroup SLAM
|
||||||
*/
|
*/
|
||||||
class GTSAM_EXPORT ImuFactor2 : public NoiseModelFactor3<NavState, NavState, imuBias::ConstantBias> {
|
class GTSAM_EXPORT ImuFactor2 : public NoiseModelFactor3<NavState, NavState, imuBias::ConstantBias> {
|
||||||
private:
|
private:
|
||||||
|
|
|
@ -24,7 +24,7 @@ namespace gtsam {
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* A class for a soft prior on any Value type
|
* A class for a soft prior on any Value type
|
||||||
* @addtogroup SLAM
|
* @ingroup SLAM
|
||||||
*/
|
*/
|
||||||
template<class VALUE>
|
template<class VALUE>
|
||||||
class PriorFactor: public NoiseModelFactor1<VALUE> {
|
class PriorFactor: public NoiseModelFactor1<VALUE> {
|
||||||
|
|
|
@ -27,7 +27,7 @@ namespace gtsam {
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Binary factor for a bearing/range measurement
|
* Binary factor for a bearing/range measurement
|
||||||
* @addtogroup SLAM
|
* @ingroup SLAM
|
||||||
*/
|
*/
|
||||||
template <typename A1, typename A2,
|
template <typename A1, typename A2,
|
||||||
typename B = typename Bearing<A1, A2>::result_type,
|
typename B = typename Bearing<A1, A2>::result_type,
|
||||||
|
|
|
@ -26,7 +26,7 @@ namespace gtsam {
|
||||||
* A class for downdating an existing factor from a graph. The AntiFactor returns the same
|
* A class for downdating an existing factor from a graph. The AntiFactor returns the same
|
||||||
* linearized Hessian matrices of the original factor, but with the opposite sign. This effectively
|
* linearized Hessian matrices of the original factor, but with the opposite sign. This effectively
|
||||||
* cancels out any affects of the original factor during optimization."
|
* cancels out any affects of the original factor during optimization."
|
||||||
* @addtogroup SLAM
|
* @ingroup SLAM
|
||||||
*/
|
*/
|
||||||
class AntiFactor: public NonlinearFactor {
|
class AntiFactor: public NonlinearFactor {
|
||||||
|
|
||||||
|
|
|
@ -34,7 +34,7 @@ namespace gtsam {
|
||||||
/**
|
/**
|
||||||
* A class for a measurement predicted by "between(config[key1],config[key2])"
|
* A class for a measurement predicted by "between(config[key1],config[key2])"
|
||||||
* @tparam VALUE the Value type
|
* @tparam VALUE the Value type
|
||||||
* @addtogroup SLAM
|
* @ingroup SLAM
|
||||||
*/
|
*/
|
||||||
template<class VALUE>
|
template<class VALUE>
|
||||||
class BetweenFactor: public NoiseModelFactor2<VALUE, VALUE> {
|
class BetweenFactor: public NoiseModelFactor2<VALUE, VALUE> {
|
||||||
|
|
|
@ -27,7 +27,7 @@ namespace gtsam {
|
||||||
* greater/less than a fixed threshold. The function
|
* greater/less than a fixed threshold. The function
|
||||||
* will need to have its value function implemented to return
|
* will need to have its value function implemented to return
|
||||||
* a scalar for comparison.
|
* a scalar for comparison.
|
||||||
* @addtogroup SLAM
|
* @ingroup SLAM
|
||||||
*/
|
*/
|
||||||
template<class VALUE>
|
template<class VALUE>
|
||||||
struct BoundingConstraint1: public NoiseModelFactor1<VALUE> {
|
struct BoundingConstraint1: public NoiseModelFactor1<VALUE> {
|
||||||
|
|
|
@ -25,7 +25,7 @@ namespace gtsam {
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Binary factor between two Pose3 variables induced by an EssentialMatrix measurement
|
* Binary factor between two Pose3 variables induced by an EssentialMatrix measurement
|
||||||
* @addtogroup SLAM
|
* @ingroup SLAM
|
||||||
*/
|
*/
|
||||||
class GTSAM_EXPORT EssentialMatrixConstraint: public NoiseModelFactor2<Pose3, Pose3> {
|
class GTSAM_EXPORT EssentialMatrixConstraint: public NoiseModelFactor2<Pose3, Pose3> {
|
||||||
|
|
||||||
|
|
|
@ -54,7 +54,7 @@ namespace gtsam {
|
||||||
/**
|
/**
|
||||||
* Non-linear factor for a constraint derived from a 2D measurement.
|
* Non-linear factor for a constraint derived from a 2D measurement.
|
||||||
* The calibration is unknown here compared to GenericProjectionFactor
|
* The calibration is unknown here compared to GenericProjectionFactor
|
||||||
* @addtogroup SLAM
|
* @ingroup SLAM
|
||||||
*/
|
*/
|
||||||
template<class CAMERA, class LANDMARK>
|
template<class CAMERA, class LANDMARK>
|
||||||
class GeneralSFMFactor: public NoiseModelFactor2<CAMERA, LANDMARK> {
|
class GeneralSFMFactor: public NoiseModelFactor2<CAMERA, LANDMARK> {
|
||||||
|
|
|
@ -33,7 +33,7 @@ namespace gtsam {
|
||||||
* Non-linear factor for a constraint derived from a 2D measurement.
|
* Non-linear factor for a constraint derived from a 2D measurement.
|
||||||
* The calibration is known here.
|
* The calibration is known here.
|
||||||
* The main building block for visual SLAM.
|
* The main building block for visual SLAM.
|
||||||
* @addtogroup SLAM
|
* @ingroup SLAM
|
||||||
*/
|
*/
|
||||||
template <class POSE = Pose3, class LANDMARK = Point3,
|
template <class POSE = Pose3, class LANDMARK = Point3,
|
||||||
class CALIBRATION = Cal3_S2>
|
class CALIBRATION = Cal3_S2>
|
||||||
|
|
|
@ -24,7 +24,7 @@
|
||||||
namespace gtsam {
|
namespace gtsam {
|
||||||
/**
|
/**
|
||||||
*
|
*
|
||||||
* @addtogroup SLAM
|
* @ingroup SLAM
|
||||||
*
|
*
|
||||||
* If you are using the factor, please cite:
|
* If you are using the factor, please cite:
|
||||||
* L. Carlone, Z. Kira, C. Beall, V. Indelman, F. Dellaert, Eliminating conditionally
|
* L. Carlone, Z. Kira, C. Beall, V. Indelman, F. Dellaert, Eliminating conditionally
|
||||||
|
@ -39,7 +39,7 @@ namespace gtsam {
|
||||||
* The factor only constrains poses (variable dimension is 6).
|
* The factor only constrains poses (variable dimension is 6).
|
||||||
* This factor requires that values contains the involved poses (Pose3).
|
* This factor requires that values contains the involved poses (Pose3).
|
||||||
* If the calibration should be optimized, as well, use SmartProjectionFactor instead!
|
* If the calibration should be optimized, as well, use SmartProjectionFactor instead!
|
||||||
* @addtogroup SLAM
|
* @ingroup SLAM
|
||||||
*/
|
*/
|
||||||
template <class CALIBRATION>
|
template <class CALIBRATION>
|
||||||
class SmartProjectionPoseFactor
|
class SmartProjectionPoseFactor
|
||||||
|
|
|
@ -29,7 +29,7 @@
|
||||||
namespace gtsam {
|
namespace gtsam {
|
||||||
/**
|
/**
|
||||||
*
|
*
|
||||||
* @addtogroup SLAM
|
* @ingroup SLAM
|
||||||
*
|
*
|
||||||
* If you are using the factor, please cite:
|
* If you are using the factor, please cite:
|
||||||
* L. Carlone, Z. Kira, C. Beall, V. Indelman, F. Dellaert, Eliminating
|
* L. Carlone, Z. Kira, C. Beall, V. Indelman, F. Dellaert, Eliminating
|
||||||
|
@ -46,7 +46,7 @@ namespace gtsam {
|
||||||
* calibration (i.e., are from the same camera), use SmartProjectionPoseFactor
|
* calibration (i.e., are from the same camera), use SmartProjectionPoseFactor
|
||||||
* instead! If the calibration should be optimized, as well, use
|
* instead! If the calibration should be optimized, as well, use
|
||||||
* SmartProjectionFactor instead!
|
* SmartProjectionFactor instead!
|
||||||
* @addtogroup SLAM
|
* @ingroup SLAM
|
||||||
*/
|
*/
|
||||||
template <class CAMERA>
|
template <class CAMERA>
|
||||||
class SmartProjectionRigFactor : public SmartProjectionFactor<CAMERA> {
|
class SmartProjectionRigFactor : public SmartProjectionFactor<CAMERA> {
|
||||||
|
|
|
@ -25,7 +25,7 @@ namespace gtsam {
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* A Generic Stereo Factor
|
* A Generic Stereo Factor
|
||||||
* @addtogroup SLAM
|
* @ingroup SLAM
|
||||||
*/
|
*/
|
||||||
template<class POSE, class LANDMARK>
|
template<class POSE, class LANDMARK>
|
||||||
class GenericStereoFactor: public NoiseModelFactor2<POSE, LANDMARK> {
|
class GenericStereoFactor: public NoiseModelFactor2<POSE, LANDMARK> {
|
||||||
|
|
|
@ -27,7 +27,7 @@ namespace gtsam {
|
||||||
/**
|
/**
|
||||||
* Non-linear factor for a constraint derived from a 2D measurement.
|
* Non-linear factor for a constraint derived from a 2D measurement.
|
||||||
* The calibration and pose are assumed known.
|
* The calibration and pose are assumed known.
|
||||||
* @addtogroup SLAM
|
* @ingroup SLAM
|
||||||
*/
|
*/
|
||||||
template<class CAMERA>
|
template<class CAMERA>
|
||||||
class TriangulationFactor: public NoiseModelFactor1<Point3> {
|
class TriangulationFactor: public NoiseModelFactor1<Point3> {
|
||||||
|
|
|
@ -28,7 +28,7 @@ namespace gtsam {
|
||||||
/**
|
/**
|
||||||
* A class for a measurement predicted by "between(config[key1],config[key2])"
|
* A class for a measurement predicted by "between(config[key1],config[key2])"
|
||||||
* @tparam VALUE the Value type
|
* @tparam VALUE the Value type
|
||||||
* @addtogroup SLAM
|
* @ingroup SLAM
|
||||||
*/
|
*/
|
||||||
template<class VALUE>
|
template<class VALUE>
|
||||||
class BetweenFactorEM: public NonlinearFactor {
|
class BetweenFactorEM: public NonlinearFactor {
|
||||||
|
|
|
@ -25,7 +25,7 @@ namespace gtsam {
|
||||||
/**
|
/**
|
||||||
* A class to model GPS measurements, including a bias term which models
|
* A class to model GPS measurements, including a bias term which models
|
||||||
* common-mode errors and that can be partially corrected if other sensors are used
|
* common-mode errors and that can be partially corrected if other sensors are used
|
||||||
* @addtogroup SLAM
|
* @ingroup SLAM
|
||||||
*/
|
*/
|
||||||
class BiasedGPSFactor: public NoiseModelFactor2<Pose3, Point3> {
|
class BiasedGPSFactor: public NoiseModelFactor2<Pose3, Point3> {
|
||||||
|
|
||||||
|
|
|
@ -29,7 +29,7 @@ namespace gtsam {
|
||||||
/**
|
/**
|
||||||
* Non-linear factor for a constraint derived from a 2D measurement. The calibration is known here.
|
* Non-linear factor for a constraint derived from a 2D measurement. The calibration is known here.
|
||||||
* i.e. the main building block for visual SLAM.
|
* i.e. the main building block for visual SLAM.
|
||||||
* @addtogroup SLAM
|
* @ingroup SLAM
|
||||||
*/
|
*/
|
||||||
template<class POSE, class LANDMARK, class CALIBRATION = Cal3_S2>
|
template<class POSE, class LANDMARK, class CALIBRATION = Cal3_S2>
|
||||||
class MultiProjectionFactor: public NoiseModelFactor {
|
class MultiProjectionFactor: public NoiseModelFactor {
|
||||||
|
|
|
@ -26,7 +26,7 @@ namespace gtsam {
|
||||||
/**
|
/**
|
||||||
* A class for a measurement predicted by "between(config[key1],config[key2])"
|
* A class for a measurement predicted by "between(config[key1],config[key2])"
|
||||||
* @tparam POSE the Pose type
|
* @tparam POSE the Pose type
|
||||||
* @addtogroup SLAM
|
* @ingroup SLAM
|
||||||
*/
|
*/
|
||||||
template<class POSE>
|
template<class POSE>
|
||||||
class PoseBetweenFactor: public NoiseModelFactor2<POSE, POSE> {
|
class PoseBetweenFactor: public NoiseModelFactor2<POSE, POSE> {
|
||||||
|
|
|
@ -23,7 +23,7 @@ namespace gtsam {
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* A class for a soft prior on any Value type
|
* A class for a soft prior on any Value type
|
||||||
* @addtogroup SLAM
|
* @ingroup SLAM
|
||||||
*/
|
*/
|
||||||
template<class POSE>
|
template<class POSE>
|
||||||
class PosePriorFactor: public NoiseModelFactor1<POSE> {
|
class PosePriorFactor: public NoiseModelFactor1<POSE> {
|
||||||
|
|
|
@ -18,7 +18,7 @@ namespace gtsam {
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* A class for a measurement between a pose and a point.
|
* A class for a measurement between a pose and a point.
|
||||||
* @addtogroup SLAM
|
* @ingroup SLAM
|
||||||
*/
|
*/
|
||||||
template<typename POSE = Pose3, typename POINT = Point3>
|
template<typename POSE = Pose3, typename POINT = Point3>
|
||||||
class PoseToPointFactor : public NoiseModelFactor2<POSE, POINT> {
|
class PoseToPointFactor : public NoiseModelFactor2<POSE, POINT> {
|
||||||
|
|
|
@ -28,7 +28,7 @@ namespace gtsam {
|
||||||
/**
|
/**
|
||||||
* Non-linear factor for a constraint derived from a 2D measurement. The calibration is known here.
|
* Non-linear factor for a constraint derived from a 2D measurement. The calibration is known here.
|
||||||
* i.e. the main building block for visual SLAM.
|
* i.e. the main building block for visual SLAM.
|
||||||
* @addtogroup SLAM
|
* @ingroup SLAM
|
||||||
*/
|
*/
|
||||||
template<class POSE, class LANDMARK, class CALIBRATION = Cal3_S2>
|
template<class POSE, class LANDMARK, class CALIBRATION = Cal3_S2>
|
||||||
class ProjectionFactorPPP: public NoiseModelFactor3<POSE, POSE, LANDMARK> {
|
class ProjectionFactorPPP: public NoiseModelFactor3<POSE, POSE, LANDMARK> {
|
||||||
|
|
|
@ -30,7 +30,7 @@ namespace gtsam {
|
||||||
/**
|
/**
|
||||||
* Non-linear factor for a constraint derived from a 2D measurement. This factor
|
* Non-linear factor for a constraint derived from a 2D measurement. This factor
|
||||||
* estimates the body pose, body-camera transform, 3D landmark, and calibration.
|
* estimates the body pose, body-camera transform, 3D landmark, and calibration.
|
||||||
* @addtogroup SLAM
|
* @ingroup SLAM
|
||||||
*/
|
*/
|
||||||
template <class POSE, class LANDMARK, class CALIBRATION = Cal3_S2>
|
template <class POSE, class LANDMARK, class CALIBRATION = Cal3_S2>
|
||||||
class GTSAM_UNSTABLE_EXPORT ProjectionFactorPPPC
|
class GTSAM_UNSTABLE_EXPORT ProjectionFactorPPPC
|
||||||
|
|
|
@ -38,7 +38,7 @@ namespace gtsam {
|
||||||
* define the alpha = (t_p - t_A) / (t_B - t_A), we will use the pose
|
* define the alpha = (t_p - t_A) / (t_B - t_A), we will use the pose
|
||||||
* interpolated between A and B by the alpha to project the corresponding
|
* interpolated between A and B by the alpha to project the corresponding
|
||||||
* landmark to Point2.
|
* landmark to Point2.
|
||||||
* @addtogroup SLAM
|
* @ingroup SLAM
|
||||||
*/
|
*/
|
||||||
|
|
||||||
class GTSAM_UNSTABLE_EXPORT ProjectionFactorRollingShutter
|
class GTSAM_UNSTABLE_EXPORT ProjectionFactorRollingShutter
|
||||||
|
|
|
@ -25,7 +25,7 @@
|
||||||
namespace gtsam {
|
namespace gtsam {
|
||||||
/**
|
/**
|
||||||
*
|
*
|
||||||
* @addtogroup SLAM
|
* @ingroup SLAM
|
||||||
*
|
*
|
||||||
* If you are using the factor, please cite:
|
* If you are using the factor, please cite:
|
||||||
* L. Carlone, Z. Kira, C. Beall, V. Indelman, F. Dellaert,
|
* L. Carlone, Z. Kira, C. Beall, V. Indelman, F. Dellaert,
|
||||||
|
@ -39,7 +39,7 @@ namespace gtsam {
|
||||||
* shutter model of the camera with given readout time. The factor requires that
|
* shutter model of the camera with given readout time. The factor requires that
|
||||||
* values contain (for each pixel observation) two consecutive camera poses from
|
* values contain (for each pixel observation) two consecutive camera poses from
|
||||||
* which the pixel observation pose can be interpolated.
|
* which the pixel observation pose can be interpolated.
|
||||||
* @addtogroup SLAM
|
* @ingroup SLAM
|
||||||
*/
|
*/
|
||||||
template <class CAMERA>
|
template <class CAMERA>
|
||||||
class GTSAM_UNSTABLE_EXPORT SmartProjectionPoseFactorRollingShutter
|
class GTSAM_UNSTABLE_EXPORT SmartProjectionPoseFactorRollingShutter
|
||||||
|
|
|
@ -24,7 +24,7 @@ namespace gtsam {
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Smart factor for range SLAM
|
* Smart factor for range SLAM
|
||||||
* @addtogroup SLAM
|
* @ingroup SLAM
|
||||||
*/
|
*/
|
||||||
class SmartRangeFactor: public NoiseModelFactor {
|
class SmartRangeFactor: public NoiseModelFactor {
|
||||||
protected:
|
protected:
|
||||||
|
|
|
@ -23,7 +23,7 @@
|
||||||
namespace gtsam {
|
namespace gtsam {
|
||||||
/**
|
/**
|
||||||
*
|
*
|
||||||
* @addtogroup SLAM
|
* @ingroup SLAM
|
||||||
*
|
*
|
||||||
* If you are using the factor, please cite:
|
* If you are using the factor, please cite:
|
||||||
* L. Carlone, Z. Kira, C. Beall, V. Indelman, F. Dellaert,
|
* L. Carlone, Z. Kira, C. Beall, V. Indelman, F. Dellaert,
|
||||||
|
@ -38,7 +38,7 @@ namespace gtsam {
|
||||||
* calibration or the same calibration can be shared by multiple cameras. This
|
* calibration or the same calibration can be shared by multiple cameras. This
|
||||||
* factor requires that values contain the involved poses and extrinsics (both
|
* factor requires that values contain the involved poses and extrinsics (both
|
||||||
* are Pose3 variables).
|
* are Pose3 variables).
|
||||||
* @addtogroup SLAM
|
* @ingroup SLAM
|
||||||
*/
|
*/
|
||||||
class GTSAM_UNSTABLE_EXPORT SmartStereoProjectionFactorPP
|
class GTSAM_UNSTABLE_EXPORT SmartStereoProjectionFactorPP
|
||||||
: public SmartStereoProjectionFactor {
|
: public SmartStereoProjectionFactor {
|
||||||
|
|
|
@ -26,7 +26,7 @@
|
||||||
namespace gtsam {
|
namespace gtsam {
|
||||||
/**
|
/**
|
||||||
*
|
*
|
||||||
* @addtogroup SLAM
|
* @ingroup SLAM
|
||||||
*
|
*
|
||||||
* If you are using the factor, please cite:
|
* If you are using the factor, please cite:
|
||||||
* L. Carlone, Z. Kira, C. Beall, V. Indelman, F. Dellaert,
|
* L. Carlone, Z. Kira, C. Beall, V. Indelman, F. Dellaert,
|
||||||
|
@ -41,7 +41,7 @@ namespace gtsam {
|
||||||
* has its own calibration.
|
* has its own calibration.
|
||||||
* The factor only constrains poses (variable dimension is 6).
|
* The factor only constrains poses (variable dimension is 6).
|
||||||
* This factor requires that values contains the involved poses (Pose3).
|
* This factor requires that values contains the involved poses (Pose3).
|
||||||
* @addtogroup SLAM
|
* @ingroup SLAM
|
||||||
*/
|
*/
|
||||||
class GTSAM_UNSTABLE_EXPORT SmartStereoProjectionPoseFactor
|
class GTSAM_UNSTABLE_EXPORT SmartStereoProjectionPoseFactor
|
||||||
: public SmartStereoProjectionFactor {
|
: public SmartStereoProjectionFactor {
|
||||||
|
|
|
@ -29,7 +29,7 @@ namespace gtsam {
|
||||||
/**
|
/**
|
||||||
* A class for a measurement predicted by "between(config[key1],config[key2])"
|
* A class for a measurement predicted by "between(config[key1],config[key2])"
|
||||||
* @tparam VALUE the Value type
|
* @tparam VALUE the Value type
|
||||||
* @addtogroup SLAM
|
* @ingroup SLAM
|
||||||
*/
|
*/
|
||||||
template<class VALUE>
|
template<class VALUE>
|
||||||
class TransformBtwRobotsUnaryFactor: public NonlinearFactor { // TODO why not NoiseModelFactor1 ?
|
class TransformBtwRobotsUnaryFactor: public NonlinearFactor { // TODO why not NoiseModelFactor1 ?
|
||||||
|
|
|
@ -31,7 +31,7 @@ namespace gtsam {
|
||||||
/**
|
/**
|
||||||
* A class for a measurement predicted by "between(config[key1],config[key2])"
|
* A class for a measurement predicted by "between(config[key1],config[key2])"
|
||||||
* @tparam VALUE the Value type
|
* @tparam VALUE the Value type
|
||||||
* @addtogroup SLAM
|
* @ingroup SLAM
|
||||||
*/
|
*/
|
||||||
template<class VALUE>
|
template<class VALUE>
|
||||||
class TransformBtwRobotsUnaryFactorEM: public NonlinearFactor {
|
class TransformBtwRobotsUnaryFactorEM: public NonlinearFactor {
|
||||||
|
|
Loading…
Reference in New Issue