diff --git a/gtsam/base/LieScalar.h b/gtsam/base/LieScalar.h index 505f06921..3b9c7037a 100644 --- a/gtsam/base/LieScalar.h +++ b/gtsam/base/LieScalar.h @@ -36,7 +36,7 @@ namespace gtsam { /** access the underlying value */ double value() const { return d_; } - /** print @param s optional string naming the object */ + /** print @param name optional string naming the object */ inline void print(const std::string& name="") const { std::cout << name << ": " << d_ << std::endl; } diff --git a/gtsam/base/LieVector.h b/gtsam/base/LieVector.h index 82455e173..ef31e93cc 100644 --- a/gtsam/base/LieVector.h +++ b/gtsam/base/LieVector.h @@ -52,7 +52,7 @@ struct LieVector : public Vector, public DerivedValue { return static_cast(*this); } - /** print @param s optional string naming the object */ + /** print @param name optional string naming the object */ inline void print(const std::string& name="") const { gtsam::print(vector(), name); } diff --git a/gtsam/base/Matrix.h b/gtsam/base/Matrix.h index 553fb5b89..adb4ee36b 100644 --- a/gtsam/base/Matrix.h +++ b/gtsam/base/Matrix.h @@ -217,8 +217,8 @@ void insertSub(Matrix& fullMatrix, const Matrix& subMatrix, size_t i, size_t j); /** * Extracts a column view from a matrix that avoids a copy - * @param matrix to extract column from - * @param index of the column + * @param A matrix to extract column from + * @param j index of the column * @return a const view of the matrix */ template @@ -228,8 +228,8 @@ const typename MATRIX::ConstColXpr column(const MATRIX& A, size_t j) { /** * Extracts a row view from a matrix that avoids a copy - * @param matrix to extract row from - * @param index of the row + * @param A matrix to extract row from + * @param j index of the row * @return a const view of the matrix */ template @@ -362,7 +362,7 @@ Vector backSubstituteUpper(const Vector& b, const Matrix& U, bool unit=false); * @param unit, set true if unit triangular * @return the solution x of L*x=b */ -Vector backSubstituteLower(const Matrix& L, const Vector& d, bool unit=false); +Vector backSubstituteLower(const Matrix& L, const Vector& b, bool unit=false); /** * create a matrix by stacking other matrices diff --git a/gtsam/base/TestableAssertions.h b/gtsam/base/TestableAssertions.h index dad1c6d20..10daafbb4 100644 --- a/gtsam/base/TestableAssertions.h +++ b/gtsam/base/TestableAssertions.h @@ -81,7 +81,7 @@ bool assert_equal(const V& expected, const boost::optional& actual, do /** * Version of assert_equals to work with vectors - * @DEPRECIATED: use container equals instead + * \deprecated: use container equals instead */ template bool assert_equal(const std::vector& expected, const std::vector& actual, double tol = 1e-9) { diff --git a/gtsam/base/Vector.h b/gtsam/base/Vector.h index 6019bbd33..0de7f519a 100644 --- a/gtsam/base/Vector.h +++ b/gtsam/base/Vector.h @@ -73,8 +73,8 @@ Vector Vector_(const std::vector& data); /** * Create vector initialized to a constant value - * @param size - * @param constant value + * @param n is the size of the vector + * @param value is a constant value to insert into the vector */ Vector repeat(size_t n, double value); @@ -82,7 +82,7 @@ Vector repeat(size_t n, double value); * Create basis vector of dimension n, * with a constant in spot i * @param n is the size of the vector - * @param index of the one + * @param i index of the one * @param value is the value to insert into the vector * @return delta vector */ @@ -92,20 +92,20 @@ Vector delta(size_t n, size_t i, double value); * Create basis vector of dimension n, * with one in spot i * @param n is the size of the vector - * @param index of the one + * @param i index of the one * @return basis vector */ inline Vector basis(size_t n, size_t i) { return delta(n, i, 1.0); } /** * Create zero vector - * @param size + * @param n size */ inline Vector zero(size_t n) { return Vector::Zero(n);} /** * Create vector initialized to ones - * @param size + * @param n size */ inline Vector ones(size_t n) { return Vector::Ones(n); } @@ -249,35 +249,35 @@ double sum(const Vector &a); /** * Calculates L2 norm for a vector * modeled after boost.ublas for compatibility - * @param vector + * @param v vector * @return the L2 norm */ double norm_2(const Vector& v); /** - * elementwise reciprocal of vector elements + * Elementwise reciprocal of vector elements * @param a vector * @return [1/a(i)] */ Vector reciprocal(const Vector &a); /** - * elementwise sqrt of vector elements - * @param a vector + * Elementwise sqrt of vector elements + * @param v is a vector * @return [sqrt(a(i))] */ Vector esqrt(const Vector& v); /** - * absolut values of vector elements - * @param a vector + * Absolute values of vector elements + * @param v is a vector * @return [abs(a(i))] */ Vector abs(const Vector& v); /** - * return the max element of a vector - * @param a vector + * Return the max element of a vector + * @param a is a vector * @return max(a) */ double max(const Vector &a); @@ -300,13 +300,13 @@ inline double inner_prod(const V1 &a, const V2& b) { /** * BLAS Level 1 scal: x <- alpha*x - * @DEPRECIATED: use operators instead + * \deprecated: use operators instead */ inline void scal(double alpha, Vector& x) { x *= alpha; } /** * BLAS Level 1 axpy: y <- alpha*x + y - * @DEPRECIATED: use operators instead + * \deprecated: use operators instead */ template inline void axpy(double alpha, const V1& x, V2& y) { diff --git a/gtsam/discrete/DiscreteConditional.h b/gtsam/discrete/DiscreteConditional.h index 6c724bf7f..c95cc36d6 100644 --- a/gtsam/discrete/DiscreteConditional.h +++ b/gtsam/discrete/DiscreteConditional.h @@ -89,14 +89,14 @@ namespace gtsam { /** * solve a conditional - * @param parentsAssignment Known values of the parents + * @param parentsValues Known values of the parents * @return MPE value of the child (1 frontal variable). */ size_t solve(const Values& parentsValues) const; /** * sample - * @param parentsAssignment Known values of the parents + * @param parentsValues Known values of the parents * @return sample from conditional */ size_t sample(const Values& parentsValues) const; diff --git a/gtsam/discrete/DiscreteMarginals.h b/gtsam/discrete/DiscreteMarginals.h index fdc3398da..1e89286a8 100644 --- a/gtsam/discrete/DiscreteMarginals.h +++ b/gtsam/discrete/DiscreteMarginals.h @@ -55,7 +55,7 @@ namespace gtsam { } /** Compute the marginal of a single variable - * @param KEY DiscreteKey of the Variable + * @param key DiscreteKey of the Variable * @return Vector of marginal probabilities */ Vector marginalProbabilities(const DiscreteKey& key) const { diff --git a/gtsam/geometry/Rot2.h b/gtsam/geometry/Rot2.h index 9528934a0..d0f3e4c14 100644 --- a/gtsam/geometry/Rot2.h +++ b/gtsam/geometry/Rot2.h @@ -83,7 +83,7 @@ namespace gtsam { /** * Named constructor with derivative * Calculate relative bearing to a landmark in local coordinate frame - * @param point 2D location of landmark + * @param d 2D location of landmark * @param H optional reference for Jacobian * @return 2D rotation \in SO(2) */ diff --git a/gtsam/geometry/Rot3.h b/gtsam/geometry/Rot3.h index 0c6b31a81..c0fbfc999 100644 --- a/gtsam/geometry/Rot3.h +++ b/gtsam/geometry/Rot3.h @@ -394,7 +394,7 @@ namespace gtsam { * such that A = R*Q = R*Qz'*Qy'*Qx'. When A is a rotation matrix, R will * be the identity and Q is a yaw-pitch-roll decomposition of A. * The implementation uses Givens rotations and is based on Hartley-Zisserman. - * @param a 3 by 3 matrix A=RQ + * @param A 3 by 3 matrix A=RQ * @return an upper triangular matrix R * @return a vector [thetax, thetay, thetaz] in radians. */ diff --git a/gtsam/inference/EliminationTree.h b/gtsam/inference/EliminationTree.h index 0b01f0586..eb45deaf0 100644 --- a/gtsam/inference/EliminationTree.h +++ b/gtsam/inference/EliminationTree.h @@ -157,7 +157,7 @@ public: * disconnected graphs, a workaround is to create zero-information factors to * bridge the disconnects. To do this, create any factor type (e.g. * BetweenFactor or RangeFactor) with the noise model - * \ref sharedPrecision(dim, 0.0), where \c dim is the appropriate + * sharedPrecision(dim, 0.0), where \c dim is the appropriate * dimensionality for that factor. */ struct DisconnectedGraphException : public std::exception { diff --git a/gtsam/inference/Factor.h b/gtsam/inference/Factor.h index 87c1f3860..b73eff9d0 100644 --- a/gtsam/inference/Factor.h +++ b/gtsam/inference/Factor.h @@ -45,7 +45,7 @@ template class Conditional; * typedefs to refer to the associated conditional and shared_ptr types of the * derived class. See IndexFactor, JacobianFactor, etc. for examples. * - * This class is \bold{not} virtual for performance reasons - derived symbolic classes, + * This class is \b not virtual for performance reasons - derived symbolic classes, * IndexFactor and IndexConditional, need to be created and destroyed quickly * during symbolic elimination. GaussianFactor and NonlinearFactor are virtual. * \nosubgrouping diff --git a/gtsam/inference/FactorGraph.h b/gtsam/inference/FactorGraph.h index 33cdd02a1..90e9e8a1f 100644 --- a/gtsam/inference/FactorGraph.h +++ b/gtsam/inference/FactorGraph.h @@ -245,8 +245,8 @@ template class BayesTree; /** * static function that combines two factor graphs - * @param const &fg1 Linear factor graph - * @param const &fg2 Linear factor graph + * @param fg1 Linear factor graph + * @param fg2 Linear factor graph * @return a new combined factor graph */ template diff --git a/gtsam/linear/GaussianFactorGraph.h b/gtsam/linear/GaussianFactorGraph.h index 8a5fe47e7..07c2e94ad 100644 --- a/gtsam/linear/GaussianFactorGraph.h +++ b/gtsam/linear/GaussianFactorGraph.h @@ -151,9 +151,9 @@ namespace gtsam { } /** - * static function that combines two factor graphs - * @param const &lfg1 Linear factor graph - * @param const &lfg2 Linear factor graph + * Static function that combines two factor graphs. + * @param lfg1 Linear factor graph + * @param lfg2 Linear factor graph * @return a new combined factor graph */ static GaussianFactorGraph combine2(const GaussianFactorGraph& lfg1, diff --git a/gtsam/linear/GaussianMultifrontalSolver.h b/gtsam/linear/GaussianMultifrontalSolver.h index 6adde1aa5..a38bb3161 100644 --- a/gtsam/linear/GaussianMultifrontalSolver.h +++ b/gtsam/linear/GaussianMultifrontalSolver.h @@ -116,7 +116,7 @@ public: * all of the other variables. This function returns the result as a mean * vector and covariance matrix. Compared to marginalCanonical, which * returns a GaussianConditional, this function back-substitutes the R factor - * to obtain the mean, then computes \Sigma = (R^T * R)^-1. + * to obtain the mean, then computes \f$ \Sigma = (R^T * R)^{-1} \f$. */ Matrix marginalCovariance(Index j) const; diff --git a/gtsam/linear/GaussianSequentialSolver.h b/gtsam/linear/GaussianSequentialSolver.h index 36e93bcf4..8fd8e2dbb 100644 --- a/gtsam/linear/GaussianSequentialSolver.h +++ b/gtsam/linear/GaussianSequentialSolver.h @@ -115,7 +115,7 @@ public: * all of the other variables. This function returns the result as a mean * vector and covariance matrix. Compared to marginalCanonical, which * returns a GaussianConditional, this function back-substitutes the R factor - * to obtain the mean, then computes \Sigma = (R^T * R)^-1. + * to obtain the mean, then computes \f$ \Sigma = (R^T * R)^{-1} \f$. */ Matrix marginalCovariance(Index j) const; diff --git a/gtsam/linear/HessianFactor.h b/gtsam/linear/HessianFactor.h index d9da6e472..5bbee3708 100644 --- a/gtsam/linear/HessianFactor.h +++ b/gtsam/linear/HessianFactor.h @@ -237,7 +237,7 @@ namespace gtsam { /** Return the number of columns and rows of the Hessian matrix */ size_t rows() const { return info_.rows(); } - /** Return a view of the block at (j1,j2) of the upper-triangular part of the + /** Return a view of the block at (j1,j2) of the upper-triangular part of the * information matrix \f$ H \f$, no data is copied. See HessianFactor class documentation * above to explain that only the upper-triangular part of the information matrix is stored * and returned by this function. @@ -249,7 +249,7 @@ namespace gtsam { */ constBlock info(const_iterator j1, const_iterator j2) const { return info_(j1-begin(), j2-begin()); } - /** Return the upper-triangular part of the full *augmented* information matrix, + /** Return the upper-triangular part of the full *augmented* information matrix, * as described above. See HessianFactor class documentation above to explain that only the * upper-triangular part of the information matrix is stored and returned by this function. */ diff --git a/gtsam/linear/JacobianFactorGraph.cpp b/gtsam/linear/JacobianFactorGraph.cpp index 835783d4a..b02375a79 100644 --- a/gtsam/linear/JacobianFactorGraph.cpp +++ b/gtsam/linear/JacobianFactorGraph.cpp @@ -1,7 +1,7 @@ /** * @file JacobianFactorGraph.h * @date Jun 6, 2012 - * @Author Yong Dian Jian + * @author Yong Dian Jian */ #include diff --git a/gtsam/linear/JacobianFactorGraph.h b/gtsam/linear/JacobianFactorGraph.h index f5e78810a..8d240c00e 100644 --- a/gtsam/linear/JacobianFactorGraph.h +++ b/gtsam/linear/JacobianFactorGraph.h @@ -13,7 +13,7 @@ * @file JacobianFactorGraph.cpp * @date Jun 6, 2012 * @brief Linear Algebra Operations for a JacobianFactorGraph - * @Author Yong Dian Jian + * @author Yong Dian Jian */ #pragma once diff --git a/gtsam/linear/VectorValues.h b/gtsam/linear/VectorValues.h index 7939b486d..f3ef57418 100644 --- a/gtsam/linear/VectorValues.h +++ b/gtsam/linear/VectorValues.h @@ -147,7 +147,7 @@ namespace gtsam { /** Insert a vector \c value with index \c j. * Causes reallocation. Can be used to insert values in any order, but - * throws an invalid_argument exception if the index \j is already used. + * throws an invalid_argument exception if the index \c j is already used. * @param value The vector to be inserted. * @param j The index with which the value will be associated. */ @@ -171,10 +171,10 @@ namespace gtsam { /** equals required by Testable for unit testing */ bool equals(const VectorValues& x, double tol = 1e-9) const; - /// @} + /// @{ /// \anchor AdvancedConstructors /// @name Advanced Constructors - /// @{ + /// @} /** Construct from a container of variable dimensions (in variable order), without initializing any values. */ template diff --git a/gtsam/nonlinear/DoglegOptimizer.cpp b/gtsam/nonlinear/DoglegOptimizer.cpp index 3edb35a76..b0ee9f460 100644 --- a/gtsam/nonlinear/DoglegOptimizer.cpp +++ b/gtsam/nonlinear/DoglegOptimizer.cpp @@ -13,7 +13,7 @@ * @file DoglegOptimizer.cpp * @brief * @author Richard Roberts - * @created Feb 26, 2012 + * @date Feb 26, 2012 */ #include diff --git a/gtsam/nonlinear/DoglegOptimizer.h b/gtsam/nonlinear/DoglegOptimizer.h index 7edb43ca9..c8ac636cf 100644 --- a/gtsam/nonlinear/DoglegOptimizer.h +++ b/gtsam/nonlinear/DoglegOptimizer.h @@ -13,7 +13,7 @@ * @file DoglegOptimizer.h * @brief * @author Richard Roberts - * @created Feb 26, 2012 + * @date Feb 26, 2012 */ #pragma once diff --git a/gtsam/nonlinear/DoglegOptimizerImpl.h b/gtsam/nonlinear/DoglegOptimizerImpl.h index 03951babf..737aa2f66 100644 --- a/gtsam/nonlinear/DoglegOptimizerImpl.h +++ b/gtsam/nonlinear/DoglegOptimizerImpl.h @@ -72,7 +72,7 @@ struct DoglegOptimizerImpl { * * The update is computed using a quadratic approximation \f$ M(\delta x) \f$ * of an original nonlinear error function (a NonlinearFactorGraph) \f$ f(x) \f$. - * The quadratic approximation is represented as a GaussianBayesNet \bayesNet, which is + * The quadratic approximation is represented as a GaussianBayesNet \f$ \bayesNet \f$, which is * obtained by eliminating a GaussianFactorGraph resulting from linearizing * the nonlinear factor graph \f$ f(x) \f$. Thus, \f$ M(\delta x) \f$ is * \f[ @@ -93,8 +93,8 @@ struct DoglegOptimizerImpl { * @param Rd The Bayes' net or tree as described above. * @param f The original nonlinear factor graph with which to evaluate the * accuracy of \f$ M(\delta x) \f$ to adjust \f$ \Delta \f$. - * @param x0 The linearization point about which \bayesNet was created - * @param ordering The variable ordering used to create \bayesNet + * @param x0 The linearization point about which \f$ \bayesNet \f$ was created + * @param ordering The variable ordering used to create\f$ \bayesNet \f$ * @param f_error The result of f.error(x0). * @return A DoglegIterationResult containing the new \c Delta, the linear * update \c dx_d, and the resulting nonlinear error \c f_error. @@ -111,7 +111,7 @@ struct DoglegOptimizerImpl { * * The update is computed using a quadratic approximation \f$ M(\delta x) \f$ * of an original nonlinear error function (a NonlinearFactorGraph) \f$ f(x) \f$. - * The quadratic approximation is represented as a GaussianBayesNet \bayesNet, which is + * The quadratic approximation is represented as a GaussianBayesNet \f$ \bayesNet \f$, which is * obtained by eliminating a GaussianFactorGraph resulting from linearizing * the nonlinear factor graph \f$ f(x) \f$. Thus, \f$ M(\delta x) \f$ is * \f[ @@ -134,8 +134,8 @@ struct DoglegOptimizerImpl { * \f$ \| (1-\tau)\delta x_u + \tau\delta x_n \| = \Delta \f$, where \f$ \Delta \f$ * is the trust region radius. * @param Delta Trust region radius - * @param xu Steepest descent minimizer - * @param xn Newton's method minimizer + * @param x_u Steepest descent minimizer + * @param x_n Newton's method minimizer */ static VectorValues ComputeBlend(double Delta, const VectorValues& x_u, const VectorValues& x_n, const bool verbose=false); }; diff --git a/gtsam/nonlinear/GaussNewtonOptimizer.cpp b/gtsam/nonlinear/GaussNewtonOptimizer.cpp index c81369299..c447a39e3 100644 --- a/gtsam/nonlinear/GaussNewtonOptimizer.cpp +++ b/gtsam/nonlinear/GaussNewtonOptimizer.cpp @@ -13,7 +13,7 @@ * @file GaussNewtonOptimizer.cpp * @brief * @author Richard Roberts - * @created Feb 26, 2012 + * @date Feb 26, 2012 */ #include diff --git a/gtsam/nonlinear/GaussNewtonOptimizer.h b/gtsam/nonlinear/GaussNewtonOptimizer.h index 39b64b667..217b6e618 100644 --- a/gtsam/nonlinear/GaussNewtonOptimizer.h +++ b/gtsam/nonlinear/GaussNewtonOptimizer.h @@ -13,7 +13,7 @@ * @file GaussNewtonOptimizer.h * @brief * @author Richard Roberts - * @created Feb 26, 2012 + * @date Feb 26, 2012 */ #pragma once diff --git a/gtsam/nonlinear/LevenbergMarquardtOptimizer.cpp b/gtsam/nonlinear/LevenbergMarquardtOptimizer.cpp index af44eee93..9a5897b41 100644 --- a/gtsam/nonlinear/LevenbergMarquardtOptimizer.cpp +++ b/gtsam/nonlinear/LevenbergMarquardtOptimizer.cpp @@ -13,7 +13,7 @@ * @file LevenbergMarquardtOptimizer.cpp * @brief * @author Richard Roberts - * @created Feb 26, 2012 + * @date Feb 26, 2012 */ #include diff --git a/gtsam/nonlinear/LevenbergMarquardtOptimizer.h b/gtsam/nonlinear/LevenbergMarquardtOptimizer.h index c1fe55c26..aae8e45cc 100644 --- a/gtsam/nonlinear/LevenbergMarquardtOptimizer.h +++ b/gtsam/nonlinear/LevenbergMarquardtOptimizer.h @@ -13,7 +13,7 @@ * @file LevenbergMarquardtOptimizer.h * @brief * @author Richard Roberts - * @created Feb 26, 2012 + * @date Feb 26, 2012 */ #pragma once diff --git a/gtsam/nonlinear/NonlinearOptimizer.h b/gtsam/nonlinear/NonlinearOptimizer.h index 388058ac0..2483aa800 100644 --- a/gtsam/nonlinear/NonlinearOptimizer.h +++ b/gtsam/nonlinear/NonlinearOptimizer.h @@ -229,7 +229,7 @@ protected: }; /** Check whether the relative error decrease is less than relativeErrorTreshold, - * the absolute error decrease is less than absoluteErrorTreshold, or + * the absolute error decrease is less than absoluteErrorTreshold, or * the error itself is less than errorThreshold. */ bool checkConvergence(double relativeErrorTreshold,