diff --git a/doc/Doxyfile.extra.in b/doc/Doxyfile.extra.in index 527821c56913ceb3c28e13825fa7be86a6b36368..4571d7c1937286e95d4d92f0ed8e96c9c7288375 100644 --- a/doc/Doxyfile.extra.in +++ b/doc/Doxyfile.extra.in @@ -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 diff --git a/doc/latex/se3.tex b/doc/latex/se3.tex index 382e9850eb845fcde382ef4654329af6f9d69fa2..ffe95c0022a54d083a16f202dc90412c3fc43a5c 100644 --- a/doc/latex/se3.tex +++ b/doc/latex/se3.tex @@ -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} diff --git a/src/multibody/frame.hpp b/src/multibody/frame.hpp index 99869428f9baa5fd3275adf3063fab2e036b626d..5cf88e4c5637da3e2943a9627fb21d9bf81284a4 100644 --- a/src/multibody/frame.hpp +++ b/src/multibody/frame.hpp @@ -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, diff --git a/src/multibody/geometry.hpp b/src/multibody/geometry.hpp index f3fddd215f570105706eaebe8bf1add296c7e3e8..b9ba60b2e81be81fd52b0905e17f4e55257fadf9 100644 --- a/src/multibody/geometry.hpp +++ b/src/multibody/geometry.hpp @@ -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. diff --git a/src/multibody/geometry.hxx b/src/multibody/geometry.hxx index 4bad2f94a3de1a9988c4c759b6d035cb607664e3..32f8b311c90003f925b287467a07f7936060929b 100644 --- a/src/multibody/geometry.hxx +++ b/src/multibody/geometry.hxx @@ -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(), diff --git a/src/multibody/liegroup/vector-space.hpp b/src/multibody/liegroup/vector-space.hpp index 72d6b87063885e6a8439f14060deb1871170a5cd..70488d5189287c73f30dd8ca479d46a697a4bbad 100644 --- a/src/multibody/liegroup/vector-space.hpp +++ b/src/multibody/liegroup/vector-space.hpp @@ -47,8 +47,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); @@ -113,7 +112,7 @@ namespace se3 // template <class ConfigL_t, class ConfigR_t> // static double squaredDistance_impl(const Eigen::MatrixBase<ConfigL_t> & q0, // const Eigen::MatrixBase<ConfigR_t> & q1) - + template <class Config_t> static void normalize_impl (const Eigen::MatrixBase<Config_t>& /*qout*/) {} diff --git a/src/multibody/model.hpp b/src/multibody/model.hpp index b7eedbfed815e0ce92c7c5bf42dec5409e5a8c55..6b06bd26c21df5f5612810f77fc0d046319cfa79 100644 --- a/src/multibody/model.hpp +++ b/src/multibody/model.hpp @@ -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,7 +260,7 @@ 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. /// @@ -397,7 +397,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). @@ -420,7 +420,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. @@ -493,7 +493,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. diff --git a/src/spatial/force.hpp b/src/spatial/force.hpp index c70d3ee58f839505d205af7ae74693f7f131ee64..d416362838f9aa97257a7020c138dd22c23ed496 100644 --- a/src/spatial/force.hpp +++ b/src/spatial/force.hpp @@ -27,8 +27,8 @@ /** \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$. - * + * The spatial force is the mathematical representation of \f$ se^{*}(3) \f$, the dual of \f$ se(3) \f$. + * * */ @@ -38,9 +38,9 @@ namespace se3 /** * @brief Base interface for forces representation. - * @details The Class implements all + * @details The Class implements all * \ingroup Force_group - * + * * @tparam Derived { description } */ template< class Derived> @@ -50,7 +50,7 @@ namespace se3 typedef Derived Derived_t; SPATIAL_TYPEDEF_TEMPLATE(Derived_t); - + public: Derived_t & derived() { return *static_cast<Derived_t*>(this); } const Derived_t& derived() const { return *static_cast<const Derived_t*>(this); } @@ -69,7 +69,7 @@ namespace se3 * @return The 3D vector associated to the linear part of the 6D force vector */ ConstLinear_t linear() const { return derived().linear_impl(); } - + /// \copydoc ForceBase::angular Angular_t angular() { return derived().angular_impl(); } @@ -94,22 +94,22 @@ namespace se3 /** * @brief Return the force * - * @return The 6D vector \f$ \phi \f$ such that + * @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} */ const Vector6 & toVector() const { return derived().toVector_impl(); } /// \copydoc ForceBase::toVector Vector6 & toVector() { return derived().toVector_impl(); } - + /* * @brief C-style cast operator * \copydoc ForceBase::toVector */ operator Vector6 () const { return toVector(); } - + // void disp(std::ostream & os) const // { // static_cast<const Derived_t*>(this)->disp_impl(os); @@ -121,28 +121,28 @@ namespace se3 * fuzzy comparison such as isApprox() */ bool operator== (const Derived_t & other) const {return derived().isEqual(other);} - + /** \returns true if at least one coefficient of \c *this and \a other does not match. */ bool operator!=(const Derived_t & other) const { return !(*this == other); } - + /** \returns true if *this is approximately equal to other, within the precision given by prec. */ bool isApprox(const Derived & other, const Scalar & prec = Eigen::NumTraits<Scalar>::dummy_precision()) const { return derived().isApprox_impl(other, prec); } - + /** \brief Copies the Derived Force into *this * \return a reference to *this */ Derived_t & operator= (const Derived_t & other) { return derived().__equl__(other); } - /** + /** * \brief Replaces *this by *this + other. * \return a reference to *this */ Derived_t & operator+= (const Derived_t & phi) { return derived().__pequ__(phi); } - - /** + + /** * \brief Replaces *this by *this - other. * \return a reference to *this */ @@ -163,7 +163,7 @@ namespace se3 /** \return an expression of the difference of *this and phi */ Derived_t operator-(const Derived_t & phi) const { return derived().__minus__(phi); } - + /** \return the dot product of *this with m * */ Scalar dot(const Motion & m) const { return static_cast<Derived_t*>(this)->dot(m); } @@ -172,11 +172,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 */ @@ -185,11 +185,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 */ @@ -197,7 +197,7 @@ namespace se3 void disp(std::ostream & os) const { derived().disp_impl(os); } friend std::ostream & operator << (std::ostream & os, const ForceBase<Derived_t> & X) - { + { X.disp(os); return os; } @@ -301,7 +301,7 @@ namespace se3 return ForceTpl(m.rotation().transpose()*linear_impl(), m.rotation().transpose()*(angular_impl() - m.translation().cross(linear_impl())) ); } - + bool isEqual (const ForceTpl & other) const { return data == other.data; } // Arithmetic operators @@ -328,7 +328,7 @@ namespace se3 ForceTpl __mult__(const double a) const { return ForceTpl(a*data); } ForceTpl __minus__() const { return ForceTpl(-data); } ForceTpl __minus__(const ForceTpl & phi) const { return ForceTpl(data - phi.data); } - + bool isApprox_impl(const ForceTpl & other, const Scalar & prec = Eigen::NumTraits<Scalar>::dummy_precision()) const { return data.isApprox(other.data, prec); } @@ -344,7 +344,7 @@ namespace se3 Linear_t linear_impl() { return data.template segment<3> (LINEAR);} /// \internal \copydoc ForceBase::linear(const Vector3 &) void linear_impl(const Vector3 & f) { data.template segment<3> (LINEAR) = f; } - + Scalar dot(const Motion & m) const { return data.dot(m.toVector()); } protected: