frames.hpp

Go to the documentation of this file.
00001 /***************************************************************************
00002                         frames.hpp `-  description
00003                        -------------------------
00004     begin                : June 2006
00005     copyright            : (C) 2006 Erwin Aertbelien
00006     email                : firstname.lastname@mech.kuleuven.be
00007 
00008  History (only major changes)( AUTHOR-Description ) :
00009 
00010  ***************************************************************************
00011  *   This library is free software; you can redistribute it and/or         *
00012  *   modify it under the terms of the GNU Lesser General Public            *
00013  *   License as published by the Free Software Foundation; either          *
00014  *   version 2.1 of the License, or (at your option) any later version.    *
00015  *                                                                         *
00016  *   This library is distributed in the hope that it will be useful,       *
00017  *   but WITHOUT ANY WARRANTY; without even the implied warranty of        *
00018  *   MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU     *
00019  *   Lesser General Public License for more details.                       *
00020  *                                                                         *
00021  *   You should have received a copy of the GNU Lesser General Public      *
00022  *   License along with this library; if not, write to the Free Software   *
00023  *   Foundation, Inc., 59 Temple Place,                                    *
00024  *   Suite 330, Boston, MA  02111-1307  USA                                *
00025  *                                                                         *
00026  ***************************************************************************/
00027 
00124 #ifndef KDL_FRAMES_H
00125 #define KDL_FRAMES_H
00126 
00127 
00128 #include "utilities/kdl-config.h"
00129 #include "utilities/utility.h"
00130 
00132 
00133 namespace KDL {
00134 
00135 
00136 
00137 class Vector;
00138 class Rotation;
00139 class Frame;
00140 class Wrench;
00141 class Twist;
00142 class Vector2;
00143 class Rotation2;
00144 class Frame2;
00145 
00146 
00147 
00151 class Vector
00152 {
00153 public:
00154     double data[3];
00156      inline Vector() {data[0]=data[1]=data[2] = 0.0;}
00157 
00159      inline Vector(double x,double y, double z);
00160 
00162      inline Vector(const Vector& arg);
00163 
00165      inline Vector& operator = ( const Vector& arg);
00166 
00168      inline double operator()(int index) const;
00169 
00171      inline double& operator() (int index);
00172 
00174      double operator[] ( int index ) const
00175        {
00176          return this->operator() ( index );
00177        }
00178 
00180      double& operator[] ( int index )
00181        {
00182          return this->operator() ( index );
00183        }
00184 
00185      inline double x() const;
00186      inline double y() const;
00187      inline double z() const;
00188      inline void x(double);
00189      inline void y(double);
00190      inline void z(double);
00191 
00193      inline void ReverseSign();
00194 
00195 
00197      inline Vector& operator-=(const Vector& arg);
00198 
00199 
00201      inline Vector& operator +=(const Vector& arg);
00202 
00204      inline friend Vector operator*(const Vector& lhs,double rhs);
00206      inline friend Vector operator*(double lhs,const Vector& rhs);
00208 
00209      inline friend Vector operator/(const Vector& lhs,double rhs);
00210      inline friend Vector operator+(const Vector& lhs,const Vector& rhs);
00211      inline friend Vector operator-(const Vector& lhs,const Vector& rhs);
00212      inline friend Vector operator*(const Vector& lhs,const Vector& rhs);
00213      inline friend Vector operator-(const Vector& arg);
00214      inline friend double dot(const Vector& lhs,const Vector& rhs);
00215 
00218      inline friend void SetToZero(Vector& v);
00219 
00221      inline static Vector Zero();
00222 
00228      double Normalize(double eps=epsilon);
00229 
00231      double Norm() const;
00232 
00233 
00234 
00236      inline void Set2DXY(const Vector2& v);
00238      inline void Set2DYZ(const Vector2& v);
00240      inline void Set2DZX(const Vector2& v);
00242      inline void Set2DPlane(const Frame& F_someframe_XY,const Vector2& v_XY);
00243 
00244 
00247      inline friend bool Equal(const Vector& a,const Vector& b,double eps=epsilon);
00248 
00250      inline friend bool operator==(const Vector& a,const Vector& b);
00252      inline friend bool operator!=(const Vector& a,const Vector& b);
00253 
00254      friend class Rotation;
00255      friend class Frame;
00256 };
00257 
00258 
00292 class Rotation
00293 {
00294 public:
00295     double data[9];
00296 
00297     inline Rotation() {
00298                 *this = Rotation::Identity();
00299         }
00300     inline Rotation(double Xx,double Yx,double Zx,
00301                 double Xy,double Yy,double Zy,
00302                 double Xz,double Yz,double Zz);
00303     inline Rotation(const Vector& x,const Vector& y,const Vector& z);
00304     // default copy constructor is sufficient
00305 
00306 
00307      inline Rotation& operator=(const Rotation& arg);
00308 
00311      inline Vector operator*(const Vector& v) const;
00312 
00314      inline double& operator()(int i,int j);
00315 
00317      inline double operator() (int i,int j) const;
00318 
00319      friend Rotation operator *(const Rotation& lhs,const Rotation& rhs);
00320 
00322      inline void SetInverse();
00323 
00325      inline Rotation Inverse() const;
00326 
00328      inline Vector Inverse(const Vector& v) const;
00329 
00331      inline Wrench Inverse(const Wrench& arg) const;
00332 
00334      inline Twist Inverse(const Twist& arg) const;
00335 
00337      inline static Rotation Identity();
00338 
00339 
00340 // = Rotations
00342     inline static Rotation RotX(double angle);
00344     inline static Rotation RotY(double angle);
00346     inline static Rotation RotZ(double angle);
00349     inline void DoRotX(double angle);
00352     inline void DoRotY(double angle);
00355     inline void DoRotZ(double angle);
00356 
00360     // @see Rot2 if you want to handle this error in another way.
00361     static Rotation Rot(const Vector& rotvec,double angle);
00362 
00364     static Rotation Rot2(const Vector& rotvec,double angle);
00365 
00368     Vector GetRot() const;
00369 
00378         double GetRotAngle(Vector& axis,double eps=epsilon) const;
00379 
00380 
00385     static Rotation EulerZYZ(double Alfa,double Beta,double Gamma);
00386 
00396     void GetEulerZYZ(double& alfa,double& beta,double& gamma) const;
00397 
00400     static Rotation Quaternion(double x,double y,double z, double w);
00401     
00404     void GetQuaternion(double& x,double& y,double& z, double& w) const;
00405 
00409     static Rotation RPY(double roll,double pitch,double yaw);
00410 
00418     void GetRPY(double& roll,double& pitch,double& yaw) const;
00419 
00420 
00427     inline static Rotation EulerZYX(double Alfa,double Beta,double Gamma) {
00428         return RPY(Gamma,Beta,Alfa);
00429     }
00430 
00442     inline void GetEulerZYX(double& Alfa,double& Beta,double& Gamma) const {
00443         GetRPY(Gamma,Beta,Alfa);
00444     }
00445 
00450      inline Twist operator * (const Twist& arg) const;
00451 
00456      inline Wrench operator * (const Wrench& arg) const;
00457 
00459      inline Vector UnitX() const {
00460          return Vector(data[0],data[3],data[6]);
00461      }
00462 
00464      inline void UnitX(const Vector& X) {
00465         data[0] = X(0);
00466         data[3] = X(1);
00467         data[6] = X(2);
00468      }
00469 
00471      inline Vector UnitY() const {
00472          return Vector(data[1],data[4],data[7]);
00473      }
00474 
00476      inline void UnitY(const Vector& X) {
00477         data[1] = X(0);
00478         data[4] = X(1);
00479         data[7] = X(2);
00480      }
00481 
00483      inline Vector UnitZ() const {
00484          return Vector(data[2],data[5],data[8]);
00485      }
00486 
00488      inline void UnitZ(const Vector& X) {
00489         data[2] = X(0);
00490         data[5] = X(1);
00491         data[8] = X(2);
00492      }
00493 
00496      friend bool Equal(const Rotation& a,const Rotation& b,double eps=epsilon);
00497 
00499      friend bool operator==(const Rotation& a,const Rotation& b);
00501      friend bool operator!=(const Rotation& a,const Rotation& b);
00502 
00503      friend class Frame;
00504 };
00505     bool operator==(const Rotation& a,const Rotation& b);
00506 
00507 
00508 
00518 class Frame {
00519 public:
00520     Vector p;       
00521     Rotation M;     
00522 
00523 public:
00524 
00525      inline Frame(const Rotation& R,const Vector& V);
00526 
00528      explicit inline Frame(const Vector& V);
00530      explicit inline Frame(const Rotation& R);
00531 
00532      inline Frame() {}
00534      inline Frame(const Frame& arg);
00535 
00537      //\TODO should be formulated as a constructor
00538      void Make4x4(double* d);
00539 
00542      inline double operator()(int i,int j);
00543 
00546      inline double operator() (int i,int j) const;
00547 
00548 // = Inverse
00550      inline Frame Inverse() const;
00551 
00553      inline Vector Inverse(const Vector& arg) const;
00554 
00556      inline Wrench Inverse(const Wrench& arg) const;
00557 
00559      inline Twist  Inverse(const Twist& arg) const;
00560 
00562      inline Frame& operator = (const Frame& arg);
00563 
00566      inline Vector operator * (const Vector& arg) const;
00567 
00574      inline Wrench operator * (const Wrench& arg) const;
00575 
00582      inline Twist operator * (const Twist& arg) const;
00583 
00585      inline friend Frame operator *(const Frame& lhs,const Frame& rhs);
00586 
00588      inline static Frame Identity();
00589 
00593      inline void Integrate(const Twist& t_this,double frequency);
00594 
00595     /*
00596     // DH_Craig1989 : constructs a transformationmatrix
00597     // T_link(i-1)_link(i) with the Denavit-Hartenberg convention as
00598     // described in the Craigs book: Craig, J. J.,Introduction to
00599     // Robotics: Mechanics and Control, Addison-Wesley,
00600     // isbn:0-201-10326-5, 1986.
00601     //
00602     // Note that the frame is a redundant way to express the information
00603     // in the DH-convention.
00604     // \verbatim
00605     // Parameters in full : a(i-1),alpha(i-1),d(i),theta(i)
00606     //
00607     //  axis i-1 is connected by link i-1 to axis i numbering axis 1
00608     //  to axis n link 0 (immobile base) to link n
00609     //
00610     //  link length a(i-1) length of the mutual perpendicular line
00611     //  (normal) between the 2 axes.  This normal runs from (i-1) to
00612     //  (i) axis.
00613     //
00614     //  link twist alpha(i-1): construct plane perpendicular to the
00615     //  normal project axis(i-1) and axis(i) into plane angle from
00616     //  (i-1) to (i) measured in the direction of the normal
00617     //
00618     //  link offset d(i) signed distance between normal (i-1) to (i)
00619     //  and normal (i) to (i+1) along axis i joint angle theta(i)
00620     //  signed angle between normal (i-1) to (i) and normal (i) to
00621     //  (i+1) along axis i
00622     //
00623     //   First and last joints : a(0)= a(n) = 0
00624     //   alpha(0) = alpha(n) = 0
00625     //
00626     //   PRISMATIC : theta(1) = 0 d(1) arbitrarily
00627     //
00628     //   REVOLUTE : theta(1) arbitrarily d(1) = 0
00629     //
00630     //   Not unique : if intersecting joint axis 2 choices for normal
00631     //   Frame assignment of the DH convention : Z(i-1) follows axis
00632     //   (i-1) X(i-1) is the normal between axis(i-1) and axis(i)
00633     //   Y(i-1) follows out of Z(i-1) and X(i-1)
00634     //
00635     //     a(i-1)     = distance from Z(i-1) to Z(i) along X(i-1)
00636     //     alpha(i-1) = angle between Z(i-1) to Z(i) along X(i-1)
00637     //     d(i)       = distance from X(i-1) to X(i) along Z(i)
00638     //     theta(i)   = angle between X(i-1) to X(i) along X(i)
00639     // \endverbatim
00640     */
00641      static Frame DH_Craig1989(double a,double alpha,double d,double theta);
00642 
00643     // DH : constructs a transformationmatrix T_link(i-1)_link(i) with
00644     // the Denavit-Hartenberg convention as described in the original
00645     // publictation: Denavit, J. and Hartenberg, R. S., A kinematic
00646     // notation for lower-pair mechanisms based on matrices, ASME
00647     // Journal of Applied Mechanics, 23:215-221, 1955.
00648 
00649      static Frame DH(double a,double alpha,double d,double theta);
00650 
00651 
00654      inline friend bool Equal(const Frame& a,const Frame& b,double eps=epsilon);
00655 
00657      inline friend bool operator==(const Frame& a,const Frame& b);
00659      inline friend bool operator!=(const Frame& a,const Frame& b);
00660 };
00661 
00668 class Twist {
00669 public:
00670     Vector vel; 
00671     Vector rot; 
00672 public:
00673 
00675     Twist():vel(),rot() {};
00676 
00677     Twist(const Vector& _vel,const Vector& _rot):vel(_vel),rot(_rot) {};
00678 
00679     inline Twist& operator-=(const Twist& arg);
00680     inline Twist& operator+=(const Twist& arg);
00682     inline double& operator()(int i);
00683 
00686     inline double operator()(int i) const;
00687 
00688      double operator[] ( int index ) const
00689        {
00690          return this->operator() ( index );
00691        }
00692 
00693      double& operator[] ( int index )
00694        {
00695          return this->operator() ( index );
00696        }
00697 
00698      inline friend Twist operator*(const Twist& lhs,double rhs);
00699      inline friend Twist operator*(double lhs,const Twist& rhs);
00700      inline friend Twist operator/(const Twist& lhs,double rhs);
00701      inline friend Twist operator+(const Twist& lhs,const Twist& rhs);
00702      inline friend Twist operator-(const Twist& lhs,const Twist& rhs);
00703      inline friend Twist operator-(const Twist& arg);
00704      inline friend double dot(const Twist& lhs,const Wrench& rhs);
00705      inline friend double dot(const Wrench& rhs,const Twist& lhs);
00706      inline friend void SetToZero(Twist& v);
00708     inline friend Twist operator*(const Twist& lhs,const Twist& rhs);
00710     inline friend Wrench operator*(const Twist& lhs,const Wrench& rhs);
00711 
00713      static inline Twist Zero();
00714 
00716      inline void ReverseSign();
00717 
00724      inline Twist RefPoint(const Vector& v_base_AB) const;
00725 
00726 
00729      inline friend bool Equal(const Twist& a,const Twist& b,double eps=epsilon);
00730 
00732      inline friend bool operator==(const Twist& a,const Twist& b);
00734      inline friend bool operator!=(const Twist& a,const Twist& b);
00735 
00736 // = Friends
00737     friend class Rotation;
00738     friend class Frame;
00739 
00740 };
00741 
00749 /*
00750 class AccelerationTwist {
00751 public:
00752     Vector trans; //!< The translational acceleration of that point
00753     Vector rot; //!< The rotational acceleration of that point.
00754 public:
00755 
00757     AccelerationTwist():trans(),rot() {};
00758 
00759     AccelerationTwist(const Vector& _trans,const Vector& _rot):trans(_trans),rot(_rot) {};
00760 
00761     inline AccelerationTwist& operator-=(const AccelerationTwist& arg);
00762     inline AccelerationTwist& operator+=(const AccelerationTwist& arg);
00764     inline double& operator()(int i);
00765 
00768     inline double operator()(int i) const;
00769 
00770     double operator[] ( int index ) const
00771     {
00772         return this->operator() ( index );
00773         }
00774 
00775      double& operator[] ( int index )
00776      {
00777          return this->operator() ( index );
00778      }
00779 
00780      inline friend AccelerationTwist operator*(const AccelerationTwist& lhs,double rhs);
00781      inline friend AccelerationTwist operator*(double lhs,const AccelerationTwist& rhs);
00782      inline friend AccelerationTwist operator/(const AccelerationTwist& lhs,double rhs);
00783      inline friend AccelerationTwist operator+(const AccelerationTwist& lhs,const AccelerationTwist& rhs);
00784      inline friend AccelerationTwist operator-(const AccelerationTwist& lhs,const AccelerationTwist& rhs);
00785      inline friend AccelerationTwist operator-(const AccelerationTwist& arg);
00786      //inline friend double dot(const AccelerationTwist& lhs,const Wrench& rhs);
00787      //inline friend double dot(const Wrench& rhs,const AccelerationTwist& lhs);
00788      inline friend void SetToZero(AccelerationTwist& v);
00789 
00790 
00792      static inline AccelerationTwist Zero();
00793 
00795      inline void ReverseSign();
00796 
00803      inline AccelerationTwist RefPoint(const Vector& v_base_AB) const;
00804 
00805 
00808      inline friend bool Equal(const AccelerationTwist& a,const AccelerationTwist& b,double eps=epsilon);
00809 
00811      inline friend bool operator==(const AccelerationTwist& a,const AccelerationTwist& b);
00813      inline friend bool operator!=(const AccelerationTwist& a,const AccelerationTwist& b);
00814 
00815 // = Friends
00816     friend class Rotation;
00817     friend class Frame;
00818 
00819 };
00820 */
00826 class Wrench
00827 {
00828 public:
00829     Vector force;       
00830     Vector torque;      
00831 public:
00832 
00834     Wrench():force(),torque() {};
00835     Wrench(const Vector& _force,const Vector& _torque):force(_force),torque(_torque) {};
00836 
00837 // = Operators
00838      inline Wrench& operator-=(const Wrench& arg);
00839      inline Wrench& operator+=(const Wrench& arg);
00840 
00842      inline double& operator()(int i);
00843 
00846      inline double operator()(int i) const;
00847 
00848      double operator[] ( int index ) const
00849        {
00850          return this->operator() ( index );
00851        }
00852 
00853      double& operator[] ( int index )
00854        {
00855          return this->operator() ( index );
00856        }
00857 
00859      inline friend Wrench operator*(const Wrench& lhs,double rhs);
00861      inline friend Wrench operator*(double lhs,const Wrench& rhs);
00863      inline friend Wrench operator/(const Wrench& lhs,double rhs);
00864 
00865      inline friend Wrench operator+(const Wrench& lhs,const Wrench& rhs);
00866      inline friend Wrench operator-(const Wrench& lhs,const Wrench& rhs);
00867 
00869      inline friend Wrench operator-(const Wrench& arg);
00870 
00873      inline friend void SetToZero(Wrench& v);
00874 
00876      static inline Wrench Zero();
00877 
00879      inline void ReverseSign();
00880 
00887      inline Wrench RefPoint(const Vector& v_base_AB) const;
00888 
00889 
00892      inline friend bool Equal(const Wrench& a,const Wrench& b,double eps=epsilon);
00893 
00895      inline friend bool operator==(const Wrench& a,const Wrench& b);
00897      inline friend bool operator!=(const Wrench& a,const Wrench& b);
00898 
00899     friend class Rotation;
00900     friend class Frame;
00901 
00902 
00903 };
00904 
00905 
00907 class Vector2
00908 {
00909     double data[2];
00910 public:
00912      Vector2() {data[0]=data[1] = 0.0;}
00913      inline Vector2(double x,double y);
00914      inline Vector2(const Vector2& arg);
00915 
00916      inline Vector2& operator = ( const Vector2& arg);
00917 
00919      inline double operator()(int index) const;
00920 
00922      inline double& operator() (int index);
00923 
00925         double operator[] ( int index ) const
00926         {
00927                 return this->operator() ( index );
00928         }
00929 
00931         double& operator[] ( int index )
00932         {
00933                 return this->operator() ( index );
00934         }
00935 
00936         inline double x() const;
00937         inline double y() const;
00938         inline void x(double);
00939         inline void y(double);
00940 
00941      inline void ReverseSign();
00942      inline Vector2& operator-=(const Vector2& arg);
00943      inline Vector2& operator +=(const Vector2& arg);
00944 
00945 
00946      inline friend Vector2 operator*(const Vector2& lhs,double rhs);
00947      inline friend Vector2 operator*(double lhs,const Vector2& rhs);
00948      inline friend Vector2 operator/(const Vector2& lhs,double rhs);
00949      inline friend Vector2 operator+(const Vector2& lhs,const Vector2& rhs);
00950      inline friend Vector2 operator-(const Vector2& lhs,const Vector2& rhs);
00951      inline friend Vector2 operator*(const Vector2& lhs,const Vector2& rhs);
00952      inline friend Vector2 operator-(const Vector2& arg);
00953      inline friend void SetToZero(Vector2& v);
00954 
00956      inline static Vector2 Zero();
00957 
00963      double Normalize(double eps=epsilon);
00964 
00966      double Norm() const;
00967 
00969      inline void Set3DXY(const Vector& v);
00970 
00972      inline void Set3DYZ(const Vector& v);
00973 
00975      inline void Set3DZX(const Vector& v);
00976 
00980      inline void Set3DPlane(const Frame& F_someframe_XY,const Vector& v_someframe);
00981 
00982 
00985      inline friend bool Equal(const Vector2& a,const Vector2& b,double eps=epsilon);
00986 
00988         inline friend bool operator==(const Vector2& a,const Vector2& b);
00990         inline friend bool operator!=(const Vector2& a,const Vector2& b);
00991 
00992     friend class Rotation2;
00993 };
00994 
00995 
00998 class Rotation2
00999 {
01000     double s,c;
01003 public:
01005     Rotation2() {c=1.0;s=0.0;}
01006 
01007     explicit Rotation2(double angle_rad):s(sin(angle_rad)),c(cos(angle_rad)) {}
01008 
01009     Rotation2(double ca,double sa):s(sa),c(ca){}
01010 
01011      inline Rotation2& operator=(const Rotation2& arg);
01012      inline Vector2 operator*(const Vector2& v) const;
01014      inline double operator() (int i,int j) const;
01015 
01016      inline friend Rotation2 operator *(const Rotation2& lhs,const Rotation2& rhs);
01017 
01018      inline void SetInverse();
01019      inline Rotation2 Inverse() const;
01020      inline Vector2 Inverse(const Vector2& v) const;
01021 
01022      inline void SetIdentity();
01023      inline static Rotation2 Identity();
01024 
01025 
01027      inline void SetRot(double angle);
01028 
01030      inline static Rotation2 Rot(double angle);
01031 
01033      inline double GetRot() const;
01034 
01037      inline friend bool Equal(const Rotation2& a,const Rotation2& b,double eps=epsilon);
01038 };
01039 
01042 class Frame2
01043  {
01044 public:
01045     Vector2 p;          
01046     Rotation2 M;        
01047 
01048 public:
01049 
01050      inline Frame2(const Rotation2& R,const Vector2& V);
01051      explicit inline Frame2(const Vector2& V);
01052      explicit inline Frame2(const Rotation2& R);
01053      inline Frame2(void);
01054      inline Frame2(const Frame2& arg);
01055      inline void Make4x4(double* d);
01056 
01059      inline double operator()(int i,int j);
01060 
01063      inline double operator() (int i,int j) const;
01064 
01065      inline void SetInverse();
01066      inline Frame2 Inverse() const;
01067      inline Vector2 Inverse(const Vector2& arg) const;
01068      inline Frame2& operator = (const Frame2& arg);
01069      inline Vector2 operator * (const Vector2& arg);
01070      inline friend Frame2 operator *(const Frame2& lhs,const Frame2& rhs);
01071      inline void SetIdentity();
01072      inline void Integrate(const Twist& t_this,double frequency);
01073      inline static Frame2 Identity() {
01074         Frame2 tmp;
01075         tmp.SetIdentity();
01076         return tmp;
01077      }
01078      inline friend bool Equal(const Frame2& a,const Frame2& b,double eps=epsilon);
01079 };
01080 
01081 IMETHOD Vector diff(const Vector& a,const Vector& b,double dt=1);
01082 IMETHOD Vector diff(const Rotation& R_a_b1,const Rotation& R_a_b2,double dt=1);
01083 IMETHOD Twist diff(const Frame& F_a_b1,const Frame& F_a_b2,double dt=1);
01084 IMETHOD Twist diff(const Twist& a,const Twist& b,double dt=1);
01085 IMETHOD Wrench diff(const Wrench& W_a_p1,const Wrench& W_a_p2,double dt=1);
01086 IMETHOD Vector addDelta(const Vector& a,const Vector&da,double dt=1);
01087 IMETHOD Rotation addDelta(const Rotation& a,const Vector&da,double dt=1);
01088 IMETHOD Frame addDelta(const Frame& a,const Twist& da,double dt=1);
01089 IMETHOD Twist addDelta(const Twist& a,const Twist&da,double dt=1);
01090 IMETHOD Wrench addDelta(const Wrench& a,const Wrench&da,double dt=1);
01091 
01092 } // namespace KDL
01093 
01094 #ifdef KDL_INLINE
01095 //    #include "vector.inl"
01096 //   #include "wrench.inl"
01097     //#include "rotation.inl"
01098     //#include "frame.inl"
01099     //#include "twist.inl"
01100     //#include "vector2.inl"
01101     //#include "rotation2.inl"
01102     //#include "frame2.inl"
01103 #include "frames.inl"
01104 #endif
01105 
01106 
01107 
01108 #endif

Generated on Wed Nov 23 19:00:14 2011 for FreeCAD by  doxygen 1.6.1