fix doxygen warnings due to groups and and incorrect filenames

release/4.3a0
Varun Agrawal 2022-07-26 15:59:32 -04:00
parent 3353ce6440
commit c82981f217
31 changed files with 47 additions and 36 deletions

View File

@ -10,7 +10,7 @@
* -------------------------------------------------------------------------- */
/**
* @file ParamaterMatrix.h
* @file ParameterMatrix.h
* @brief Define ParameterMatrix class which is used to store values at
* interpolation points.
* @author Varun Agrawal, Frank Dellaert

View File

@ -38,7 +38,7 @@ class GTSAM_EXPORT Cal3_S2Stereo : public Cal3_S2 {
using shared_ptr = boost::shared_ptr<Cal3_S2Stereo>;
/// @name Standard Constructors
/// @
/// @{
/// default calibration leaves coordinates unchanged
Cal3_S2Stereo() = default;
@ -55,6 +55,8 @@ class GTSAM_EXPORT Cal3_S2Stereo : public Cal3_S2 {
Cal3_S2Stereo(double fov, int w, int h, double b)
: Cal3_S2(fov, w, h), b_(b) {}
/// @}
/**
* Convert intrinsic coordinates xy to image coordinates uv, fixed derivaitves
* @param p point in intrinsic coordinates
@ -82,7 +84,6 @@ class GTSAM_EXPORT Cal3_S2Stereo : public Cal3_S2 {
*/
Vector3 calibrate(const Vector3& p) const { return Cal3_S2::calibrate(p); }
/// @}
/// @name Testable
/// @{

View File

@ -133,8 +133,6 @@ public:
inline double distance() const {
return d_;
}
/// @}
};
template<> struct traits<OrientedPlane3> : public internal::Manifold<

View File

@ -27,7 +27,6 @@
namespace gtsam {
using std::vector;
using Point3Pairs = vector<Point3Pair>;
/** instantiate concept checks */
GTSAM_CONCEPT_POSE_INST(Pose3)

View File

@ -83,7 +83,7 @@ public:
* A pose aTb is estimated between pairs (a_point, b_point) such that a_point = aTb * b_point
* Note this allows for noise on the points but in that case the mapping will not be exact.
*/
static boost::optional<Pose3> Align(const std::vector<Point3Pair>& abPointPairs);
static boost::optional<Pose3> Align(const Point3Pairs& abPointPairs);
// Version of Pose3::Align that takes 2 matrices.
static boost::optional<Pose3> Align(const Matrix& a, const Matrix& b);

View File

@ -132,7 +132,7 @@ class GTSAM_EXPORT Similarity2 : public LieGroup<Similarity2, 4> {
* using the algorithm described here:
* http://www5.informatik.uni-erlangen.de/Forschung/Publikationen/2005/Zinsser05-PSR.pdf
*/
static Similarity2 Align(const std::vector<Pose2Pair>& abPosePairs);
static Similarity2 Align(const Pose2Pairs& abPosePairs);
/// @}
/// @name Lie Group

View File

@ -120,7 +120,7 @@ class GTSAM_EXPORT Similarity3 : public LieGroup<Similarity3, 7> {
/**
* Create Similarity3 by aligning at least three point pairs
*/
static Similarity3 Align(const std::vector<Point3Pair>& abPointPairs);
static Similarity3 Align(const Point3Pairs& abPointPairs);
/**
* Create the Similarity3 object that aligns at least two pose pairs.

View File

@ -82,7 +82,6 @@ class GTSAM_EXPORT SphericalCamera {
EmptyCal::shared_ptr emptyCal_;
public:
/// @}
/// @name Standard Constructors
/// @{

View File

@ -106,13 +106,13 @@ class GTSAM_EXPORT HybridGaussianFactorGraph
void add(JacobianFactor&& factor);
/// Add a Jacobian factor as a shared ptr.
void add(boost::shared_ptr<JacobianFactor> factor);
void add(JacobianFactor::shared_ptr factor);
/// Add a DecisionTreeFactor to the factor graph.
void add(DecisionTreeFactor&& factor);
/// Add a DecisionTreeFactor as a shared ptr.
void add(boost::shared_ptr<DecisionTreeFactor> factor);
void add(DecisionTreeFactor::shared_ptr factor);
};
} // namespace gtsam

View File

@ -10,7 +10,7 @@
* -------------------------------------------------------------------------- */
/**
* @file BayesTree-inl.h
* @file BayesTree-inst.h
* @brief Bayes Tree is a tree of cliques of a Bayes Chain
* @author Frank Dellaert
* @author Michael Kaess

View File

@ -1,5 +1,5 @@
/**
* @file EliminatableClusterTree-inst.h
* @file ClusterTree-inst.h
* @date Oct 8, 2013
* @author Kai Ni
* @author Richard Roberts

View File

@ -1,5 +1,5 @@
/**
* @file EliminatableClusterTree.h
* @file ClusterTree.h
* @date Oct 8, 2013
* @author Kai Ni
* @author Richard Roberts
@ -139,7 +139,6 @@ class ClusterTree {
const KeyFormatter& keyFormatter = DefaultKeyFormatter) const;
/// @}
/// @name Advanced Interface
/// @{
@ -169,6 +168,7 @@ class ClusterTree {
protected:
/// @name Details
/// @{
/// Assignment operator - makes a deep copy of the tree structure, but only pointers to factors
/// are copied, factors are not cloned.
@ -236,6 +236,7 @@ class EliminatableClusterTree : public ClusterTree<GRAPH> {
protected:
/// @name Details
/// @{
/// Assignment operator - makes a deep copy of the tree structure, but only pointers to factors
/// are copied, factors are not cloned.

View File

@ -10,7 +10,7 @@
* -------------------------------------------------------------------------- */
/**
* @file EliminationTree-inl.h
* @file EliminationTree-inst.h
* @author Frank Dellaert
* @author Richard Roberts
* @date Oct 13, 2010

View File

@ -10,7 +10,7 @@
* -------------------------------------------------------------------------- */
/**
* @file FactorGraph-inl.h
* @file FactorGraph-inst.h
* @brief Factor Graph Base Class
* @author Carlos Nieto
* @author Frank Dellaert

View File

@ -10,7 +10,7 @@
* -------------------------------------------------------------------------- */
/**
* @file ISAM-inl.h
* @file ISAM-inst.h
* @brief Incremental update functionality (iSAM) for BayesTree.
* @author Michael Kaess
*/

View File

@ -89,7 +89,8 @@ public:
*/
FastMap<Key, size_t> invert() const;
/// @name Fill-reducing Orderings @{
/// @name Fill-reducing Orderings
/// @{
/// Compute a fill-reducing ordering using COLAMD from a factor graph (see details for note on
/// performance). This internally builds a VariableIndex so if you already have a VariableIndex,
@ -215,7 +216,8 @@ public:
/// @}
/// @name Named Constructors @{
/// @name Named Constructors
/// @{
template<class FACTOR_GRAPH>
static Ordering Create(OrderingType orderingType,
@ -241,7 +243,8 @@ public:
/// @}
/// @name Testable @{
/// @name Testable
/// @{
GTSAM_EXPORT
void print(const std::string& str = "", const KeyFormatter& keyFormatter =

View File

@ -10,7 +10,7 @@
* -------------------------------------------------------------------------- */
/**
* @file Pose3AttitudeFactor.h
* @file AttitudeFactor.h
* @author Frank Dellaert
* @brief Header file for Attitude factor
* @date January 28, 2014

View File

@ -36,6 +36,9 @@ public:
/// dimension of the variable - used to autodetect sizes
static const size_t dimension = 6;
/// @name Standard Constructors
/// @{
ConstantBias() :
biasAcc_(0.0, 0.0, 0.0), biasGyro_(0.0, 0.0, 0.0) {
}
@ -48,6 +51,8 @@ public:
biasAcc_(v.head<3>()), biasGyro_(v.tail<3>()) {
}
/// @}
/** return the accelerometer and gyro biases in a single vector */
Vector6 vector() const {
Vector6 v;
@ -83,7 +88,6 @@ public:
return measurement - biasGyro_;
}
/// @}
/// @name Testable
/// @{

View File

@ -10,7 +10,7 @@
* -------------------------------------------------------------------------- */
/**
* @file NonlinearISAM-inl.h
* @file NonlinearISAM.cpp
* @date Jan 19, 2010
* @author Viorela Ila and Richard Roberts
*/

View File

@ -59,6 +59,9 @@ namespace gtsam {
// shorthand for a smart pointer to a factor
typedef typename boost::shared_ptr<BetweenFactor> shared_ptr;
/// @name Standard Constructors
/// @{
/** default constructor - only use for serialization */
BetweenFactor() {}
@ -68,6 +71,8 @@ namespace gtsam {
Base(model, key1, key2), measured_(measured) {
}
/// @}
~BetweenFactor() override {}
/// @return a deep copy of this factor
@ -75,7 +80,6 @@ namespace gtsam {
return boost::static_pointer_cast<gtsam::NonlinearFactor>(
gtsam::NonlinearFactor::shared_ptr(new This(*this))); }
/// @}
/// @name Testable
/// @{

View File

@ -10,7 +10,7 @@
* -------------------------------------------------------------------------- */
/**
* @file SmartFactorParams
* @file SmartFactorParams.h
* @brief Collect common parameters for SmartProjection and SmartStereoProjection factors
* @author Luca Carlone
* @author Zsolt Kira

View File

@ -10,7 +10,7 @@
* -------------------------------------------------------------------------- */
/**
* @file GenericStereoFactor.h
* @file StereoFactor.h
* @brief A non-linear factor for stereo measurements
* @author Alireza Fathi
* @author Chris Beall

View File

@ -103,6 +103,7 @@ namespace gtsam {
/// @}
/// @name Testable
/// @{
/** Print with optional formatter */
void print(

View File

@ -22,7 +22,8 @@ protected:
public:
static const size_t dimension = 2;
// constructors
/// @name Constructors
/// @{
/** Default constructor - straight ahead */
BearingS2() {}

View File

@ -10,7 +10,7 @@
* -------------------------------------------------------------------------- */
/**
* @file Event
* @file Event.cpp
* @brief Space-time event
* @author Frank Dellaert
* @author Jay Chakravarty

View File

@ -10,7 +10,7 @@
* -------------------------------------------------------------------------- */
/**
* @file Event
* @file Event.h
* @brief Space-time event
* @author Frank Dellaert
* @author Jay Chakravarty

View File

@ -10,7 +10,7 @@
* -------------------------------------------------------------------------- */
/**
* @file QPParser.cpp
* @file QPSParser.cpp
* @author Ivan Dario Jimenez
* @date 3/5/16
*/

View File

@ -10,7 +10,7 @@
* -------------------------------------------------------------------------- */
/**
* @file QPParser.h
* @file QPSParser.h
* @brief QPS parser implementation
* @author Ivan Dario Jimenez
* @date 3/5/16

View File

@ -1,5 +1,5 @@
/**
* @file Mechanization_bRn.cpp
* @file Mechanization_bRn2.cpp
* @date Jan 25, 2012
* @author Chris Beall
* @author Frank Dellaert

View File

@ -1,5 +1,5 @@
/**
* @file Mechanization_bRn.h
* @file Mechanization_bRn2.h
* @date Jan 25, 2012
* @author Chris Beall
* @author Frank Dellaert

View File

@ -1,5 +1,5 @@
/**
* @file PoseToPointFactor.hpp
* @file PoseToPointFactor.h
* @brief This factor can be used to model relative position measurements
* from a (2D or 3D) pose to a landmark
* @author David Wisth