Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022 #ifndef KDL_ROTATIONALINERTIA_HPP
00023 #define KDL_ROTATIONALINERTIA_HPP
00024
00025 #include "frames.hpp"
00026
00027
00028
00029 namespace KDL
00030 {
00031
00032 class RigidBodyInertia;
00033
00034 class RotationalInertia{
00035 public:
00036
00037 explicit RotationalInertia(double Ixx=0,double Iyy=0,double Izz=0,double Ixy=0,double Ixz=0,double Iyz=0);
00038
00039 static inline RotationalInertia Zero(){
00040 return RotationalInertia(0,0,0,0,0,0);
00041 };
00042
00043 friend RotationalInertia operator*(double a, const RotationalInertia& I);
00044 friend RotationalInertia operator+(const RotationalInertia& Ia, const RotationalInertia& Ib);
00045
00049 KDL::Vector operator*(const KDL::Vector& omega) const;
00050
00051 ~RotationalInertia();
00052
00053 friend class RigidBodyInertia;
00055 friend RigidBodyInertia operator*(double a,const RigidBodyInertia& I);
00057 friend RigidBodyInertia operator+(const RigidBodyInertia& Ia,const RigidBodyInertia& Ib);
00059 friend Wrench operator*(const RigidBodyInertia& I,const Twist& t);
00061 friend RigidBodyInertia operator*(const Frame& T,const RigidBodyInertia& I);
00063 friend RigidBodyInertia operator*(const Rotation& R,const RigidBodyInertia& I);
00064
00065 double data[9];
00066 };
00067
00068 RotationalInertia operator*(double a, const RotationalInertia& I);
00069 RotationalInertia operator+(const RotationalInertia& Ia, const RotationalInertia& Ib);
00070
00071 }
00072
00073 #endif
00074