00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039
00040
00041
00042
00043
00044
00045
00046
00047
00048
00049
00050
00051
00052
00053
00054 #include <cob_undercarriage_ctrl/UndercarriageCtrlGeom.h>
00055
00056
00057 UndercarriageCtrlGeom::UndercarriageCtrlGeom(std::string sIniDirectory)
00058 {
00059 m_sIniDirectory = sIniDirectory;
00060
00061
00062 m_bEMStopActive = false;
00063
00064 IniFile iniFile;
00065 iniFile.SetFileName(m_sIniDirectory + "Platform.ini", "UnderCarriageCtrlGeom.cpp");
00066 iniFile.GetKeyInt("Config", "NumberOfWheels", &m_iNumberOfDrives, true);
00067
00068
00069 m_vdVelGearDriveRadS.assign(4,0);
00070 m_vdVelGearSteerRadS.assign(4,0);
00071 m_vdDltAngGearDriveRad.assign(4,0);
00072 m_vdAngGearSteerRad.assign(4,0);
00073
00074
00075
00076
00077
00078 m_vdVelGearDriveCmdRadS.assign(4,0);
00079 m_vdVelGearSteerCmdRadS.assign(4,0);
00080 m_vdAngGearSteerCmdRad.assign(4,0);
00081
00082 m_vdWheelXPosMM.assign(4,0);
00083 m_vdWheelYPosMM.assign(4,0);
00084 m_vdWheelDistMM.assign(4,0);
00085 m_vdWheelAngRad.assign(4,0);
00086
00087 m_vdExWheelXPosMM.assign(4,0);
00088 m_vdExWheelYPosMM.assign(4,0);
00089 m_vdExWheelDistMM.assign(4,0);
00090 m_vdExWheelAngRad.assign(4,0);
00091
00092 m_vdAngGearSteerTarget1Rad.assign(4,0);
00093 m_vdVelGearDriveTarget1RadS.assign(4,0);
00094 m_vdAngGearSteerTarget2Rad.assign(4,0);
00095 m_vdVelGearDriveTarget2RadS.assign(4,0);
00096 m_vdAngGearSteerTargetRad.assign(4,0);
00097 m_vdVelGearDriveTargetRadS.assign(4,0);
00098
00099 m_dCmdVelLongMMS = 0;
00100 m_dCmdVelLatMMS = 0;
00101 m_dCmdRotRobRadS = 0;
00102 m_dCmdRotVelRadS = 0;
00103
00104 m_UnderCarriagePrms.WheelNeutralPos.assign(4,0);
00105 m_UnderCarriagePrms.vdSteerDriveCoupling.assign(4,0);
00106 m_UnderCarriagePrms.vdFactorVel.assign(4,0);
00107
00108 m_vdCtrlVal.assign( 4, std::vector<double> (2,0.0) );
00109
00110
00111
00112
00113
00114 m_dSpring = 10.0;
00115 m_dDamp = 2.5;
00116 m_dVirtM = 0.1;
00117 m_dDPhiMax = 12.0;
00118 m_dDDPhiMax = 100.0;
00119
00120
00121
00122
00123
00124
00125
00126
00127
00128
00129
00130
00131
00132
00133
00134
00135
00136 }
00137
00138
00139 UndercarriageCtrlGeom::~UndercarriageCtrlGeom(void)
00140 {
00141
00142
00143
00144
00145
00146
00147
00148
00149
00150
00151
00152
00153 }
00154
00155
00156 void UndercarriageCtrlGeom::InitUndercarriageCtrl(void)
00157 {
00158
00159
00160 IniFile iniFile;
00161
00162 iniFile.SetFileName(m_sIniDirectory + "Platform.ini", "UnderCarriageCtrlGeom.cpp");
00163 iniFile.GetKeyInt("Geom", "DistWheels", &m_UnderCarriagePrms.iDistWheels, true);
00164 iniFile.GetKeyInt("Geom", "RadiusWheel", &m_UnderCarriagePrms.iRadiusWheelMM, true);
00165 iniFile.GetKeyInt("Geom", "DistSteerAxisToDriveWheelCenter", &m_UnderCarriagePrms.iDistSteerAxisToDriveWheelMM, true);
00166
00167 iniFile.GetKeyDouble("Geom", "Wheel1XPos", &m_vdWheelXPosMM[0], true);
00168 iniFile.GetKeyDouble("Geom", "Wheel1YPos", &m_vdWheelYPosMM[0], true);
00169 iniFile.GetKeyDouble("Geom", "Wheel2XPos", &m_vdWheelXPosMM[1], true);
00170 iniFile.GetKeyDouble("Geom", "Wheel2YPos", &m_vdWheelYPosMM[1], true);
00171 iniFile.GetKeyDouble("Geom", "Wheel3XPos", &m_vdWheelXPosMM[2], true);
00172 iniFile.GetKeyDouble("Geom", "Wheel3YPos", &m_vdWheelYPosMM[2], true);
00173 iniFile.GetKeyDouble("Geom", "Wheel4XPos", &m_vdWheelXPosMM[3], true);
00174 iniFile.GetKeyDouble("Geom", "Wheel4YPos", &m_vdWheelYPosMM[3], true);
00175
00176 iniFile.GetKeyDouble("DrivePrms", "MaxDriveRate", &m_UnderCarriagePrms.dMaxDriveRateRadpS, true);
00177 iniFile.GetKeyDouble("DrivePrms", "MaxSteerRate", &m_UnderCarriagePrms.dMaxSteerRateRadpS, true);
00178
00179 iniFile.GetKeyDouble("DrivePrms", "Wheel1SteerDriveCoupling", &m_UnderCarriagePrms.vdSteerDriveCoupling[0], true);
00180 iniFile.GetKeyDouble("DrivePrms", "Wheel2SteerDriveCoupling", &m_UnderCarriagePrms.vdSteerDriveCoupling[1], true);
00181 iniFile.GetKeyDouble("DrivePrms", "Wheel3SteerDriveCoupling", &m_UnderCarriagePrms.vdSteerDriveCoupling[2], true);
00182 iniFile.GetKeyDouble("DrivePrms", "Wheel4SteerDriveCoupling", &m_UnderCarriagePrms.vdSteerDriveCoupling[3], true);
00183
00184 iniFile.GetKeyDouble("DrivePrms", "Wheel1NeutralPosition", &m_UnderCarriagePrms.WheelNeutralPos[0], true);
00185 iniFile.GetKeyDouble("DrivePrms", "Wheel2NeutralPosition", &m_UnderCarriagePrms.WheelNeutralPos[1], true);
00186 iniFile.GetKeyDouble("DrivePrms", "Wheel3NeutralPosition", &m_UnderCarriagePrms.WheelNeutralPos[2], true);
00187 iniFile.GetKeyDouble("DrivePrms", "Wheel4NeutralPosition", &m_UnderCarriagePrms.WheelNeutralPos[3], true);
00188
00189 for(int i = 0; i<4; i++)
00190 {
00191 m_UnderCarriagePrms.WheelNeutralPos[i] = MathSup::convDegToRad(m_UnderCarriagePrms.WheelNeutralPos[i]);
00192
00193 m_vdAngGearSteerCmdRad[i] = m_UnderCarriagePrms.WheelNeutralPos[i];
00194
00195
00196
00197 m_vdAngGearSteerTargetRad[i] = m_UnderCarriagePrms.WheelNeutralPos[i];
00198 }
00199
00200 iniFile.GetKeyDouble("Thread", "ThrUCarrCycleTimeS", &m_UnderCarriagePrms.dCmdRateS, true);
00201
00202
00203 iniFile.SetFileName(m_sIniDirectory + "MotionCtrl.ini", "PltfHardwareCoB3.h");
00204
00205 iniFile.GetKeyDouble("SteerCtrl", "Spring", &m_dSpring, true);
00206 iniFile.GetKeyDouble("SteerCtrl", "Damp", &m_dDamp, true);
00207 iniFile.GetKeyDouble("SteerCtrl", "VirtMass", &m_dVirtM, true);
00208 iniFile.GetKeyDouble("SteerCtrl", "DPhiMax", &m_dDPhiMax, true);
00209 iniFile.GetKeyDouble("SteerCtrl", "DDPhiMax", &m_dDDPhiMax, true);
00210
00211
00212 for(int i=0; i<4; i++)
00213 {
00214 m_vdWheelDistMM[i] = sqrt( (m_vdWheelXPosMM[i] * m_vdWheelXPosMM[i]) + (m_vdWheelYPosMM[i] * m_vdWheelYPosMM[i]) );
00215 m_vdWheelAngRad[i] = MathSup::atan4quad(m_vdWheelXPosMM[i], m_vdWheelYPosMM[i]);
00216 }
00217
00218
00219 CalcExWheelPos();
00220
00221
00222 for(int i = 0; i<4; i++)
00223 {
00224 m_UnderCarriagePrms.vdFactorVel[i] = - m_UnderCarriagePrms.vdSteerDriveCoupling[i]
00225 +(double(m_UnderCarriagePrms.iDistSteerAxisToDriveWheelMM) / double(m_UnderCarriagePrms.iRadiusWheelMM));
00226 }
00227
00228 }
00229
00230
00231 void UndercarriageCtrlGeom::SetDesiredPltfVelocity(double dCmdVelLongMMS, double dCmdVelLatMMS, double dCmdRotRobRadS, double dCmdRotVelRadS)
00232 {
00233
00234 double dCurrentPosWheelRAD;
00235 double dtempDeltaPhi1RAD, dtempDeltaPhi2RAD;
00236 double dtempDeltaPhiCmd1RAD, dtempDeltaPhiCmd2RAD;
00237 double dtempWeightedDelta1RAD, dtempWeightedDelta2RAD;
00238
00239
00240 m_dCmdVelLongMMS = dCmdVelLongMMS;
00241 m_dCmdVelLatMMS = dCmdVelLatMMS;
00242 m_dCmdRotRobRadS = dCmdRotRobRadS;
00243 m_dCmdRotVelRadS = dCmdRotVelRadS;
00244
00245 CalcInverse();
00246
00247
00248 for (int i = 0; i<4; i++)
00249 {
00250
00251 dCurrentPosWheelRAD = m_vdAngGearSteerRad[i];
00252 MathSup::normalizePi(dCurrentPosWheelRAD);
00253
00254
00255 dtempDeltaPhi1RAD = m_vdAngGearSteerTarget1Rad[i] - dCurrentPosWheelRAD;
00256 dtempDeltaPhi2RAD = m_vdAngGearSteerTarget2Rad[i] - dCurrentPosWheelRAD;
00257 MathSup::normalizePi(dtempDeltaPhi1RAD);
00258 MathSup::normalizePi(dtempDeltaPhi2RAD);
00259
00260 dtempDeltaPhiCmd1RAD = m_vdAngGearSteerTarget1Rad[i] - m_vdAngGearSteerTargetRad[i];
00261 dtempDeltaPhiCmd2RAD = m_vdAngGearSteerTarget2Rad[i] - m_vdAngGearSteerTargetRad[i];
00262 MathSup::normalizePi(dtempDeltaPhiCmd1RAD);
00263 MathSup::normalizePi(dtempDeltaPhiCmd2RAD);
00264
00265
00266
00267
00268
00269
00270
00271 dtempWeightedDelta1RAD = 0.6*fabs(dtempDeltaPhi1RAD) + 0.4*fabs(dtempDeltaPhiCmd1RAD);
00272 dtempWeightedDelta2RAD = 0.6*fabs(dtempDeltaPhi2RAD) + 0.4*fabs(dtempDeltaPhiCmd2RAD);
00273
00274
00275 if (dtempWeightedDelta1RAD <= dtempWeightedDelta2RAD)
00276 {
00277
00278 m_vdVelGearDriveTargetRadS[i] = m_vdVelGearDriveTarget1RadS[i];
00279 m_vdAngGearSteerTargetRad[i] = m_vdAngGearSteerTarget1Rad[i];
00280 }
00281 else
00282 {
00283
00284 m_vdVelGearDriveTargetRadS[i] = m_vdVelGearDriveTarget2RadS[i];
00285 m_vdAngGearSteerTargetRad[i] = m_vdAngGearSteerTarget2Rad[i];
00286 }
00287
00288
00289
00290
00291
00292
00293
00294
00295
00296
00297
00298
00299
00300
00301
00302
00303
00304
00305
00306
00307
00308
00309
00310
00311
00312
00313
00314
00315
00316
00317
00318
00319 }
00320
00321
00322
00323
00324
00325
00326
00327
00328
00329
00330
00331
00332
00333 }
00334
00335
00336 void UndercarriageCtrlGeom::SetActualWheelValues(std::vector<double> vdVelGearDriveRadS, std::vector<double> vdVelGearSteerRadS, std::vector<double> vdDltAngGearDriveRad, std::vector<double> vdAngGearSteerRad)
00337 {
00338
00339
00340 m_vdVelGearDriveRadS = vdVelGearDriveRadS;
00341 m_vdVelGearSteerRadS = vdVelGearSteerRadS;
00342 m_vdDltAngGearDriveRad = vdDltAngGearDriveRad;
00343 m_vdAngGearSteerRad = vdAngGearSteerRad;
00344
00345
00346 CalcExWheelPos();
00347
00348
00349 CalcDirect();
00350 }
00351
00352
00353 void UndercarriageCtrlGeom::GetSteerDriveSetValues(std::vector<double> & vdVelGearDriveRadS, std::vector<double> & vdAngGearSteerRad)
00354 {
00355
00356
00357 CalcInverse();
00358
00359 vdVelGearDriveRadS = m_vdVelGearDriveTarget1RadS;
00360 vdAngGearSteerRad = m_vdAngGearSteerTarget1Rad;
00361 }
00362
00363
00364 void UndercarriageCtrlGeom::GetNewCtrlStateSteerDriveSetValues(std::vector<double> & vdVelGearDriveRadS, std::vector<double> & vdVelGearSteerRadS, std::vector<double> & vdAngGearSteerRad,
00365 double & dVelLongMMS, double & dVelLatMMS, double & dRotRobRadS, double & dRotVelRadS)
00366 {
00367
00368 if(m_bEMStopActive == false)
00369 {
00370
00371 CalcControlStep();
00372 }
00373
00374 vdVelGearDriveRadS = m_vdVelGearDriveCmdRadS;
00375 vdVelGearSteerRadS = m_vdVelGearSteerCmdRadS;
00376 vdAngGearSteerRad = m_vdAngGearSteerCmdRad;
00377
00378 dVelLongMMS = m_dCmdVelLongMMS;
00379 dVelLatMMS = m_dCmdVelLatMMS;
00380 dRotRobRadS = m_dCmdRotRobRadS;
00381 dRotVelRadS = m_dCmdRotVelRadS;
00382
00383
00384
00385
00386
00387
00388
00389
00390
00391 }
00392
00393
00394 void UndercarriageCtrlGeom::GetActualPltfVelocity(double & dDeltaLongMM, double & dDeltaLatMM, double & dDeltaRotRobRad, double & dDeltaRotVelRad,
00395 double & dVelLongMMS, double & dVelLatMMS, double & dRotRobRadS, double & dRotVelRadS)
00396 {
00397 dVelLongMMS = m_dVelLongMMS;
00398 dVelLatMMS = m_dVelLatMMS;
00399 dRotRobRadS = m_dRotRobRadS;
00400 dRotVelRadS = m_dRotVelRadS;
00401
00402
00403
00404
00405 dDeltaLongMM = dVelLongMMS * m_UnderCarriagePrms.dCmdRateS;
00406 dDeltaLatMM = dVelLatMMS * m_UnderCarriagePrms.dCmdRateS;
00407 dDeltaRotRobRad = dRotRobRadS * m_UnderCarriagePrms.dCmdRateS;
00408 dDeltaRotVelRad = dRotVelRadS * m_UnderCarriagePrms.dCmdRateS;
00409 }
00410
00411
00412 void UndercarriageCtrlGeom::CalcInverse(void)
00413 {
00414
00415 double dtempAxVelXRobMMS, dtempAxVelYRobMMS;
00416
00417
00418 if((m_dCmdVelLongMMS == 0) && (m_dCmdVelLatMMS == 0) && (m_dCmdRotRobRadS == 0) && (m_dCmdRotVelRadS == 0))
00419 {
00420 for(int i = 0; i<4; i++)
00421 {
00422 m_vdAngGearSteerTarget1Rad[i] = m_vdAngGearSteerRad[i];
00423 m_vdVelGearDriveTarget1RadS[i] = 0.0;
00424 m_vdAngGearSteerTarget2Rad[i] = m_vdAngGearSteerRad[i];
00425 m_vdVelGearDriveTarget2RadS[i] = 0.0;
00426 }
00427 return;
00428 }
00429
00430
00431 for (int i = 0; i<4; i++)
00432 {
00433
00434
00435 dtempAxVelXRobMMS = m_dCmdVelLongMMS;
00436 dtempAxVelYRobMMS = m_dCmdVelLatMMS;
00437
00438 dtempAxVelXRobMMS += m_dCmdRotRobRadS * m_vdExWheelDistMM[i] * -sin(m_vdExWheelAngRad[i]);
00439 dtempAxVelYRobMMS += m_dCmdRotRobRadS * m_vdExWheelDistMM[i] * cos(m_vdExWheelAngRad[i]);
00440
00441
00442
00443 m_vdAngGearSteerTarget1Rad[i] = MathSup::atan4quad(dtempAxVelYRobMMS, dtempAxVelXRobMMS);
00444
00445 m_vdAngGearSteerTarget2Rad[i] = m_vdAngGearSteerTarget1Rad[i] + MathSup::PI;
00446 MathSup::normalizePi(m_vdAngGearSteerTarget2Rad[i]);
00447
00448
00449 m_vdVelGearDriveTarget1RadS[i] = sqrt( (dtempAxVelXRobMMS * dtempAxVelXRobMMS) +
00450 (dtempAxVelYRobMMS * dtempAxVelYRobMMS) ) / (double)m_UnderCarriagePrms.iRadiusWheelMM;
00451
00452 m_vdVelGearDriveTarget2RadS[i] = - m_vdVelGearDriveTarget1RadS[i];
00453 }
00454 }
00455
00456
00457 void UndercarriageCtrlGeom::CalcDirect(void)
00458 {
00459
00460 double dtempVelXRobMMS;
00461 double dtempVelYRobMMS;
00462 double dtempRotRobRADPS;
00463 double dtempDiffXMM;
00464 double dtempDiffYMM;
00465 double dtempRelPhiWheelsRAD;
00466 double dtempRelDistWheelsMM;
00467 double dtempRelPhiWheel1RAD;
00468 double dtempRelPhiWheel2RAD;
00469 std::vector<double> vdtempVelWheelMMS(4);
00470
00471
00472 dtempVelXRobMMS = 0;
00473 dtempVelYRobMMS = 0;
00474 dtempRotRobRADPS = 0;
00475
00476
00477
00478
00479 for(int i = 0; i<m_iNumberOfDrives; i++)
00480 {
00481
00482 vdtempVelWheelMMS[i] = m_UnderCarriagePrms.iRadiusWheelMM * (m_vdVelGearDriveRadS[i] - m_UnderCarriagePrms.vdFactorVel[i]* m_vdVelGearSteerRadS[i]);
00483 }
00484
00485
00486 for(int i = 0; i< (m_iNumberOfDrives-1) ; i++)
00487 {
00488
00489 dtempDiffXMM = m_vdExWheelXPosMM[i+1] - m_vdExWheelXPosMM[i];
00490 dtempDiffYMM = m_vdExWheelYPosMM[i+1] - m_vdExWheelYPosMM[i];
00491 dtempRelDistWheelsMM = sqrt( dtempDiffXMM*dtempDiffXMM + dtempDiffYMM*dtempDiffYMM );
00492 dtempRelPhiWheelsRAD = MathSup::atan4quad( dtempDiffYMM, dtempDiffXMM );
00493
00494
00495 dtempRelPhiWheel1RAD = m_vdAngGearSteerRad[i] - dtempRelPhiWheelsRAD;
00496 dtempRelPhiWheel2RAD = m_vdAngGearSteerRad[i+1] - dtempRelPhiWheelsRAD;
00497
00498 dtempRotRobRADPS += (vdtempVelWheelMMS[i+1] * sin(dtempRelPhiWheel2RAD) - vdtempVelWheelMMS[i] * sin(dtempRelPhiWheel1RAD))/dtempRelDistWheelsMM;
00499 }
00500
00501
00502
00503 dtempDiffXMM = m_vdExWheelXPosMM[0] - m_vdExWheelXPosMM[m_iNumberOfDrives-1];
00504 dtempDiffYMM = m_vdExWheelYPosMM[0] - m_vdExWheelYPosMM[m_iNumberOfDrives-1];
00505 dtempRelDistWheelsMM = sqrt( dtempDiffXMM*dtempDiffXMM + dtempDiffYMM*dtempDiffYMM );
00506 dtempRelPhiWheelsRAD = MathSup::atan4quad( dtempDiffYMM, dtempDiffXMM );
00507
00508
00509 dtempRelPhiWheel1RAD = m_vdAngGearSteerRad[m_iNumberOfDrives-1] - dtempRelPhiWheelsRAD;
00510 dtempRelPhiWheel2RAD = m_vdAngGearSteerRad[0] - dtempRelPhiWheelsRAD;
00511
00512
00513 dtempRotRobRADPS += (vdtempVelWheelMMS[0]*sin(dtempRelPhiWheel2RAD) - vdtempVelWheelMMS[m_iNumberOfDrives-1]*sin(dtempRelPhiWheel1RAD))/dtempRelDistWheelsMM;
00514
00515
00516 for(int i = 0; i<m_iNumberOfDrives; i++)
00517 {
00518 dtempVelXRobMMS += vdtempVelWheelMMS[i]*cos(m_vdAngGearSteerRad[i]);
00519 dtempVelYRobMMS += vdtempVelWheelMMS[i]*sin(m_vdAngGearSteerRad[i]);
00520 }
00521
00522
00523 m_dRotRobRadS = dtempRotRobRADPS/m_iNumberOfDrives;
00524 m_dRotVelRadS = 0;
00525
00526
00527 m_dVelLongMMS = dtempVelXRobMMS/m_iNumberOfDrives;
00528 m_dVelLatMMS = dtempVelYRobMMS/m_iNumberOfDrives;
00529
00530
00531
00532 }
00533
00534
00535 void UndercarriageCtrlGeom::CalcExWheelPos(void)
00536 {
00537
00538 for(int i = 0; i<4; i++)
00539 {
00540
00541 m_vdExWheelXPosMM[i] = m_vdWheelXPosMM[i] + m_UnderCarriagePrms.iDistSteerAxisToDriveWheelMM * sin(m_vdAngGearSteerRad[i]);
00542 m_vdExWheelYPosMM[i] = m_vdWheelYPosMM[i] - m_UnderCarriagePrms.iDistSteerAxisToDriveWheelMM * cos(m_vdAngGearSteerRad[i]);
00543
00544
00545 m_vdExWheelDistMM[i] = sqrt( (m_vdExWheelXPosMM[i] * m_vdExWheelXPosMM[i]) + (m_vdExWheelYPosMM[i] * m_vdExWheelYPosMM[i]) );
00546
00547
00548 m_vdExWheelAngRad[i] = MathSup::atan4quad( m_vdExWheelYPosMM[i], m_vdExWheelXPosMM[i]);
00549 }
00550 }
00551
00552
00553 void UndercarriageCtrlGeom::CalcControlStep(void)
00554 {
00555
00556 if ((m_dCmdVelLongMMS == 0) && (m_dCmdVelLatMMS == 0) && (m_dCmdRotRobRadS == 0) && (m_dCmdRotVelRadS == 0))
00557 {
00558 m_vdVelGearDriveCmdRadS.assign(4,0.0);
00559 m_vdVelGearSteerCmdRadS.assign(4,0.0);
00560
00561
00562 for(int i=0; i<4; i++)
00563 {
00564 m_vdCtrlVal[i][0] = 0.0;
00565 m_vdCtrlVal[i][1] = 0.0;
00566 }
00567 return;
00568 }
00569
00570
00571 double dCurrentPosWheelRAD;
00572 double dDeltaPhi;
00573 double dForceDamp, dForceProp, dAccCmd, dVelCmdInt;
00574
00575 for (int i=0; i<4; i++)
00576 {
00577
00578 m_vdVelGearDriveCmdRadS[i] = m_vdVelGearDriveTargetRadS[i];
00579 m_vdAngGearSteerCmdRad[i] = m_vdAngGearSteerTargetRad[i];
00580
00581
00582
00583
00584
00585
00586
00587
00588
00589
00590
00591 }
00592
00593
00594 for (int i = 0; i<4; i++)
00595 {
00596
00597 dCurrentPosWheelRAD = m_vdAngGearSteerRad[i];
00598 MathSup::normalizePi(dCurrentPosWheelRAD);
00599 dDeltaPhi = m_vdAngGearSteerCmdRad[i] - dCurrentPosWheelRAD;
00600 MathSup::normalizePi(dDeltaPhi);
00601
00602
00603
00604
00605 dForceDamp = - m_dDamp * m_vdCtrlVal[i][1];
00606 dForceProp = m_dSpring * dDeltaPhi;
00607 dAccCmd = (dForceDamp + dForceProp) / m_dVirtM;
00608 if (dAccCmd > m_dDDPhiMax)
00609 {
00610 dAccCmd = m_dDDPhiMax;
00611 }
00612 else if (dAccCmd < -m_dDDPhiMax)
00613 {
00614 dAccCmd = -m_dDDPhiMax;
00615 }
00616 dVelCmdInt = m_vdCtrlVal[i][1] + m_UnderCarriagePrms.dCmdRateS * dAccCmd;
00617 if (dVelCmdInt > m_dDPhiMax)
00618 {
00619 dVelCmdInt = m_dDPhiMax;
00620 }
00621 else if (dVelCmdInt < -m_dDPhiMax)
00622 {
00623 dVelCmdInt = -m_dDPhiMax;
00624 }
00625
00626 m_vdCtrlVal[i][0] = dDeltaPhi;
00627 m_vdCtrlVal[i][1] = dVelCmdInt;
00628
00629 m_vdVelGearSteerCmdRadS[i] = dVelCmdInt;
00630
00631
00632 if(fabs(m_vdVelGearSteerCmdRadS[i]) > m_UnderCarriagePrms.dMaxSteerRateRadpS)
00633 {
00634 if (m_vdVelGearSteerCmdRadS[i] > 0)
00635 m_vdVelGearSteerCmdRadS[i] = m_UnderCarriagePrms.dMaxSteerRateRadpS;
00636 else
00637 m_vdVelGearSteerCmdRadS[i] = -m_UnderCarriagePrms.dMaxSteerRateRadpS;
00638 }
00639 }
00640
00641
00642 for (int i = 0; i<4; i++)
00643 {
00644 m_vdVelGearDriveCmdRadS[i] += m_vdVelGearSteerCmdRadS[i] * m_UnderCarriagePrms.vdFactorVel[i];
00645 }
00646
00647 }
00648
00649
00650 void UndercarriageCtrlGeom::operator=(const UndercarriageCtrlGeom & GeomCtrl)
00651 {
00652
00653 m_dVelLongMMS = GeomCtrl.m_dVelLongMMS;
00654 m_dVelLatMMS = GeomCtrl.m_dVelLatMMS;
00655 m_dRotRobRadS = GeomCtrl.m_dRotRobRadS;
00656 m_dRotVelRadS = GeomCtrl.m_dRotVelRadS;
00657
00658
00659 m_vdVelGearDriveRadS = GeomCtrl.m_vdVelGearDriveRadS;
00660 m_vdVelGearSteerRadS = GeomCtrl.m_vdVelGearSteerRadS;
00661 m_vdDltAngGearDriveRad = GeomCtrl.m_vdDltAngGearDriveRad;
00662 m_vdAngGearSteerRad = GeomCtrl.m_vdAngGearSteerRad;
00663
00664
00665 m_dCmdVelLongMMS = GeomCtrl.m_dCmdVelLongMMS;
00666 m_dCmdVelLatMMS = GeomCtrl.m_dCmdVelLatMMS;
00667 m_dCmdRotRobRadS = GeomCtrl.m_dCmdRotRobRadS;
00668 m_dCmdRotVelRadS = GeomCtrl.m_dCmdRotVelRadS;
00669
00670
00671 m_vdVelGearDriveCmdRadS = GeomCtrl.m_vdVelGearDriveCmdRadS;
00672 m_vdVelGearSteerCmdRadS = GeomCtrl.m_vdVelGearSteerCmdRadS;
00673 m_vdAngGearSteerCmdRad = GeomCtrl.m_vdAngGearSteerCmdRad;
00674
00675
00676
00677 m_vdAngGearSteerTarget1Rad = GeomCtrl.m_vdAngGearSteerTarget1Rad;
00678 m_vdVelGearDriveTarget1RadS = GeomCtrl.m_vdVelGearDriveTarget1RadS;
00679
00680 m_vdAngGearSteerTarget2Rad = GeomCtrl.m_vdAngGearSteerTarget2Rad;
00681 m_vdVelGearDriveTarget2RadS = GeomCtrl.m_vdVelGearDriveTarget2RadS;
00682
00683
00684 m_vdWheelXPosMM = GeomCtrl.m_vdWheelXPosMM;
00685 m_vdWheelYPosMM = GeomCtrl.m_vdWheelYPosMM;
00686 m_vdWheelDistMM = GeomCtrl.m_vdWheelDistMM;
00687 m_vdWheelAngRad = GeomCtrl.m_vdWheelAngRad;
00688
00689
00690 m_vdExWheelXPosMM = GeomCtrl.m_vdExWheelXPosMM;
00691 m_vdExWheelYPosMM = GeomCtrl.m_vdExWheelYPosMM;
00692 m_vdExWheelDistMM = GeomCtrl.m_vdExWheelDistMM;
00693 m_vdExWheelAngRad = GeomCtrl.m_vdExWheelAngRad;
00694
00695
00696 m_UnderCarriagePrms = GeomCtrl.m_UnderCarriagePrms;
00697
00698
00699
00700 m_dSpring = GeomCtrl.m_dSpring;
00701 m_dDamp = GeomCtrl.m_dDamp;
00702 m_dVirtM = GeomCtrl.m_dDPhiMax;
00703 m_dDPhiMax = GeomCtrl.m_dDPhiMax;
00704 m_dDDPhiMax = GeomCtrl.m_dDDPhiMax;
00705
00706 m_vdCtrlVal = GeomCtrl.m_vdCtrlVal;
00707 }
00708
00709
00710 void UndercarriageCtrlGeom::setEMStopActive(bool bEMStopActive)
00711 {
00712 m_bEMStopActive = bEMStopActive;
00713
00714
00715 if(m_bEMStopActive)
00716 {
00717
00718 for(int i=0; i<4; i++)
00719 {
00720 for(int j=0; j< 2; j++)
00721 {
00722 m_vdCtrlVal[i][j] = 0.0;
00723 }
00724 }
00725
00726 for(int i=0; i<4; i++)
00727 {
00728 m_vdVelGearDriveCmdRadS[i] = 0.0;
00729 m_vdVelGearSteerCmdRadS[i] = 0.0;
00730 }
00731 }
00732
00733 }