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_RIGIDBODYINERTIA_HPP
00023 #define KDL_RIGIDBODYINERTIA_HPP
00024
00025 #include "frames.hpp"
00026
00027 #include "rotationalinertia.hpp"
00028
00029 namespace KDL {
00030
00037 class RigidBodyInertia{
00038 public:
00039
00044 explicit RigidBodyInertia(double m=0, const Vector& oc=Vector::Zero(), const RotationalInertia& Ic=RotationalInertia::Zero());
00045
00049 static inline RigidBodyInertia Zero(){
00050 return RigidBodyInertia(0.0,Vector::Zero(),RotationalInertia::Zero());
00051 };
00052
00053
00054 ~RigidBodyInertia(){};
00055
00059 friend RigidBodyInertia operator*(double a,const RigidBodyInertia& I);
00065 friend RigidBodyInertia operator+(const RigidBodyInertia& Ia,const RigidBodyInertia& Ib);
00066
00071 friend Wrench operator*(const RigidBodyInertia& I,const Twist& t);
00072
00076 friend RigidBodyInertia operator*(const Frame& T,const RigidBodyInertia& I);
00081 friend RigidBodyInertia operator*(const Rotation& R,const RigidBodyInertia& I);
00082
00087 RigidBodyInertia RefPoint(const Vector& p);
00088
00092 double getMass() const{
00093 return m;
00094 };
00095
00099 Vector getCOG() const{
00100 if(m==0) return Vector::Zero();
00101 else return h/m;
00102 };
00103
00107 RotationalInertia getRotationalInertia() const{
00108 return I;
00109 };
00110
00111 private:
00112 RigidBodyInertia(double m,const Vector& h,const RotationalInertia& I,bool mhi);
00113 double m;
00114 RotationalInertia I;
00115 Vector h;
00116
00117 friend class ArticulatedBodyInertia;
00118
00119 };
00120 }
00121
00122
00123 #endif