fix latex symbol warnings

release/4.3a0
Varun Agrawal 2022-07-26 16:00:33 -04:00
parent c82981f217
commit fd839e71b6
14 changed files with 25 additions and 24 deletions

View File

@ -26,7 +26,7 @@
#include <type_traits>
namespace gtsam {
/// An shorthand alias for accessing the ::type inside std::enable_if that can be used in a template directly
/// An shorthand alias for accessing the \::type inside std::enable_if that can be used in a template directly
template<bool B, class T = void>
using enable_if_t = typename std::enable_if<B, T>::type;
}

View File

@ -147,7 +147,7 @@ namespace gtsam {
size_t id_;
size_t t_;
size_t tWall_;
double t2_ ; ///< cache the \sum t_i^2
double t2_ ; ///< cache the \f$ \sum t_i^2 \f$
size_t tIt_;
size_t tMax_;
size_t tMin_;

View File

@ -86,7 +86,7 @@ namespace gtsam {
static Rot2 atan2(double y, double x);
/**
* Random, generates random angle \in [-p,pi]
* Random, generates random angle \f$\in\f$ [-pi,pi]
* Example:
* std::mt19937 engine(42);
* Unit3 unit = Unit3::Random(engine);

View File

@ -129,7 +129,7 @@ class GTSAM_EXPORT Rot3 : public LieGroup<Rot3, 3> {
Rot3(double w, double x, double y, double z) : Rot3(Quaternion(w, x, y, z)) {}
/**
* Random, generates a random axis, then random angle \in [-p,pi]
* Random, generates a random axis, then random angle \f$\in\f$ [-pi,pi]
* Example:
* std::mt19937 engine(42);
* Unit3 unit = Unit3::Random(engine);

View File

@ -74,7 +74,7 @@ GTSAM_EXPORT Matrix3 topLeft(const SO4 &Q, OptionalJacobian<9, 6> H = boost::non
/**
* Project to Stiefel manifold of 4*3 orthonormal 3-frames in R^4, i.e., pi(Q)
* -> S \in St(3,4).
* -> \f$ S \in St(3,4) \f$.
*/
GTSAM_EXPORT Matrix43 stiefel(const SO4 &Q, OptionalJacobian<12, 6> H = boost::none);

View File

@ -121,7 +121,8 @@ class SO : public LieGroup<SO<N>, internal::DimensionSO(N)> {
/// currently only defined for SO3.
static SO ClosestTo(const MatrixNN& M);
/// Named constructor that finds chordal mean = argmin_R \sum sqr(|R-R_i|_F),
/// Named constructor that finds chordal mean
/// \f$ mu = argmin_R \sum sqr(|R-R_i|_F) \f$,
/// currently only defined for SO3.
static SO ChordalMean(const std::vector<SO>& rotations);

View File

@ -74,8 +74,8 @@ class AcceleratedPowerMethod : public PowerMethod<Operator> {
/**
* Run accelerated power iteration to get ritzVector with beta and previous
* two ritzVector x0 and x00, and return y = (A * x0 - \beta * x00) / || A * x0
* - \beta * x00 ||
* two ritzVector x0 and x00, and return
* \f$y = (A * x0 - \beta * x00) / || A * x0 - \beta * x00 ||\f$
*/
Vector acceleratedPowerIteration (const Vector &x1, const Vector &x0,
const double beta) const {
@ -86,8 +86,8 @@ class AcceleratedPowerMethod : public PowerMethod<Operator> {
/**
* Run accelerated power iteration to get ritzVector with beta and previous
* two ritzVector x0 and x00, and return y = (A * x0 - \beta * x00) / || A * x0
* - \beta * x00 ||
* two ritzVector x0 and x00, and return
* \f$y = (A * x0 - \beta * x00) / || A * x0 - \beta * x00 ||\f$
*/
Vector acceleratedPowerIteration () const {
Vector y = acceleratedPowerIteration(this->ritzVector_, previousVector_, beta_);

View File

@ -338,7 +338,7 @@ namespace gtsam {
/**
* Compute the gradient at a key:
* \grad f(x_i) = \sum_j G_ij*x_j - g_i
* \f$ \grad f(x_i) = \sum_j G_ij*x_j - g_i \f$
*/
Vector gradient(Key key, const VectorValues& x) const override;

View File

@ -86,8 +86,9 @@ class ExtendedKalmanFilter {
/// @{
/**
* Calculate predictive density P(x_) ~ \int P(x_min) P(x_min, x_)
* The motion model should be given as a factor with key1 for x_min and key2_ for x
* Calculate predictive density
* \f$ P(x_) ~ \int P(x_min) P(x_min, x_)\f$
* The motion model should be given as a factor with key1 for \f$x_min\f$ and key2 for \f$x_\f$
*/
T predict(const NoiseModelFactor& motionFactor);

View File

@ -110,8 +110,8 @@ public:
//*************************************************************************
/**
* This class implements the first position-momentum update rule
* p_k = -D_1 L_d(q_k,q_{k+1},h) = \frac{1}{h}mr^{2}\left(q_{k+1}-q_{k}\right)+mgrh(1-\alpha)\,\sin\left((1-\alpha)q_{k}+\alpha q_{k+1}\right)
* = (1/h)mr^2 (q_{k+1}-q_k) + mgrh(1-alpha) sin ((1-alpha)q_k+\alpha q_{k+1})
* \f$ p_k = -D_1 L_d(q_k,q_{k+1},h) = \frac{1}{h}mr^{2}\left(q_{k+1}-q_{k}\right)+mgrh(1-\alpha)\,\sin\left((1-\alpha)q_{k}+\alpha q_{k+1}\right) \f$
* \f$ = (1/h)mr^2 (q_{k+1}-q_k) + mgrh(1-alpha) sin ((1-alpha)q_k+\alpha q_{k+1}) \f$
*/
class PendulumFactorPk: public NoiseModelFactor3<double, double, double> {
public:
@ -166,8 +166,8 @@ public:
//*************************************************************************
/**
* This class implements the second position-momentum update rule
* p_k1 = D_2 L_d(q_k,q_{k+1},h) = \frac{1}{h}mr^{2}\left(q_{k+1}-q_{k}\right)-mgrh\alpha\sin\left((1-\alpha)q_{k}+\alpha q_{k+1}\right)
* = (1/h)mr^2 (q_{k+1}-q_k) - mgrh alpha sin ((1-alpha)q_k+\alpha q_{k+1})
* \f$ p_k1 = D_2 L_d(q_k,q_{k+1},h) = \frac{1}{h}mr^{2}\left(q_{k+1}-q_{k}\right)-mgrh\alpha\sin\left((1-\alpha)q_{k}+\alpha q_{k+1}\right) \f$
* \f$ = (1/h)mr^2 (q_{k+1}-q_k) - mgrh alpha sin ((1-alpha)q_k+\alpha q_{k+1}) \f$
*/
class PendulumFactorPk1: public NoiseModelFactor3<double, double, double> {
public:

View File

@ -40,7 +40,7 @@ public:
return boost::static_pointer_cast<gtsam::NonlinearFactor>(
gtsam::NonlinearFactor::shared_ptr(new Reconstruction(*this))); }
/** \f$ log((g_k\exp(h\xi_k))^{-1}g_{k+1}) = 0, with optional derivatives */
/** \f$ log((g_k\exp(h\xi_k))^{-1}g_{k+1}) = 0 \f$, with optional derivatives */
Vector evaluateError(const Pose3& gk1, const Pose3& gk, const Vector6& xik,
boost::optional<Matrix&> H1 = boost::none,
boost::optional<Matrix&> H2 = boost::none,
@ -195,5 +195,4 @@ public:
};
} /* namespace gtsam */
} // namespace gtsam

View File

@ -102,7 +102,7 @@ protected:
/**
* Compute minimum step size alpha to move from the current point @p xk to the
* next feasible point along a direction @p p: x' = xk + alpha*p,
* where alpha \in [0,maxAlpha].
* where alpha \f$\in\f$ [0,maxAlpha].
*
* For QP, maxAlpha = 1. For LP: maxAlpha = Inf.
*

View File

@ -30,7 +30,7 @@ namespace gtsam {
* min y
* st Ax = b
* Cx - y <= d
* where y \in R, x \in R^n, and Ax = b and Cx <= d is the constraints of the original problem.
* where \f$y \in R\f$, \f$x \in R^n\f$, and Ax = b and Cx <= d is the constraints of the original problem.
*
* If the solution for this problem {x*,y*} has y* <= 0, we'll have x* a feasible initial point
* of the original problem

View File

@ -236,7 +236,7 @@ public:
return info_.aboveDiagonalRange(0, size(), size(), size() + 1).col(0);
}
/** Return a copy of the block at (j1,j2) of the <emph>upper-triangular part</emph> of the
/** Return a copy of the block at (j1,j2) of the <em>upper-triangular part</em> of the
* squared term \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.
@ -252,7 +252,7 @@ public:
return info_.block(J1, J2);
}
/** Return the <emph>upper-triangular part</emph> of the full squared term, as described above.
/** Return the <em>upper-triangular part</em> of the full squared term, 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.
*/