Commit 7b4833a0 authored by Guilhem Saurel's avatar Guilhem Saurel Committed by jcarpent
Browse files

[Doc] Fix doxygen warnings

- remove leftidx package, not available in MathJbx
- replace `\leftidx{^` by `{}^{`
- fix param lists
- comment documentation of commented code
- replace `<i>` & `<li>` with `*i*` & `*li*`, that are valid in html & md
parent 3ae43223
......@@ -530,7 +530,7 @@ GENERATE_LATEX = YES
# The EXTRA_PACKAGES tag can be to specify one or more names of LaTeX
# packages that should be included in the LaTeX output.
EXTRA_PACKAGES += leftidx
EXTRA_PACKAGES +=
#---------------------------------------------------------------------------
# Configuration options related to the preprocessor
......
......@@ -11,52 +11,50 @@
\newcommand{\dpartial}[2]{\frac{\partial{#1}}{\partial{#2}}}
\newcommand{\ddpartial}[2]{\frac{\partial^2{#1}}{\partial{#2}^2}}
\newcommand{\aRb}{\ \leftidx{^A}R_B}
\newcommand{\aMb}{\ \leftidx{^A}M_B}
\newcommand{\amb}{\ \leftidx{^A}m_B}
\newcommand{\apb}{{\ \leftidx{^A}{AB}{}}}
\newcommand{\aXb}{\ \leftidx{^A}X_B}
\newcommand{\bRa}{\ \leftidx{^B}R_A}
\newcommand{\bMa}{\ \leftidx{^B}M_A}
\newcommand{\bma}{\ \leftidx{^B}m_A}
\newcommand{\bpa}{\ \leftidx{^B}{BA}{}}
\newcommand{\bXa}{\ \leftidx{^B}X_A}
\newcommand{\ap}{\ \leftidx{^A}p}
\newcommand{\bp}{\ \leftidx{^B}p}
\newcommand{\afs}{\ \leftidx{^A}\phi}
\newcommand{\bfs}{\ \leftidx{^B}\phi}
\newcommand{\af}{\ \leftidx{^A}f}
\renewcommand{\bf}{\ \leftidx{^B}f}
\newcommand{\an}{\ \leftidx{^A}\tau}
\newcommand{\bn}{\ \leftidx{^B}\tau}
\newcommand{\avs}{\ \leftidx{^A}\nu}
\newcommand{\bvs}{\ \leftidx{^B}\nu}
\newcommand{\aRb}{\ {}^{A}R_B}
\newcommand{\aMb}{\ {}^{A}M_B}
\newcommand{\amb}{\ {}^{A}m_B}
\newcommand{\apb}{{\ {}^{A}{AB}{}}}
\newcommand{\aXb}{\ {}^{A}X_B}
\newcommand{\bRa}{\ {}^{B}R_A}
\newcommand{\bMa}{\ {}^{B}M_A}
\newcommand{\bma}{\ {}^{B}m_A}
\newcommand{\bpa}{\ {}^{B}{BA}{}}
\newcommand{\bXa}{\ {}^{B}X_A}
\newcommand{\ap}{\ {}^{A}p}
\newcommand{\bp}{\ {}^{B}p}
\newcommand{\afs}{\ {}^{A}\phi}
\newcommand{\bfs}{\ {}^{B}\phi}
\newcommand{\af}{\ {}^{A}f}
\renewcommand{\bf}{\ {}^{B}f}
\newcommand{\an}{\ {}^{A}\tau}
\newcommand{\bn}{\ {}^{B}\tau}
\newcommand{\avs}{\ {}^{A}\nu}
\newcommand{\bvs}{\ {}^{B}\nu}
\newcommand{\w}{\omega}
\newcommand{\av}{\ \leftidx{^A}v}
\newcommand{\bv}{\ \leftidx{^B}v}
\newcommand{\aw}{\ \leftidx{^A}\w}
\newcommand{\bw}{\ \leftidx{^B}\w}
\newcommand{\aI}{\ \leftidx{^A}I}
\newcommand{\bI}{\ \leftidx{^B}I}
\newcommand{\cI}{\ \leftidx{^C}I}
\newcommand{\aY}{\ \leftidx{^A}Y}
\newcommand{\bY}{\ \leftidx{^B}Y}
\newcommand{\cY}{\ \leftidx{^c}Y}
\newcommand{\aXc}{\ \leftidx{^A}X_C}
\newcommand{\aMc}{\ \leftidx{^A}M_C}
\newcommand{\aRc}{\ \leftidx{^A}R_C}
\newcommand{\apc}{\ \leftidx{^A}{AC}{}}
\newcommand{\bXc}{\ \leftidx{^B}X_C}
\newcommand{\bRc}{\ \leftidx{^B}R_C}
\newcommand{\bMc}{\ \leftidx{^B}M_C}
\newcommand{\bpc}{\ \leftidx{^B}{BC}{}}
\usepackage{leftidx}
\newcommand{\av}{\ {}^{A}v}
\newcommand{\bv}{\ {}^{B}v}
\newcommand{\aw}{\ {}^{A}\w}
\newcommand{\bw}{\ {}^{B}\w}
\newcommand{\aI}{\ {}^{A}I}
\newcommand{\bI}{\ {}^{B}I}
\newcommand{\cI}{\ {}^{C}I}
\newcommand{\aY}{\ {}^{A}Y}
\newcommand{\bY}{\ {}^{B}Y}
\newcommand{\cY}{\ {}^{c}Y}
\newcommand{\aXc}{\ {}^{A}X_C}
\newcommand{\aMc}{\ {}^{A}M_C}
\newcommand{\aRc}{\ {}^{A}R_C}
\newcommand{\apc}{\ {}^{A}{AC}{}}
\newcommand{\bXc}{\ {}^{B}X_C}
\newcommand{\bRc}{\ {}^{B}R_C}
\newcommand{\bMc}{\ {}^{B}M_C}
\newcommand{\bpc}{\ {}^{B}{BC}{}}
\begin{document}
\title{SE(3) operations}
......
......@@ -109,7 +109,7 @@ namespace se3
/// and expressed in the local frame of the joint..
container::aligned_vector<Inertia> Ycrb;
/// \brief Vector of sub-tree composite rigid body inertia time derivatives \f$ \dot{Y}_{crb}$\f. See Data::Ycrb for more details.
/// \brief Vector of sub-tree composite rigid body inertia time derivatives \f$ \dot{Y}_{crb}\f$. See Data::Ycrb for more details.
container::aligned_vector<Inertia::Matrix6> dYcrb; // TODO: change with dense symmetric matrix6
/// \brief The joint space inertia matrix (a square matrix of dim model.nv).
......@@ -174,7 +174,7 @@ namespace se3
// dCCRBA return quantities
/// \brief Centroidal Momentum Matrix Time Variation
/// \note \f$ \dot{h_g} = A_g \ddot{q}\ + \dot{A_g}\dot{q}f$ maps the joint velocity and acceleration vectors to the time variation of the centroidal momentum.
/// \note \f$ \dot{h_g} = A_g \ddot{q}\ + \dot{A_g}\dot{q}\f$ maps the joint velocity and acceleration vectors to the time variation of the centroidal momentum.
Matrix6x dAg;
/// \brief Centroidal momentum quantity.
......@@ -271,7 +271,7 @@ namespace se3
/// \brief Inverse of the operational-space inertia matrix
Eigen::MatrixXd JMinvJt;
/// \brief Cholesky decompostion of \JMinvJt.
/// \brief Cholesky decompostion of \f$\JMinvJt\f$.
Eigen::LLT<Eigen::MatrixXd> llt_JMinvJt;
/// \brief Lagrange Multipliers corresponding to the contact forces in se3::forwardDynamics.
......
......@@ -60,7 +60,7 @@ namespace se3
/// \param[in] name Name of the frame.
/// \param[in] parent Index of the parent joint in the kinematic tree.
/// \param[in] previousFrame Index of the parent frame in the kinematic tree.
/// \param[in] placement Placement of the frame wrt the parent joint frame.
/// \param[in] frame_placement Placement of the frame wrt the parent joint frame.
/// \param[in] type The type of the frame, see the enum FrameType
///
FrameTpl(const std::string & name,
......
......@@ -241,7 +241,7 @@ namespace se3
///
/// This simply corresponds to storing in a re-arranged manner the information stored
/// in geomModel.geometryObjects and geomModel.collisionPairs.
/// \param[in] GeomModel the geometry model (const)
/// \param[in] geomModel the geometry model (const)
///
/// \warning Outer objects are not duplicated (i.e. if a is in outerObjects[b], then
/// b is not in outerObjects[a]).
......@@ -255,7 +255,7 @@ namespace se3
/// condition can be used to temporarily remove a pair without touching the model, in a versatile
/// manner.
/// \param[in] pairId the index of the pair in GeomModel::collisionPairs vector.
/// \param[in] new value of the activation boolean (true by default).
/// \param[in] flag value of the activation boolean (true by default).
void activateCollisionPair(const PairIndex pairId,const bool flag=true);
/// Deactivate a collision pair.
......
......@@ -98,12 +98,12 @@ namespace se3
}
/**
* @brief Associate a GeometryObject of type COLLISION to a joint's inner objects list
*
* @param[in] joint Index of the joint
* @param[in] inner_object Index of the GeometryObject that will be an inner object
*/
//
// @brief Associate a GeometryObject of type COLLISION to a joint's inner objects list
//
// @param[in] joint Index of the joint
// @param[in] inner_object Index of the GeometryObject that will be an inner object
//
// inline void GeometryModel::addInnerObject(const JointIndex joint_id, const GeomIndex inner_object)
// {
// if (std::find(innerObjects[joint_id].begin(),
......@@ -114,12 +114,12 @@ namespace se3
// std::cout << "inner object already added" << std::endl;
// }
/**
* @brief Associate a GeometryObject of type COLLISION to a joint's outer objects list
*
* @param[in] joint Index of the joint
* @param[in] inner_object Index of the GeometryObject that will be an outer object
*/
//
// @brief Associate a GeometryObject of type COLLISION to a joint's outer objects list
//
// @param[in] joint Index of the joint
// @param[in] inner_object Index of the GeometryObject that will be an outer object
//
// inline void GeometryModel::addOutterObject (const JointIndex joint, const GeomIndex outer_object)
// {
// if (std::find(outerObjects[joint].begin(),
......
......@@ -49,8 +49,7 @@ namespace se3
}
/// Constructor
/// \param size size of the vector space: should be the equal to template
/// argument for static sized vector-spaces.
/// \param other other VectorSpaceOperation from which to retrieve size
VectorSpaceOperation (const VectorSpaceOperation& other) : Base (), size_ (other.size_.value())
{
assert (size_.value() >= 0);
......
......@@ -60,19 +60,19 @@ namespace se3
/// \brief Number of operational frames.
int nframes;
/// \brief Spatial inertias of the body <i> expressed in the supporting joint frame <i>.
/// \brief Spatial inertias of the body *i* expressed in the supporting joint frame *i*.
container::aligned_vector<Inertia> inertias;
/// \brief Placement (SE3) of the input of joint <i> regarding to the parent joint output <li>.
/// \brief Placement (SE3) of the input of joint *i* regarding to the parent joint output *li*.
container::aligned_vector<SE3> jointPlacements;
/// \brief Model of joint <i>, encapsulated in a JointModelAccessor.
/// \brief Model of joint *i*, encapsulated in a JointModelAccessor.
JointModelVector joints;
/// \brief Joint parent of joint <i>, denoted <li> (li==parents[i]).
/// \brief Joint parent of joint *i*, denoted *li* (li==parents[i]).
std::vector<JointIndex> parents;
/// \brief Name of joint <i>
/// \brief Name of joint *i*
std::vector<std::string> names;
/// \brief Vector of joint's neutral configurations
......@@ -98,8 +98,8 @@ namespace se3
container::aligned_vector<Frame> frames;
/// \brief Vector of subtrees.
/// subtree[j] corresponds to the subtree supported by the joint j.
/// The first element of subtree[j] is the index of the joint j itself.
/// subtree[j] corresponds to the subtree supported by the joint *j*.
/// The first element of subtree[j] is the index of the joint *j* itself.
std::vector<IndexVector> subtrees;
/// \brief Spatial gravity of the model.
......@@ -260,9 +260,9 @@ namespace se3
/// \warning If no joint is found, return the number of elements at time T.
/// This can lead to errors if the model is expanded after this method is called
/// (for example to get the id of a parent joint)
/// \param[in] index Index of the joint.
/// \param[in] name Name of the joint.
///
/// \return Index of the joint.
/// \return name Name of the joint.
///
JointIndex getJointId(const std::string & name) const;
......
......@@ -19,6 +19,14 @@
#ifndef __se3_force_base_hpp__
#define __se3_force_base_hpp__
/** \addtogroup Force_group Force
*
* This module represents a spatial force, e.g. a spatial impulse or force associated to a body.
* The spatial force is the mathematical representation of \f$ se^{*}(3) \f$, the dual of \f$ se(3) \f$.
*
*
*/
namespace se3
{
/**
......@@ -83,7 +91,7 @@ namespace se3
*
* @return The 6D vector \f$ \phi \f$ such that
* \f{equation*}
* \leftidx{^A}\phi = \begin{bmatrix} \leftidx{^A}f \\ \leftidx{^A}\tau \end{bmatrix}
* {}^{A}\phi = \begin{bmatrix} {}^{A}f \\ {}^{A}\tau \end{bmatrix}
* \f}
*/
ToVectorConstReturnType toVector() const { return derived().toVector_impl(); }
......@@ -161,11 +169,11 @@ namespace se3
/**
* @brief Transform from A to B coordinates the Force represented by *this such that
* \f{equation*}
* \leftidx{^B}f = \leftidx{^B}X_A^* * \leftidx{^A}f
* {}^{B}f = {}^{B}X_A^* * {}^{A}f
* \f}
*
* @param[in] m The rigid transformation \f$ \leftidx{^B}m_A \f$ whose coordinates transform for forces is
* \leftidx{^B}X_A^*
* @param[in] m The rigid transformation \f$ {}^{B}m_A \f$ whose coordinates transform for forces is
* {}^{B}X_A^*
*
* @return an expression of the force expressed in the new coordinates
*/
......@@ -176,11 +184,11 @@ namespace se3
/**
* @brief Transform from B to A coordinates the Force represented by *this such that
* \f{equation*}
* \leftidx{^A}f = \leftidx{^A}X_B^* * \leftidx{^A}f
* {}^{A}f = {}^{A}X_B^* * {}^{A}f
* \f}
*
* @param[in] m The rigid transformation \f$ \leftidx{^B}m_A \f$ whose coordinates transform for forces is
* \leftidx{^B}X_A^*
* @param[in] m The rigid transformation \f$ {}^{B}m_A \f$ whose coordinates transform for forces is
* {}^{B}X_A^*
*
* @return an expression of the force expressed in the new coordinates
*/
......
......@@ -54,3 +54,4 @@ FORCE_TYPEDEF_GENERIC(Derived,PINOCCHIO_MACRO_EMPTY_ARG)
#include "pinocchio/spatial/force-ref.hpp"
#endif // ifndef __se3_force_hpp__
Markdown is supported
0% or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment