diff --git a/gtsam/slam/AntiFactor.h b/gtsam/slam/AntiFactor.h index 19f73c8b9..b5e77b578 100644 --- a/gtsam/slam/AntiFactor.h +++ b/gtsam/slam/AntiFactor.h @@ -26,6 +26,7 @@ namespace gtsam { * 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 * cancels out any affects of the original factor during optimization." + * @addtogroup SLAM */ class AntiFactor: public NonlinearFactor { diff --git a/gtsam/slam/BearingFactor.h b/gtsam/slam/BearingFactor.h index 326491e8c..86a6e159c 100644 --- a/gtsam/slam/BearingFactor.h +++ b/gtsam/slam/BearingFactor.h @@ -24,6 +24,7 @@ namespace gtsam { /** * Binary factor for a bearing measurement + * @addtogroup SLAM */ template class BearingFactor: public NoiseModelFactor2 { diff --git a/gtsam/slam/BearingRangeFactor.h b/gtsam/slam/BearingRangeFactor.h index 52f301b3c..d701054f9 100644 --- a/gtsam/slam/BearingRangeFactor.h +++ b/gtsam/slam/BearingRangeFactor.h @@ -26,6 +26,7 @@ namespace gtsam { /** * Binary factor for a bearing measurement + * @addtogroup SLAM */ template class BearingRangeFactor: public NoiseModelFactor2 { diff --git a/gtsam/slam/BetweenFactor.h b/gtsam/slam/BetweenFactor.h index d93e5fe81..14314ceb7 100644 --- a/gtsam/slam/BetweenFactor.h +++ b/gtsam/slam/BetweenFactor.h @@ -27,6 +27,7 @@ namespace gtsam { /** * A class for a measurement predicted by "between(config[key1],config[key2])" * @tparam VALUE the Value type + * @addtogroup SLAM */ template class BetweenFactor: public NoiseModelFactor2 { diff --git a/gtsam/slam/BoundingConstraint.h b/gtsam/slam/BoundingConstraint.h index 0032d9a05..43d3802c0 100644 --- a/gtsam/slam/BoundingConstraint.h +++ b/gtsam/slam/BoundingConstraint.h @@ -27,6 +27,7 @@ namespace gtsam { * greater/less than a fixed threshold. The function * will need to have its value function implemented to return * a scalar for comparison. + * @addtogroup SLAM */ template struct BoundingConstraint1: public NoiseModelFactor1 { diff --git a/gtsam/slam/GeneralSFMFactor.h b/gtsam/slam/GeneralSFMFactor.h index a9db7dcbe..beb2f1e67 100644 --- a/gtsam/slam/GeneralSFMFactor.h +++ b/gtsam/slam/GeneralSFMFactor.h @@ -29,7 +29,9 @@ namespace gtsam { /** - * Non-linear factor for a constraint derived from a 2D measurement. The calibration is unknown here compared to GenericProjectionFactor + * Non-linear factor for a constraint derived from a 2D measurement. + * The calibration is unknown here compared to GenericProjectionFactor + * @addtogroup SLAM */ template class GeneralSFMFactor: public NoiseModelFactor2 { diff --git a/gtsam/slam/PriorFactor.h b/gtsam/slam/PriorFactor.h index 79ea4c0ce..5bd0ee76f 100644 --- a/gtsam/slam/PriorFactor.h +++ b/gtsam/slam/PriorFactor.h @@ -22,6 +22,7 @@ namespace gtsam { /** * A class for a soft prior on any Value type + * @addtogroup SLAM */ template class PriorFactor: public NoiseModelFactor1 { diff --git a/gtsam/slam/ProjectionFactor.h b/gtsam/slam/ProjectionFactor.h index 048756435..00bb7f36a 100644 --- a/gtsam/slam/ProjectionFactor.h +++ b/gtsam/slam/ProjectionFactor.h @@ -28,6 +28,7 @@ namespace gtsam { /** * 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. + * @addtogroup SLAM */ template class GenericProjectionFactor: public NoiseModelFactor2 { diff --git a/gtsam/slam/RangeFactor.h b/gtsam/slam/RangeFactor.h index 78727f08f..fa4ddb7f2 100644 --- a/gtsam/slam/RangeFactor.h +++ b/gtsam/slam/RangeFactor.h @@ -24,6 +24,7 @@ namespace gtsam { /** * Binary factor for a range measurement + * @addtogroup SLAM */ template class RangeFactor: public NoiseModelFactor2 { diff --git a/gtsam/slam/StereoFactor.h b/gtsam/slam/StereoFactor.h index 94af6e10e..05b37b0ff 100644 --- a/gtsam/slam/StereoFactor.h +++ b/gtsam/slam/StereoFactor.h @@ -23,6 +23,10 @@ namespace gtsam { +/* + * A Generic Stereo Factor + * @addtogroup SLAM + */ template class GenericStereoFactor: public NoiseModelFactor2 { private: