From 4c154259ce07468d42ed58ad9db60b012098bcac Mon Sep 17 00:00:00 2001
From: jcarpent <jcarpent@laas.fr>
Date: Mon, 8 Aug 2016 14:23:03 +0200
Subject: [PATCH] [Doc] Update contents

---
 src/algorithm/frames.hpp | 30 +++++++++++++++++-------------
 src/multibody/frame.hpp  | 32 +++++++++++++++++++-------------
 src/multibody/model.hpp  | 21 +++++++++++----------
 3 files changed, 47 insertions(+), 36 deletions(-)

diff --git a/src/algorithm/frames.hpp b/src/algorithm/frames.hpp
index c045c66df..30fbc7c15 100644
--- a/src/algorithm/frames.hpp
+++ b/src/algorithm/frames.hpp
@@ -27,10 +27,11 @@ namespace se3
 {
 
   /**
-   * @brief      Update the position of each extra frame
+   * @brief      Updates the position of each frame contained in the model
+   *
+   * @param[in]  model  The kinematic model.
+   * @param      data   Data associated to model.
    *
-   * @param[in]  model  The kinematic model
-   * @param      data   Data associated to model
    * @warning    One of the algorithms forwardKinematics should have been called first
    */
   inline void framesForwardKinematics(const Model & model,
@@ -38,11 +39,12 @@ namespace se3
                                       );
 
   /**
-   * @brief      Compute Kinematics of full model, then the position of each operational frame
+   * @brief      First calls the forwardKinematics on the model, then computes the placement of each frame.
+   *             /sa se3::forwardKinematics
    *
-   * @param[in]  model                    The kinematic model
-   * @param      data                     Data associated to model
-   * @param[in]  q                        Configuration vector
+   * @param[in]  model                    The kinematic model.
+   * @param      data                     Data associated to model.
+   * @param[in]  q                        Configuration vector.
    */
   inline void framesForwardKinematics(const Model & model,
                                       Data & data,
@@ -50,17 +52,19 @@ namespace se3
                                       );
 
   /**
-   * @brief      Return the jacobian of the operational frame in the world frame or
-     in the local frame depending on the template argument.
+   * @brief      Returns the jacobian of the frame expresssed in the world frame or
+     in the local frame depending on the template argument. 
+   
+   * @remark Expressed in the local frame, the jacobian maps the joint velocity vector to the spatial velocity of the center of the frame, expressed in the frame coordinates system. Expressed in the global frame, the jacobian maps to the spatial velocity of the point coinciding with the center of the world and attached to the frame.
    *
    * @param[in]  model       The kinematic model
    * @param[in]  data        Data associated to model
    * @param[in]  frame_id    Id of the operational frame we want to compute the jacobian
-   * @param      J           The filled Jacobian Matrix
+   * @param[out] J           The Jacobian of the
    *
-   * @tparam     localFrame  Express the jacobian in the local or global frame
+   * @tparam     local_frame  If true, the jacobian is expressed in the local frame. Otherwise, the jacobian is expressed in the world frame.
    * 
-   * @warning    The function computeJacobians should have been called first
+   * @warning    The function se3::computeJacobians should have been called first
    */
   template<bool local_frame>
   inline void getFrameJacobian(const Model & model,
@@ -102,7 +106,7 @@ namespace se3
   
   
   
-  template<bool localFrame>
+  template<bool local_frame>
   inline void getFrameJacobian(const Model & model,
                                const Data & data,
                                const Model::FrameIndex frame_id,
diff --git a/src/multibody/frame.hpp b/src/multibody/frame.hpp
index 77ad2519b..6634f40ca 100644
--- a/src/multibody/frame.hpp
+++ b/src/multibody/frame.hpp
@@ -24,19 +24,22 @@
 #include "pinocchio/tools/string-generator.hpp"
 
 #include <Eigen/StdVector>
-#include <iostream>
+#include <string>
 
 namespace se3
 {
-
+  ///
+  /// \brief Enum on the possible type of frame
+  ///
   enum FrameType
   {
-    OP_FRAME,
-    JOINT,
-    FIXED_JOINT,
-    BODY,
-    SENSOR
+    OP_FRAME, // operational frame type
+    JOINT, // joint frame type
+    FIXED_JOINT, // fixed joint frame type
+    BODY, // body frame type
+    SENSOR // sensor frame type
   };
+  
   ///
   /// \brief A Plucker coordinate frame attached to a parent joint inside a kinematic tree
   ///
@@ -44,26 +47,29 @@ namespace se3
   {
     EIGEN_MAKE_ALIGNED_OPERATOR_NEW
     typedef se3::JointIndex JointIndex;
-      
-    Frame() : name(randomStringGenerator(8)), parent(), placement(), type(){} // needed by EIGEN_DEFINE_STL_VECTOR_SPECIALIZATION
     
     ///
-    /// \brief Default constructor of a Frame
+    /// \brief Default constructor of a frame.
+    ///
+    Frame() : name(randomStringGenerator(8)), parent(), placement(), type() {} // needed by std::vector
+    
+    ///
+    /// \brief Builds a frame defined by its name, its joint parent id, its placement and its type.
     ///
     /// \param[in] name Name of the frame.
     /// \param[in] parent Index of the parent joint in the kinematic tree.
     /// \param[in] placement Placement of the frame wrt the parent joint frame.
     /// \param[in] type The type of the frame, see the enum FrameType
     ///
-    Frame(const std::string & name, const JointIndex parent, const SE3 & frame_placement, const FrameType type ):
-    name(name)
+    Frame(const std::string & name, const JointIndex parent, const SE3 & frame_placement, const FrameType type)
+    : name(name)
     , parent(parent)
     , placement(frame_placement)
     , type(type)
     {}
     
     ///
-    /// \brief Compare the current Frame with another frame. Return true if all properties match.
+    /// \returns true if *this and other matches and have the same parent, name and type.
     ///
     /// \param[in] other The frame to which the current frame is compared.
     ///
diff --git a/src/multibody/model.hpp b/src/multibody/model.hpp
index bc668c274..effcacb02 100644
--- a/src/multibody/model.hpp
+++ b/src/multibody/model.hpp
@@ -233,24 +233,25 @@ namespace se3
     const std::string & getJointName(const JointIndex index) const;
 
     ///
-    /// \brief Return the index of a frame given by its name.
+    /// \brief Returns the index of a frame given by its name.
+    ///        \sa Model::existFrame to check if the frame exists or not.
     ///
-    /// \warning If no frame is found, return the number of elements at time T.
+    /// \warning If no frame is found, returns the size of the vector of Model::frames.
     /// This can lead to errors if the model is expanded after this method is called
-    /// (for example to get the id of a parent frame)
+    /// (for example to get the id of a parent frame).
     /// 
-    /// \param[in] index Index of the frame.
+    /// \param[in] name Name of the frame.
     ///
     /// \return Index of the frame.
     ///
     FrameIndex getFrameId (const std::string & name) const;
     
     ///
-    /// \brief Check if a frame given by its name exists.
+    /// \brief Checks if a frame given by its name exists.
     ///
     /// \param[in] name Name of the frame.
     ///
-    /// \return Return true if the frame exists.
+    /// \return Returns true if the frame exists.
     ///
     bool existFrame (const std::string & name) const;
     
@@ -318,23 +319,23 @@ namespace se3
     const SE3 & getFramePlacement(const FrameIndex index) const;
 
     ///
-    /// \brief Add a frame to the kinematic tree.
+    /// \brief Adds a frame to the kinematic tree.
     ///
     /// \param[in] frame The frame to add to the kinematic tree.
     ///
-    /// \return Return true if the frame has been successfully added.
+    /// \return Returns true if the frame has been successfully added.
     ///
     bool addFrame(const Frame & frame);
     
     ///
-    /// \brief Create and add a frame to the kinematic tree.
+    /// \brief Creates and adds a frame to the kinematic tree.
     ///
     /// \param[in] name Name of the frame.
     /// \param[in] parent Index of the supporting joint.
     /// \param[in] placement Placement of the frame regarding to the joint frame.
     /// \param[in] type The type of the frame
     ///
-    /// \return Return true if the frame has been successfully added.
+    /// \return Returns true if the frame has been successfully added.
     ///
     bool addFrame(const std::string & name, const JointIndex parent, const SE3 & placement, const FrameType type = OP_FRAME);
 
-- 
GitLab