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 #ifndef UndercarriageCtrlGeom_INCLUDEDEF_H
00019 #define UndercarriageCtrlGeom_INCLUDEDEF_H
00020 
00021 
00022 
00023 #include <cob_utilities/IniFile.h>
00024 #include <cob_utilities/MathSup.h>
00025 #include <cob_utilities/TimeStamp.h>
00026 
00027 class UndercarriageCtrlGeom
00028 {
00029 private:
00030 
00031         bool m_bEMStopActive;
00032 
00033         int m_iNumberOfDrives;
00034 
00035         std::string m_sIniDirectory;
00036 
00037         
00038 
00039 
00040 
00041 
00042 
00043 
00044 
00045 
00046 
00047 
00048         
00049         double m_dVelLongMMS;
00050         double m_dVelLatMMS;
00051         double m_dRotRobRadS;
00052         double m_dRotVelRadS;
00053 
00054         
00055         std::vector<double> m_vdVelGearDriveRadS;
00056         std::vector<double> m_vdVelGearSteerRadS;
00057         std::vector<double> m_vdDltAngGearDriveRad;
00058         std::vector<double> m_vdAngGearSteerRad;
00059 
00060         
00061         double m_dCmdVelLongMMS;
00062         double m_dCmdVelLatMMS;
00063         double m_dCmdRotRobRadS;
00064         double m_dCmdRotVelRadS;
00065 
00066         
00067 
00068 
00069 
00070 
00071 
00072 
00073 
00074 
00075         
00076         std::vector<double> m_vdVelGearDriveCmdRadS;
00077         std::vector<double> m_vdVelGearSteerCmdRadS;
00078         std::vector<double> m_vdAngGearSteerCmdRad;
00079 
00080         
00081         
00082         std::vector<double> m_vdAngGearSteerTarget1Rad; 
00083         std::vector<double> m_vdVelGearDriveTarget1RadS;
00084         std::vector<double> m_vdAngGearSteerTarget2Rad; 
00085         std::vector<double> m_vdVelGearDriveTarget2RadS;
00086         std::vector<double> m_vdAngGearSteerTargetRad; 
00087         std::vector<double> m_vdVelGearDriveTargetRadS;
00088 
00093         std::vector<double> m_vdWheelXPosMM;
00094         std::vector<double> m_vdWheelYPosMM;
00095         std::vector<double> m_vdWheelDistMM;
00096         std::vector<double> m_vdWheelAngRad;
00097 
00102         std::vector<double> m_vdExWheelXPosMM;
00103         std::vector<double> m_vdExWheelYPosMM;
00104         std::vector<double> m_vdExWheelDistMM;
00105         std::vector<double> m_vdExWheelAngRad;
00106 
00107         struct ParamType
00108         {
00109                 int iDistWheels;
00110                 int iRadiusWheelMM;
00111 
00112                 int iDistSteerAxisToDriveWheelMM;
00113 
00114                 double dMaxDriveRateRadpS;
00115                 double dMaxSteerRateRadpS;
00116                 double dCmdRateS;
00117                 std::vector<double> WheelNeutralPos;
00118                 std::vector<double> vdSteerDriveCoupling;
00123                 std::vector<double> vdFactorVel;
00124         };
00125 
00126         ParamType m_UnderCarriagePrms;
00127 
00138         double m_dSpring, m_dDamp, m_dVirtM, m_dDPhiMax, m_dDDPhiMax;
00147         std::vector< std::vector<double> > m_vdCtrlVal;
00148 
00149         
00150         
00151 
00152         
00153         void CalcInverse(void);
00154 
00155         
00156         void CalcDirect(void);
00157 
00158         
00159         void CalcExWheelPos(void);
00160 
00161         
00162         void CalcControlStep(void);
00163 
00164 public:
00165 
00166         
00167         UndercarriageCtrlGeom(std::string sIniDirectory);
00168 
00169         
00170         ~UndercarriageCtrlGeom(void);
00171 
00172         
00173         void InitUndercarriageCtrl(void);
00174 
00175         
00176         void SetDesiredPltfVelocity(double dCmdVelLongMMS, double dCmdVelLatMMS, double dCmdRotRobRadS, double dCmdRotVelRadS);
00177 
00178         
00179         void SetActualWheelValues(std::vector<double> vdVelGearDriveRadS, std::vector<double> vdVelGearSteerRadS, std::vector<double> vdDltAngGearDriveRad, std::vector<double> vdAngGearSteerRad);
00180 
00181         
00182         void GetSteerDriveSetValues(std::vector<double> & vdVelGearDriveRadS, std::vector<double> & vdAngGearSteerRad);
00183 
00184         
00185         void GetNewCtrlStateSteerDriveSetValues(std::vector<double> & vdVelGearDriveRadS, std::vector<double> & vdVelGearSteerRadS, std::vector<double> & vdAngGearSteerRad,
00186                                                 double & dVelLongMMS, double & dVelLatMMS, double & dRotRobRadS, double & dRotVelRadS);
00187 
00188         
00189         void GetActualPltfVelocity(double & dDeltaLongMM, double & dDeltaLatMM, double & dDeltaRotRobRad, double & dDeltaRotVelRad,
00190                                         double & dVelLongMMS, double & dVelLatMMS, double & dRotRobRadS, double & dRotVelRadS);
00191 
00192         
00193         void setEMStopActive(bool bEMStopActive);
00194 
00195         
00196         void operator=(const UndercarriageCtrlGeom & GeomCtrl);
00197 };
00198 #endif
00199