[orocos-kdl] 01/07: Imported Upstream version 1.3.1+dfsg

Leopold Palomo-Avellaneda leo at alaxarxa.net
Thu Jul 7 07:59:39 UTC 2016


This is an automated email from the git hooks/post-receive script.

lepalom-guest pushed a commit to branch master
in repository orocos-kdl.

commit b2d2f31e93f437fc52c84a7298d1d6df60d517b1
Author: Leopold Palomo-Avellaneda <leopold.palomo at upc.edu>
Date:   Tue Jun 28 08:26:21 2016 +0200

    Imported Upstream version 1.3.1+dfsg
---
 orocos_kdl/config/FindEigen3.cmake        |  95 +++++++++++++++++--
 orocos_kdl/package.xml                    |   2 +-
 orocos_kdl/src/articulatedbodyinertia.hpp |  52 ++++++-----
 orocos_kdl/src/chainiksolverpos_nr_jl.hpp |   2 +-
 orocos_kdl/src/frames.cpp                 |   6 +-
 orocos_kdl/src/jntarray.hpp               |   2 +-
 orocos_kdl/src/jntarrayacc.hpp            |  14 +++
 orocos_kdl/src/jntarrayvel.hpp            |  12 ++-
 orocos_kdl/src/jntspaceinertiamatrix.hpp  | 149 ++++++++++++++++--------------
 orocos_kdl/src/rigidbodyinertia.hpp       |  51 +++++-----
 orocos_kdl/src/rotationalinertia.hpp      |   3 +
 11 files changed, 263 insertions(+), 125 deletions(-)

diff --git a/orocos_kdl/config/FindEigen3.cmake b/orocos_kdl/config/FindEigen3.cmake
index 65fe96b..3519a6c 100644
--- a/orocos_kdl/config/FindEigen3.cmake
+++ b/orocos_kdl/config/FindEigen3.cmake
@@ -1,6 +1,89 @@
-FIND_PATH(EIGEN3_INCLUDE_DIR Eigen/Core /usr/include /usr/include/eigen3 /usr/local/include /usr/local/include/eigen3 /opt/local/include/eigen3)
-IF ( EIGEN3_INCLUDE_DIR )
-    MESSAGE(STATUS "-- Looking for Eigen3 - found")
-ELSE ( EIGEN3_INCLUDE_DIR )
-    MESSAGE(FATAL_ERROR "-- Looking for Eigen3 - not found")
-ENDIF ( EIGEN3_INCLUDE_DIR )
+# - Try to find Eigen3 lib
+#
+# This module supports requiring a minimum version, e.g. you can do
+#   find_package(Eigen3 3.1.2)
+# to require version 3.1.2 or newer of Eigen3.
+#
+# Once done this will define
+#
+#  EIGEN3_FOUND - system has eigen lib with correct version
+#  EIGEN3_INCLUDE_DIR - the eigen include directory
+#  EIGEN3_VERSION - eigen version
+#
+# This module reads hints about search locations from 
+# the following enviroment variables:
+#
+# EIGEN3_ROOT
+# EIGEN3_ROOT_DIR
+
+# Copyright (c) 2006, 2007 Montel Laurent, <montel at kde.org>
+# Copyright (c) 2008, 2009 Gael Guennebaud, <g.gael at free.fr>
+# Copyright (c) 2009 Benoit Jacob <jacob.benoit.1 at gmail.com>
+# Redistribution and use is allowed according to the terms of the 2-clause BSD license.
+
+if(NOT Eigen3_FIND_VERSION)
+  if(NOT Eigen3_FIND_VERSION_MAJOR)
+    set(Eigen3_FIND_VERSION_MAJOR 2)
+  endif(NOT Eigen3_FIND_VERSION_MAJOR)
+  if(NOT Eigen3_FIND_VERSION_MINOR)
+    set(Eigen3_FIND_VERSION_MINOR 91)
+  endif(NOT Eigen3_FIND_VERSION_MINOR)
+  if(NOT Eigen3_FIND_VERSION_PATCH)
+    set(Eigen3_FIND_VERSION_PATCH 0)
+  endif(NOT Eigen3_FIND_VERSION_PATCH)
+
+  set(Eigen3_FIND_VERSION "${Eigen3_FIND_VERSION_MAJOR}.${Eigen3_FIND_VERSION_MINOR}.${Eigen3_FIND_VERSION_PATCH}")
+endif(NOT Eigen3_FIND_VERSION)
+
+macro(_eigen3_check_version)
+  file(READ "${EIGEN3_INCLUDE_DIR}/Eigen/src/Core/util/Macros.h" _eigen3_version_header)
+
+  string(REGEX MATCH "define[ \t]+EIGEN_WORLD_VERSION[ \t]+([0-9]+)" _eigen3_world_version_match "${_eigen3_version_header}")
+  set(EIGEN3_WORLD_VERSION "${CMAKE_MATCH_1}")
+  string(REGEX MATCH "define[ \t]+EIGEN_MAJOR_VERSION[ \t]+([0-9]+)" _eigen3_major_version_match "${_eigen3_version_header}")
+  set(EIGEN3_MAJOR_VERSION "${CMAKE_MATCH_1}")
+  string(REGEX MATCH "define[ \t]+EIGEN_MINOR_VERSION[ \t]+([0-9]+)" _eigen3_minor_version_match "${_eigen3_version_header}")
+  set(EIGEN3_MINOR_VERSION "${CMAKE_MATCH_1}")
+
+  set(EIGEN3_VERSION ${EIGEN3_WORLD_VERSION}.${EIGEN3_MAJOR_VERSION}.${EIGEN3_MINOR_VERSION})
+  if(${EIGEN3_VERSION} VERSION_LESS ${Eigen3_FIND_VERSION})
+    set(EIGEN3_VERSION_OK FALSE)
+  else(${EIGEN3_VERSION} VERSION_LESS ${Eigen3_FIND_VERSION})
+    set(EIGEN3_VERSION_OK TRUE)
+  endif(${EIGEN3_VERSION} VERSION_LESS ${Eigen3_FIND_VERSION})
+
+  if(NOT EIGEN3_VERSION_OK)
+
+    message(STATUS "Eigen3 version ${EIGEN3_VERSION} found in ${EIGEN3_INCLUDE_DIR}, "
+                   "but at least version ${Eigen3_FIND_VERSION} is required")
+  endif(NOT EIGEN3_VERSION_OK)
+endmacro(_eigen3_check_version)
+
+if (EIGEN3_INCLUDE_DIR)
+
+  # in cache already
+  _eigen3_check_version()
+  set(EIGEN3_FOUND ${EIGEN3_VERSION_OK})
+
+else (EIGEN3_INCLUDE_DIR)
+
+  find_path(EIGEN3_INCLUDE_DIR NAMES signature_of_eigen3_matrix_library
+      HINTS
+      ENV EIGEN3_ROOT 
+      ENV EIGEN3_ROOT_DIR
+      PATHS
+      ${CMAKE_INSTALL_PREFIX}/include
+      ${KDE4_INCLUDE_DIR}
+      PATH_SUFFIXES eigen3 eigen
+    )
+
+  if(EIGEN3_INCLUDE_DIR)
+    _eigen3_check_version()
+  endif(EIGEN3_INCLUDE_DIR)
+
+  include(FindPackageHandleStandardArgs)
+  find_package_handle_standard_args(Eigen3 DEFAULT_MSG EIGEN3_INCLUDE_DIR EIGEN3_VERSION_OK)
+
+  mark_as_advanced(EIGEN3_INCLUDE_DIR)
+
+endif(EIGEN3_INCLUDE_DIR)
diff --git a/orocos_kdl/package.xml b/orocos_kdl/package.xml
index 878c42b..6f8ee68 100644
--- a/orocos_kdl/package.xml
+++ b/orocos_kdl/package.xml
@@ -1,6 +1,6 @@
 <package>
   <name>orocos_kdl</name>
-  <version>1.3.0</version>
+  <version>1.3.1</version>
   <description>
     This package contains a recent version of the Kinematics and Dynamics
     Library (KDL), distributed by the Orocos Project. 
diff --git a/orocos_kdl/src/articulatedbodyinertia.hpp b/orocos_kdl/src/articulatedbodyinertia.hpp
index e2524a7..eaca55a 100644
--- a/orocos_kdl/src/articulatedbodyinertia.hpp
+++ b/orocos_kdl/src/articulatedbodyinertia.hpp
@@ -69,34 +69,13 @@ namespace KDL {
         
         ~ArticulatedBodyInertia(){};
         
-        /**
-         * Scalar product: I_new = double * I_old
-         */
         friend ArticulatedBodyInertia operator*(double a,const ArticulatedBodyInertia& I);
-        /**
-         * addition I: I_new = I_old1 + I_old2, make sure that I_old1
-         * and I_old2 are expressed in the same reference frame/point,
-         * otherwise the result is worth nothing
-         */
         friend ArticulatedBodyInertia operator+(const ArticulatedBodyInertia& Ia,const ArticulatedBodyInertia& Ib);
         friend ArticulatedBodyInertia operator+(const ArticulatedBodyInertia& Ia,const RigidBodyInertia& Ib);
         friend ArticulatedBodyInertia operator-(const ArticulatedBodyInertia& Ia,const ArticulatedBodyInertia& Ib);
         friend ArticulatedBodyInertia operator-(const ArticulatedBodyInertia& Ia,const RigidBodyInertia& Ib);
-
-        /**
-         * calculate spatial momentum: h = I*v
-         * make sure that the twist v and the inertia are expressed in the same reference frame/point
-         */
         friend Wrench operator*(const ArticulatedBodyInertia& I,const Twist& t);
-
-        /**
-         * Coordinate system transform Ia = T_a_b*Ib with T_a_b the frame from a to b.
-         */
         friend ArticulatedBodyInertia operator*(const Frame& T,const ArticulatedBodyInertia& I);
-        /**
-         * Reference frame orientation change Ia = R_a_b*Ib with R_a_b
-         * the rotation of b expressed in a
-         */
         friend ArticulatedBodyInertia operator*(const Rotation& R,const ArticulatedBodyInertia& I);
 
         /**
@@ -111,7 +90,36 @@ namespace KDL {
         Eigen::Matrix3d H;
         Eigen::Matrix3d I;
     };
-}//namespace
 
+    /**
+     * Scalar product: I_new = double * I_old
+     */
+    ArticulatedBodyInertia operator*(double a,const ArticulatedBodyInertia& I);
+    /**
+     * addition I: I_new = I_old1 + I_old2, make sure that I_old1
+     * and I_old2 are expressed in the same reference frame/point,
+     * otherwise the result is worth nothing
+     */
+    ArticulatedBodyInertia operator+(const ArticulatedBodyInertia& Ia,const ArticulatedBodyInertia& Ib);
+    ArticulatedBodyInertia operator+(const ArticulatedBodyInertia& Ia,const RigidBodyInertia& Ib);
+    ArticulatedBodyInertia operator-(const ArticulatedBodyInertia& Ia,const ArticulatedBodyInertia& Ib);
+    ArticulatedBodyInertia operator-(const ArticulatedBodyInertia& Ia,const RigidBodyInertia& Ib);
+
+    /**
+     * calculate spatial momentum: h = I*v
+     * make sure that the twist v and the inertia are expressed in the same reference frame/point
+     */
+    Wrench operator*(const ArticulatedBodyInertia& I,const Twist& t);
+
+    /**
+     * Coordinate system transform Ia = T_a_b*Ib with T_a_b the frame from a to b.
+     */
+    ArticulatedBodyInertia operator*(const Frame& T,const ArticulatedBodyInertia& I);
+    /**
+     * Reference frame orientation change Ia = R_a_b*Ib with R_a_b
+     * the rotation of b expressed in a
+     */
+    ArticulatedBodyInertia operator*(const Rotation& R,const ArticulatedBodyInertia& I);
 
+}
 #endif
diff --git a/orocos_kdl/src/chainiksolverpos_nr_jl.hpp b/orocos_kdl/src/chainiksolverpos_nr_jl.hpp
index ba39a54..703f915 100644
--- a/orocos_kdl/src/chainiksolverpos_nr_jl.hpp
+++ b/orocos_kdl/src/chainiksolverpos_nr_jl.hpp
@@ -46,8 +46,8 @@ namespace KDL {
          * kinematics solver for that chain.
          *
          * @param chain the chain to calculate the inverse position for
-         * @param q_max the maximum joint positions
          * @param q_min the minimum joint positions
+         * @param q_max the maximum joint positions
          * @param fksolver a forward position kinematics solver
          * @param iksolver an inverse velocity kinematics solver
          * @param maxiter the maximum Newton-Raphson iterations,
diff --git a/orocos_kdl/src/frames.cpp b/orocos_kdl/src/frames.cpp
index 7293384..4b9ec2d 100644
--- a/orocos_kdl/src/frames.cpp
+++ b/orocos_kdl/src/frames.cpp
@@ -197,10 +197,10 @@ namespace KDL {
     */
     void Rotation::GetQuaternion(double& x,double& y,double& z, double& w) const
     {
-        double trace = (*this)(0,0) + (*this)(1,1) + (*this)(2,2) + 1.0;
-	double epsilon=1E-12;
+        double trace = (*this)(0,0) + (*this)(1,1) + (*this)(2,2);
+        double epsilon=1E-12;
         if( trace > epsilon ){
-            double s = 0.5 / sqrt(trace);
+            double s = 0.5 / sqrt(trace + 1.0);
             w = 0.25 / s;
             x = ( (*this)(2,1) - (*this)(1,2) ) * s;
             y = ( (*this)(0,2) - (*this)(2,0) ) * s;
diff --git a/orocos_kdl/src/jntarray.hpp b/orocos_kdl/src/jntarray.hpp
index c438a67..e0ff388 100644
--- a/orocos_kdl/src/jntarray.hpp
+++ b/orocos_kdl/src/jntarray.hpp
@@ -62,7 +62,7 @@ class MyTask : public RTT::TaskContext
    ** use j here
    }
 };
-/endcode
+\endcode
 
      */	
 
diff --git a/orocos_kdl/src/jntarrayacc.hpp b/orocos_kdl/src/jntarrayacc.hpp
index 329a991..141d153 100644
--- a/orocos_kdl/src/jntarrayacc.hpp
+++ b/orocos_kdl/src/jntarrayacc.hpp
@@ -32,6 +32,19 @@ namespace KDL
     // Equal is friend function, but default arguments for friends are forbidden (§8.3.6.4)
     class JntArrayAcc;
     bool Equal(const JntArrayAcc& src1,const JntArrayAcc& src2,double eps=epsilon);
+    void Add(const JntArrayAcc& src1,const JntArrayAcc& src2,JntArrayAcc& dest);
+    void Add(const JntArrayAcc& src1,const JntArrayVel& src2,JntArrayAcc& dest);
+    void Add(const JntArrayAcc& src1,const JntArray& src2,JntArrayAcc& dest);
+    void Subtract(const JntArrayAcc& src1,const JntArrayAcc& src2,JntArrayAcc& dest);
+    void Subtract(const JntArrayAcc& src1,const JntArrayVel& src2,JntArrayAcc& dest);
+    void Subtract(const JntArrayAcc& src1,const JntArray& src2,JntArrayAcc& dest);
+    void Multiply(const JntArrayAcc& src,const double& factor,JntArrayAcc& dest);
+    void Multiply(const JntArrayAcc& src,const doubleVel& factor,JntArrayAcc& dest);
+    void Multiply(const JntArrayAcc& src,const doubleAcc& factor,JntArrayAcc& dest);
+    void Divide(const JntArrayAcc& src,const double& factor,JntArrayAcc& dest);
+    void Divide(const JntArrayAcc& src,const doubleVel& factor,JntArrayAcc& dest);
+    void Divide(const JntArrayAcc& src,const doubleAcc& factor,JntArrayAcc& dest);
+    void SetToZero(JntArrayAcc& array);
 
     class JntArrayAcc
     {
@@ -68,6 +81,7 @@ namespace KDL
         friend bool Equal(const JntArrayAcc& src1,const JntArrayAcc& src2,double eps);
 
     };
+
 }
 
 #endif
diff --git a/orocos_kdl/src/jntarrayvel.hpp b/orocos_kdl/src/jntarrayvel.hpp
index 396c56d..cfc27a6 100644
--- a/orocos_kdl/src/jntarrayvel.hpp
+++ b/orocos_kdl/src/jntarrayvel.hpp
@@ -31,8 +31,17 @@ namespace KDL
     // Equal is friend function, but default arguments for friends are forbidden (§8.3.6.4)
     class JntArrayVel;
     bool Equal(const JntArrayVel& src1,const JntArrayVel& src2,double eps=epsilon);
+    void Add(const JntArrayVel& src1,const JntArrayVel& src2,JntArrayVel& dest);
+    void Add(const JntArrayVel& src1,const JntArray& src2,JntArrayVel& dest);
+    void Subtract(const JntArrayVel& src1,const JntArrayVel& src2,JntArrayVel& dest);
+    void Subtract(const JntArrayVel& src1,const JntArray& src2,JntArrayVel& dest);
+    void Multiply(const JntArrayVel& src,const double& factor,JntArrayVel& dest);
+    void Multiply(const JntArrayVel& src,const doubleVel& factor,JntArrayVel& dest);
+    void Divide(const JntArrayVel& src,const double& factor,JntArrayVel& dest);
+    void Divide(const JntArrayVel& src,const doubleVel& factor,JntArrayVel& dest);
+    void SetToZero(JntArrayVel& array);
+
 
-    
     class JntArrayVel
     {
     public:
@@ -61,6 +70,7 @@ namespace KDL
         friend bool Equal(const JntArrayVel& src1,const JntArrayVel& src2,double eps);
 
     };
+
 }
 
 #endif
diff --git a/orocos_kdl/src/jntspaceinertiamatrix.hpp b/orocos_kdl/src/jntspaceinertiamatrix.hpp
index 843968a..ae4f012 100644
--- a/orocos_kdl/src/jntspaceinertiamatrix.hpp
+++ b/orocos_kdl/src/jntspaceinertiamatrix.hpp
@@ -30,10 +30,6 @@
 
 namespace KDL
 {
-    // Equal is friend function, but default arguments for friends are forbidden (§8.3.6.4)
-    class JntSpaceInertiaMatrix;
-    bool Equal(const JntSpaceInertiaMatrix& src1,const JntSpaceInertiaMatrix& src2,double eps=epsilon);
-
     /**
      * @brief This class represents an fixed size matrix containing
      * the Joint-Space Inertia Matrix of a KDL::Chain.
@@ -138,84 +134,99 @@ class MyTask : public RTT::TaskContext
          */
         unsigned int columns()const;
 
-        /**
-         * Function to add two joint matrix, all the arguments must
-         * have the same size: A + B = C. This function is
-         * aliasing-safe, A or B can be the same array as C.
-         *
-         * @param src1 A
-         * @param src2 B
-         * @param dest C
-         */
         friend void Add(const JntSpaceInertiaMatrix& src1,const JntSpaceInertiaMatrix& src2,JntSpaceInertiaMatrix& dest);
-        /**
-         * Function to subtract two joint matrix, all the arguments must
-         * have the same size: A - B = C. This function is
-         * aliasing-safe, A or B can be the same array as C.
-         *
-         * @param src1 A
-         * @param src2 B
-         * @param dest C
-         */
         friend void Subtract(const JntSpaceInertiaMatrix& src1,const JntSpaceInertiaMatrix& src2,JntSpaceInertiaMatrix& dest);
-        /**
-         * Function to multiply all the array values with a scalar
-         * factor: A*b=C. This function is aliasing-safe, A can be the
-         * same array as C.
-         *
-         * @param src A
-         * @param factor b
-         * @param dest C
-         */
         friend void Multiply(const JntSpaceInertiaMatrix& src,const double& factor,JntSpaceInertiaMatrix& dest);
-        /**
-         * Function to divide all the array values with a scalar
-         * factor: A/b=C. This function is aliasing-safe, A can be the
-         * same array as C.
-         *
-         * @param src A
-         * @param factor b
-         * @param dest C
-         */
         friend void Divide(const JntSpaceInertiaMatrix& src,const double& factor,JntSpaceInertiaMatrix& dest);
-        /**
-         * Function to multiply a KDL::Jacobian with a KDL::JntSpaceInertiaMatrix
-         * to get a KDL::Twist, it should not be used to calculate the
-         * forward velocity kinematics, the solver classes are built
-         * for this purpose.
-         * J*q = t
-         *
-         * @param jac J
-         * @param src q
-         * @param dest t
-         * @post dest==Twist::Zero() if 0==src.rows() (ie src is empty)
-         */
         friend void Multiply(const JntSpaceInertiaMatrix& src, const JntArray& vec, JntArray& dest);
-        /**
-         * Function to set all the values of the array to 0
-         *
-         * @param array
-         */
         friend void SetToZero(JntSpaceInertiaMatrix& matrix);
-        /**
-         * Function to check if two matrices are the same with a
-         *precision of eps
-         *
-         * @param src1
-         * @param src2
-         * @param eps default: epsilon
-         * @return true if each element of src1 is within eps of the same
-		 * element in src2, or if both src1 and src2 have no data (ie 0==rows())
-         */
         friend bool Equal(const JntSpaceInertiaMatrix& src1,const JntSpaceInertiaMatrix& src2,double eps);
-
         friend bool operator==(const JntSpaceInertiaMatrix& src1,const JntSpaceInertiaMatrix& src2);
         //friend bool operator!=(const JntSpaceInertiaMatrix& src1,const JntSpaceInertiaMatrix& src2);
-        };
+    };
 
     bool operator==(const JntSpaceInertiaMatrix& src1,const JntSpaceInertiaMatrix& src2);
     //bool operator!=(const JntSpaceInertiaMatrix& src1,const JntSpaceInertiaMatrix& src2);
 
+    /**
+     * Function to add two joint matrix, all the arguments must
+     * have the same size: A + B = C. This function is
+     * aliasing-safe, A or B can be the same array as C.
+     *
+     * @param src1 A
+     * @param src2 B
+     * @param dest C
+     */
+    void Add(const JntSpaceInertiaMatrix& src1,const JntSpaceInertiaMatrix& src2,JntSpaceInertiaMatrix& dest);
+
+    /**
+     * Function to subtract two joint matrix, all the arguments must
+     * have the same size: A - B = C. This function is
+     * aliasing-safe, A or B can be the same array as C.
+     *
+     * @param src1 A
+     * @param src2 B
+     * @param dest C
+     */
+    void Subtract(const JntSpaceInertiaMatrix& src1,const JntSpaceInertiaMatrix& src2,JntSpaceInertiaMatrix& dest);
+
+    /**
+     * Function to multiply all the array values with a scalar
+     * factor: A*b=C. This function is aliasing-safe, A can be the
+     * same array as C.
+     *
+     * @param src A
+     * @param factor b
+     * @param dest C
+     */
+    void Multiply(const JntSpaceInertiaMatrix& src,const double& factor,JntSpaceInertiaMatrix& dest);
+
+    /**
+     * Function to divide all the array values with a scalar
+     * factor: A/b=C. This function is aliasing-safe, A can be the
+     * same array as C.
+     *
+     * @param src A
+     * @param factor b
+     * @param dest C
+     */
+    void Divide(const JntSpaceInertiaMatrix& src,const double& factor,JntSpaceInertiaMatrix& dest);
+
+    /**
+     * Function to multiply a KDL::Jacobian with a KDL::JntSpaceInertiaMatrix
+     * to get a KDL::Twist, it should not be used to calculate the
+     * forward velocity kinematics, the solver classes are built
+     * for this purpose.
+     * J*q = t
+     *
+     * @param jac J
+     * @param src q
+     * @param dest t
+     * @post dest==Twist::Zero() if 0==src.rows() (ie src is empty)
+     */
+    void Multiply(const JntSpaceInertiaMatrix& src, const JntArray& vec, JntArray& dest);
+
+    /**
+     * Function to set all the values of the array to 0
+     *
+     * @param array
+     */
+    void SetToZero(JntSpaceInertiaMatrix& matrix);
+
+    /**
+     * Function to check if two matrices are the same with a
+     *precision of eps
+     *
+     * @param src1
+     * @param src2
+     * @param eps default: epsilon
+     * @return true if each element of src1 is within eps of the same
+     * element in src2, or if both src1 and src2 have no data (ie 0==rows())
+     */
+    bool Equal(const JntSpaceInertiaMatrix& src1,const JntSpaceInertiaMatrix& src2,double eps=epsilon);
+
+    bool operator==(const JntSpaceInertiaMatrix& src1,const JntSpaceInertiaMatrix& src2);
+
 }
 
 #endif
diff --git a/orocos_kdl/src/rigidbodyinertia.hpp b/orocos_kdl/src/rigidbodyinertia.hpp
index 8f94c65..8992c4f 100644
--- a/orocos_kdl/src/rigidbodyinertia.hpp
+++ b/orocos_kdl/src/rigidbodyinertia.hpp
@@ -53,31 +53,10 @@ namespace KDL {
         
         ~RigidBodyInertia(){};
         
-        /**
-         * Scalar product: I_new = double * I_old
-         */
         friend RigidBodyInertia operator*(double a,const RigidBodyInertia& I);
-        /**
-         * addition I: I_new = I_old1 + I_old2, make sure that I_old1
-         * and I_old2 are expressed in the same reference frame/point,
-         * otherwise the result is worth nothing
-         */
         friend RigidBodyInertia operator+(const RigidBodyInertia& Ia,const RigidBodyInertia& Ib);
-
-        /**
-         * calculate spatial momentum: h = I*v
-         * make sure that the twist v and the inertia are expressed in the same reference frame/point
-         */
         friend Wrench operator*(const RigidBodyInertia& I,const Twist& t);
-
-        /**
-         * Coordinate system transform Ia = T_a_b*Ib with T_a_b the frame from a to b.
-         */
         friend RigidBodyInertia operator*(const Frame& T,const RigidBodyInertia& I);
-        /**
-         * Reference frame orientation change Ia = R_a_b*Ib with R_a_b
-         * the rotation of b expressed in a
-         */
         friend RigidBodyInertia operator*(const Rotation& R,const RigidBodyInertia& I);
 
         /**
@@ -117,6 +96,36 @@ namespace KDL {
         friend class ArticulatedBodyInertia;
         
     };
+
+    /**
+     * Scalar product: I_new = double * I_old
+     */
+    RigidBodyInertia operator*(double a,const RigidBodyInertia& I);
+    /**
+     * addition I: I_new = I_old1 + I_old2, make sure that I_old1
+     * and I_old2 are expressed in the same reference frame/point,
+     * otherwise the result is worth nothing
+     */
+    RigidBodyInertia operator+(const RigidBodyInertia& Ia,const RigidBodyInertia& Ib);
+
+    /**
+     * calculate spatial momentum: h = I*v
+     * make sure that the twist v and the inertia are expressed in the same reference frame/point
+     */
+    Wrench operator*(const RigidBodyInertia& I,const Twist& t);
+
+    /**
+     * Coordinate system transform Ia = T_a_b*Ib with T_a_b the frame from a to b.
+     */
+    RigidBodyInertia operator*(const Frame& T,const RigidBodyInertia& I);
+    /**
+     * Reference frame orientation change Ia = R_a_b*Ib with R_a_b
+     * the rotation of b expressed in a
+     */
+    RigidBodyInertia operator*(const Rotation& R,const RigidBodyInertia& I);
+
+
+
 }//namespace
 
 
diff --git a/orocos_kdl/src/rotationalinertia.hpp b/orocos_kdl/src/rotationalinertia.hpp
index a648392..c3c21c4 100644
--- a/orocos_kdl/src/rotationalinertia.hpp
+++ b/orocos_kdl/src/rotationalinertia.hpp
@@ -65,6 +65,9 @@ namespace KDL
         double data[9];
 	};
 
+    RotationalInertia operator*(double a, const RotationalInertia& I);
+    RotationalInertia operator+(const RotationalInertia& Ia, const RotationalInertia& Ib);
+
 }
 
 #endif

-- 
Alioth's /usr/local/bin/git-commit-notice on /srv/git.debian.org/git/debian-science/packages/orocos/orocos-kdl.git



More information about the debian-science-commits mailing list