UndercarriageCtrlGeom.h
Go to the documentation of this file.
00001 /*
00002  * Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
00003  *
00004  * Licensed under the Apache License, Version 2.0 (the "License");
00005  * you may not use this file except in compliance with the License.
00006  * You may obtain a copy of the License at
00007  *
00008  *   http://www.apache.org/licenses/LICENSE-2.0
00009 
00010  * Unless required by applicable law or agreed to in writing, software
00011  * distributed under the License is distributed on an "AS IS" BASIS,
00012  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00013  * See the License for the specific language governing permissions and
00014  * limitations under the License.
00015  */
00016 
00017 
00018 #ifndef UndercarriageCtrlGeom_INCLUDEDEF_H
00019 #define UndercarriageCtrlGeom_INCLUDEDEF_H
00020 
00021 //#include <time.h>
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         /*// Logging for debugging
00038         // create Filepointers
00039         FILE * m_pfileDesVel, * m_pfileMeasVel;
00040         FILE * m_pfileSteerAngTarget1, * m_pfileSteerAngTarget2;
00041         FILE * m_pfileSteerAngTarget, * m_pfileDriveVelTarget;
00042         FILE * m_pfileSteerAngCmd, * m_pfileSteerVelCmd, * m_pfileDriveVelCmd;
00043         // create TimeStamp
00044         TimeStamp m_RawTime, m_StartTime;
00045         double m_dNowTime;*/
00046 
00047 
00048         // Actual Values for PltfMovement (calculated from Actual Wheelspeeds)
00049         double m_dVelLongMMS;
00050         double m_dVelLatMMS;
00051         double m_dRotRobRadS;
00052         double m_dRotVelRadS;
00053 
00054         // Actual Wheelspeed (read from Motor-Ctrls)
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         // Desired Pltf-Movement (set from PltfHwItf)
00061         double m_dCmdVelLongMMS;
00062         double m_dCmdVelLatMMS;
00063         double m_dCmdRotRobRadS;
00064         double m_dCmdRotVelRadS;
00065 
00066         /*// Interpolated Wheelspeeds (calculated from desired and current Pltf-Config)
00067         std::vector<double> m_vdVelGearDriveIntpRadS;
00068         std::vector<double> m_vdVelGearSteerIntpRadS;
00069         std::vector<double> m_vdAngGearSteerIntpRad;
00070 
00071         // Delta values for interpolating between two commands
00072         std::vector<double> m_vdDeltaAngIntpRad;
00073         std::vector<double> m_vdDeltaDriveIntpRadS;*/
00074 
00075         // Desired Wheelspeeds set to ELMO-Ctrl's (calculated from desired Pltf-Movement)
00076         std::vector<double> m_vdVelGearDriveCmdRadS;
00077         std::vector<double> m_vdVelGearSteerCmdRadS;
00078         std::vector<double> m_vdAngGearSteerCmdRad;
00079 
00080         // Target Wheelspeed and -angle (calculated from desired Pltf-Movement with Inverse without controle!)
00081         // This Values might not be valid (to high step response in steering rate, ...) for commanding the drives
00082         std::vector<double> m_vdAngGearSteerTarget1Rad; // alternativ 1 for steering angle
00083         std::vector<double> m_vdVelGearDriveTarget1RadS;
00084         std::vector<double> m_vdAngGearSteerTarget2Rad; // alternativ 2 for steering angle (+/- PI)
00085         std::vector<double> m_vdVelGearDriveTarget2RadS;
00086         std::vector<double> m_vdAngGearSteerTargetRad; // choosen alternativ for steering angle
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         // Factor for thread cycle time of ThreadMotionPltfCtrl and ThreadUnderCarriageCtrl
00150         //double m_dThreadCycleMultiplier;
00151 
00152         // calculate inverse kinematics
00153         void CalcInverse(void);
00154 
00155         // calculate direct kinematics
00156         void CalcDirect(void);
00157 
00158         // calculate Exact Wheel Position in robot coordinates
00159         void CalcExWheelPos(void);
00160 
00161         // perform one discrete Controle Step
00162         void CalcControlStep(void);
00163 
00164 public:
00165 
00166         // Constructor
00167         UndercarriageCtrlGeom(std::string sIniDirectory);
00168 
00169         // Destructor
00170         ~UndercarriageCtrlGeom(void);
00171 
00172         // Initialize Parameters for Controller and Kinematics
00173         void InitUndercarriageCtrl(void);
00174 
00175         // Set desired value for Plattform Velocity to UndercarriageCtrl (Sollwertvorgabe)
00176         void SetDesiredPltfVelocity(double dCmdVelLongMMS, double dCmdVelLatMMS, double dCmdRotRobRadS, double dCmdRotVelRadS);
00177 
00178         // Set actual values of wheels (steer/drive velocity/position) (Istwerte)
00179         void SetActualWheelValues(std::vector<double> vdVelGearDriveRadS, std::vector<double> vdVelGearSteerRadS, std::vector<double> vdDltAngGearDriveRad, std::vector<double> vdAngGearSteerRad);
00180 
00181         // Get result of inverse kinematics (without controller)
00182         void GetSteerDriveSetValues(std::vector<double> & vdVelGearDriveRadS, std::vector<double> & vdAngGearSteerRad);
00183 
00184         // Get set point values for the Wheels (including controller) from UndercarriangeCtrl
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         // Get result of direct kinematics
00189         void GetActualPltfVelocity(double & dDeltaLongMM, double & dDeltaLatMM, double & dDeltaRotRobRad, double & dDeltaRotVelRad,
00190                                         double & dVelLongMMS, double & dVelLatMMS, double & dRotRobRadS, double & dRotVelRadS);
00191 
00192         // Set EM flag and stop Ctrlr
00193         void setEMStopActive(bool bEMStopActive);
00194 
00195         // operator overloading
00196         void operator=(const UndercarriageCtrlGeom & GeomCtrl);
00197 };
00198 #endif
00199 


cob_undercarriage_ctrl
Author(s): Christian Connette
autogenerated on Sat Jun 8 2019 21:02:32