UndercarriageCtrlGeom.h
Go to the documentation of this file.
1 /*
2  * Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9 
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  */
16 
17 
18 #ifndef UndercarriageCtrlGeom_INCLUDEDEF_H
19 #define UndercarriageCtrlGeom_INCLUDEDEF_H
20 
21 //#include <time.h>
22 
23 #include <cob_utilities/IniFile.h>
24 #include <cob_utilities/MathSup.h>
26 
28 {
29 private:
30 
32 
34 
35  std::string m_sIniDirectory;
36 
37  /*// Logging for debugging
38  // create Filepointers
39  FILE * m_pfileDesVel, * m_pfileMeasVel;
40  FILE * m_pfileSteerAngTarget1, * m_pfileSteerAngTarget2;
41  FILE * m_pfileSteerAngTarget, * m_pfileDriveVelTarget;
42  FILE * m_pfileSteerAngCmd, * m_pfileSteerVelCmd, * m_pfileDriveVelCmd;
43  // create TimeStamp
44  TimeStamp m_RawTime, m_StartTime;
45  double m_dNowTime;*/
46 
47 
48  // Actual Values for PltfMovement (calculated from Actual Wheelspeeds)
49  double m_dVelLongMMS;
50  double m_dVelLatMMS;
51  double m_dRotRobRadS;
52  double m_dRotVelRadS;
53 
54  // Actual Wheelspeed (read from Motor-Ctrls)
55  std::vector<double> m_vdVelGearDriveRadS;
56  std::vector<double> m_vdVelGearSteerRadS;
57  std::vector<double> m_vdDltAngGearDriveRad;
58  std::vector<double> m_vdAngGearSteerRad;
59 
60  // Desired Pltf-Movement (set from PltfHwItf)
65 
66  /*// Interpolated Wheelspeeds (calculated from desired and current Pltf-Config)
67  std::vector<double> m_vdVelGearDriveIntpRadS;
68  std::vector<double> m_vdVelGearSteerIntpRadS;
69  std::vector<double> m_vdAngGearSteerIntpRad;
70 
71  // Delta values for interpolating between two commands
72  std::vector<double> m_vdDeltaAngIntpRad;
73  std::vector<double> m_vdDeltaDriveIntpRadS;*/
74 
75  // Desired Wheelspeeds set to ELMO-Ctrl's (calculated from desired Pltf-Movement)
76  std::vector<double> m_vdVelGearDriveCmdRadS;
77  std::vector<double> m_vdVelGearSteerCmdRadS;
78  std::vector<double> m_vdAngGearSteerCmdRad;
79 
80  // Target Wheelspeed and -angle (calculated from desired Pltf-Movement with Inverse without controle!)
81  // This Values might not be valid (to high step response in steering rate, ...) for commanding the drives
82  std::vector<double> m_vdAngGearSteerTarget1Rad; // alternativ 1 for steering angle
83  std::vector<double> m_vdVelGearDriveTarget1RadS;
84  std::vector<double> m_vdAngGearSteerTarget2Rad; // alternativ 2 for steering angle (+/- PI)
85  std::vector<double> m_vdVelGearDriveTarget2RadS;
86  std::vector<double> m_vdAngGearSteerTargetRad; // choosen alternativ for steering angle
87  std::vector<double> m_vdVelGearDriveTargetRadS;
88 
93  std::vector<double> m_vdWheelXPosMM;
94  std::vector<double> m_vdWheelYPosMM;
95  std::vector<double> m_vdWheelDistMM;
96  std::vector<double> m_vdWheelAngRad;
97 
102  std::vector<double> m_vdExWheelXPosMM;
103  std::vector<double> m_vdExWheelYPosMM;
104  std::vector<double> m_vdExWheelDistMM;
105  std::vector<double> m_vdExWheelAngRad;
106 
107  struct ParamType
108  {
111 
113 
116  double dCmdRateS;
117  std::vector<double> WheelNeutralPos;
118  std::vector<double> vdSteerDriveCoupling;
123  std::vector<double> vdFactorVel;
124  };
125 
127 
147  std::vector< std::vector<double> > m_vdCtrlVal;
148 
149  // Factor for thread cycle time of ThreadMotionPltfCtrl and ThreadUnderCarriageCtrl
150  //double m_dThreadCycleMultiplier;
151 
152  // calculate inverse kinematics
153  void CalcInverse(void);
154 
155  // calculate direct kinematics
156  void CalcDirect(void);
157 
158  // calculate Exact Wheel Position in robot coordinates
159  void CalcExWheelPos(void);
160 
161  // perform one discrete Controle Step
162  void CalcControlStep(void);
163 
164 public:
165 
166  // Constructor
167  UndercarriageCtrlGeom(std::string sIniDirectory);
168 
169  // Destructor
171 
172  // Initialize Parameters for Controller and Kinematics
173  void InitUndercarriageCtrl(void);
174 
175  // Set desired value for Plattform Velocity to UndercarriageCtrl (Sollwertvorgabe)
176  void SetDesiredPltfVelocity(double dCmdVelLongMMS, double dCmdVelLatMMS, double dCmdRotRobRadS, double dCmdRotVelRadS);
177 
178  // Set actual values of wheels (steer/drive velocity/position) (Istwerte)
179  void SetActualWheelValues(std::vector<double> vdVelGearDriveRadS, std::vector<double> vdVelGearSteerRadS, std::vector<double> vdDltAngGearDriveRad, std::vector<double> vdAngGearSteerRad);
180 
181  // Get result of inverse kinematics (without controller)
182  void GetSteerDriveSetValues(std::vector<double> & vdVelGearDriveRadS, std::vector<double> & vdAngGearSteerRad);
183 
184  // Get set point values for the Wheels (including controller) from UndercarriangeCtrl
185  void GetNewCtrlStateSteerDriveSetValues(std::vector<double> & vdVelGearDriveRadS, std::vector<double> & vdVelGearSteerRadS, std::vector<double> & vdAngGearSteerRad,
186  double & dVelLongMMS, double & dVelLatMMS, double & dRotRobRadS, double & dRotVelRadS);
187 
188  // Get result of direct kinematics
189  void GetActualPltfVelocity(double & dDeltaLongMM, double & dDeltaLatMM, double & dDeltaRotRobRad, double & dDeltaRotVelRad,
190  double & dVelLongMMS, double & dVelLatMMS, double & dRotRobRadS, double & dRotVelRadS);
191 
192  // Set EM flag and stop Ctrlr
193  void setEMStopActive(bool bEMStopActive);
194 
195  // operator overloading
196  void operator=(const UndercarriageCtrlGeom & GeomCtrl);
197 };
198 #endif
199 
UndercarriageCtrlGeom::m_sIniDirectory
std::string m_sIniDirectory
Definition: UndercarriageCtrlGeom.h:35
UndercarriageCtrlGeom::m_dVirtM
double m_dVirtM
Definition: UndercarriageCtrlGeom.h:138
UndercarriageCtrlGeom::m_dVelLongMMS
double m_dVelLongMMS
Definition: UndercarriageCtrlGeom.h:49
UndercarriageCtrlGeom::SetActualWheelValues
void SetActualWheelValues(std::vector< double > vdVelGearDriveRadS, std::vector< double > vdVelGearSteerRadS, std::vector< double > vdDltAngGearDriveRad, std::vector< double > vdAngGearSteerRad)
Definition: UndercarriageCtrlGeom.cpp:300
UndercarriageCtrlGeom::m_vdAngGearSteerTargetRad
std::vector< double > m_vdAngGearSteerTargetRad
Definition: UndercarriageCtrlGeom.h:86
UndercarriageCtrlGeom::m_dRotVelRadS
double m_dRotVelRadS
Definition: UndercarriageCtrlGeom.h:52
UndercarriageCtrlGeom::setEMStopActive
void setEMStopActive(bool bEMStopActive)
Definition: UndercarriageCtrlGeom.cpp:674
UndercarriageCtrlGeom::m_dVelLatMMS
double m_dVelLatMMS
Definition: UndercarriageCtrlGeom.h:50
UndercarriageCtrlGeom::m_vdAngGearSteerRad
std::vector< double > m_vdAngGearSteerRad
Definition: UndercarriageCtrlGeom.h:58
UndercarriageCtrlGeom::m_vdWheelDistMM
std::vector< double > m_vdWheelDistMM
Definition: UndercarriageCtrlGeom.h:95
UndercarriageCtrlGeom::m_vdExWheelXPosMM
std::vector< double > m_vdExWheelXPosMM
Definition: UndercarriageCtrlGeom.h:102
IniFile.h
UndercarriageCtrlGeom::UndercarriageCtrlGeom
UndercarriageCtrlGeom(std::string sIniDirectory)
Definition: UndercarriageCtrlGeom.cpp:21
UndercarriageCtrlGeom::m_dCmdRotRobRadS
double m_dCmdRotRobRadS
Definition: UndercarriageCtrlGeom.h:63
UndercarriageCtrlGeom::ParamType::iRadiusWheelMM
int iRadiusWheelMM
Definition: UndercarriageCtrlGeom.h:110
UndercarriageCtrlGeom::m_vdVelGearDriveTarget2RadS
std::vector< double > m_vdVelGearDriveTarget2RadS
Definition: UndercarriageCtrlGeom.h:85
UndercarriageCtrlGeom::m_vdVelGearSteerRadS
std::vector< double > m_vdVelGearSteerRadS
Definition: UndercarriageCtrlGeom.h:56
UndercarriageCtrlGeom::operator=
void operator=(const UndercarriageCtrlGeom &GeomCtrl)
Definition: UndercarriageCtrlGeom.cpp:614
UndercarriageCtrlGeom::m_vdCtrlVal
std::vector< std::vector< double > > m_vdCtrlVal
Definition: UndercarriageCtrlGeom.h:147
UndercarriageCtrlGeom::ParamType::vdSteerDriveCoupling
std::vector< double > vdSteerDriveCoupling
Definition: UndercarriageCtrlGeom.h:118
UndercarriageCtrlGeom::m_dRotRobRadS
double m_dRotRobRadS
Definition: UndercarriageCtrlGeom.h:51
UndercarriageCtrlGeom::m_dDPhiMax
double m_dDPhiMax
Definition: UndercarriageCtrlGeom.h:138
UndercarriageCtrlGeom::m_vdExWheelDistMM
std::vector< double > m_vdExWheelDistMM
Definition: UndercarriageCtrlGeom.h:104
TimeStamp.h
UndercarriageCtrlGeom::m_UnderCarriagePrms
ParamType m_UnderCarriagePrms
Definition: UndercarriageCtrlGeom.h:126
UndercarriageCtrlGeom::m_vdVelGearDriveTarget1RadS
std::vector< double > m_vdVelGearDriveTarget1RadS
Definition: UndercarriageCtrlGeom.h:83
UndercarriageCtrlGeom::ParamType::dMaxDriveRateRadpS
double dMaxDriveRateRadpS
Definition: UndercarriageCtrlGeom.h:114
UndercarriageCtrlGeom::ParamType::vdFactorVel
std::vector< double > vdFactorVel
Definition: UndercarriageCtrlGeom.h:123
UndercarriageCtrlGeom::m_vdWheelXPosMM
std::vector< double > m_vdWheelXPosMM
Definition: UndercarriageCtrlGeom.h:93
UndercarriageCtrlGeom::GetNewCtrlStateSteerDriveSetValues
void GetNewCtrlStateSteerDriveSetValues(std::vector< double > &vdVelGearDriveRadS, std::vector< double > &vdVelGearSteerRadS, std::vector< double > &vdAngGearSteerRad, double &dVelLongMMS, double &dVelLatMMS, double &dRotRobRadS, double &dRotVelRadS)
Definition: UndercarriageCtrlGeom.cpp:328
UndercarriageCtrlGeom::m_vdWheelYPosMM
std::vector< double > m_vdWheelYPosMM
Definition: UndercarriageCtrlGeom.h:94
UndercarriageCtrlGeom::ParamType::iDistSteerAxisToDriveWheelMM
int iDistSteerAxisToDriveWheelMM
Definition: UndercarriageCtrlGeom.h:112
UndercarriageCtrlGeom::m_vdDltAngGearDriveRad
std::vector< double > m_vdDltAngGearDriveRad
Definition: UndercarriageCtrlGeom.h:57
UndercarriageCtrlGeom::m_vdAngGearSteerTarget1Rad
std::vector< double > m_vdAngGearSteerTarget1Rad
Definition: UndercarriageCtrlGeom.h:82
UndercarriageCtrlGeom::CalcExWheelPos
void CalcExWheelPos(void)
Definition: UndercarriageCtrlGeom.cpp:499
UndercarriageCtrlGeom::InitUndercarriageCtrl
void InitUndercarriageCtrl(void)
Definition: UndercarriageCtrlGeom.cpp:120
UndercarriageCtrlGeom::m_vdExWheelYPosMM
std::vector< double > m_vdExWheelYPosMM
Definition: UndercarriageCtrlGeom.h:103
UndercarriageCtrlGeom::m_bEMStopActive
bool m_bEMStopActive
Definition: UndercarriageCtrlGeom.h:31
UndercarriageCtrlGeom::CalcDirect
void CalcDirect(void)
Definition: UndercarriageCtrlGeom.cpp:421
UndercarriageCtrlGeom::m_vdVelGearDriveRadS
std::vector< double > m_vdVelGearDriveRadS
Definition: UndercarriageCtrlGeom.h:55
UndercarriageCtrlGeom::m_dCmdVelLongMMS
double m_dCmdVelLongMMS
Definition: UndercarriageCtrlGeom.h:61
MathSup.h
UndercarriageCtrlGeom::m_vdVelGearDriveTargetRadS
std::vector< double > m_vdVelGearDriveTargetRadS
Definition: UndercarriageCtrlGeom.h:87
UndercarriageCtrlGeom::GetSteerDriveSetValues
void GetSteerDriveSetValues(std::vector< double > &vdVelGearDriveRadS, std::vector< double > &vdAngGearSteerRad)
Definition: UndercarriageCtrlGeom.cpp:317
UndercarriageCtrlGeom::m_vdAngGearSteerCmdRad
std::vector< double > m_vdAngGearSteerCmdRad
Definition: UndercarriageCtrlGeom.h:78
UndercarriageCtrlGeom::m_dCmdRotVelRadS
double m_dCmdRotVelRadS
Definition: UndercarriageCtrlGeom.h:64
UndercarriageCtrlGeom::CalcInverse
void CalcInverse(void)
Definition: UndercarriageCtrlGeom.cpp:376
UndercarriageCtrlGeom::GetActualPltfVelocity
void GetActualPltfVelocity(double &dDeltaLongMM, double &dDeltaLatMM, double &dDeltaRotRobRad, double &dDeltaRotVelRad, double &dVelLongMMS, double &dVelLatMMS, double &dRotRobRadS, double &dRotVelRadS)
Definition: UndercarriageCtrlGeom.cpp:358
UndercarriageCtrlGeom::m_dCmdVelLatMMS
double m_dCmdVelLatMMS
Definition: UndercarriageCtrlGeom.h:62
UndercarriageCtrlGeom::m_dSpring
double m_dSpring
Definition: UndercarriageCtrlGeom.h:138
UndercarriageCtrlGeom
Definition: UndercarriageCtrlGeom.h:27
UndercarriageCtrlGeom::ParamType::dMaxSteerRateRadpS
double dMaxSteerRateRadpS
Definition: UndercarriageCtrlGeom.h:115
UndercarriageCtrlGeom::ParamType::WheelNeutralPos
std::vector< double > WheelNeutralPos
Definition: UndercarriageCtrlGeom.h:117
UndercarriageCtrlGeom::CalcControlStep
void CalcControlStep(void)
Definition: UndercarriageCtrlGeom.cpp:517
UndercarriageCtrlGeom::ParamType
Definition: UndercarriageCtrlGeom.h:107
UndercarriageCtrlGeom::m_iNumberOfDrives
int m_iNumberOfDrives
Definition: UndercarriageCtrlGeom.h:33
UndercarriageCtrlGeom::SetDesiredPltfVelocity
void SetDesiredPltfVelocity(double dCmdVelLongMMS, double dCmdVelLatMMS, double dCmdRotRobRadS, double dCmdRotVelRadS)
Definition: UndercarriageCtrlGeom.cpp:195
UndercarriageCtrlGeom::m_vdVelGearSteerCmdRadS
std::vector< double > m_vdVelGearSteerCmdRadS
Definition: UndercarriageCtrlGeom.h:77
UndercarriageCtrlGeom::m_vdWheelAngRad
std::vector< double > m_vdWheelAngRad
Definition: UndercarriageCtrlGeom.h:96
UndercarriageCtrlGeom::m_vdExWheelAngRad
std::vector< double > m_vdExWheelAngRad
Definition: UndercarriageCtrlGeom.h:105
UndercarriageCtrlGeom::m_vdVelGearDriveCmdRadS
std::vector< double > m_vdVelGearDriveCmdRadS
Definition: UndercarriageCtrlGeom.h:76
UndercarriageCtrlGeom::~UndercarriageCtrlGeom
~UndercarriageCtrlGeom(void)
Definition: UndercarriageCtrlGeom.cpp:103
UndercarriageCtrlGeom::m_dDDPhiMax
double m_dDDPhiMax
Definition: UndercarriageCtrlGeom.h:138
UndercarriageCtrlGeom::m_vdAngGearSteerTarget2Rad
std::vector< double > m_vdAngGearSteerTarget2Rad
Definition: UndercarriageCtrlGeom.h:84
UndercarriageCtrlGeom::m_dDamp
double m_dDamp
Definition: UndercarriageCtrlGeom.h:138
UndercarriageCtrlGeom::ParamType::dCmdRateS
double dCmdRateS
Definition: UndercarriageCtrlGeom.h:116
UndercarriageCtrlGeom::ParamType::iDistWheels
int iDistWheels
Definition: UndercarriageCtrlGeom.h:109


cob_undercarriage_ctrl
Author(s): Christian Connette
autogenerated on Wed Nov 8 2023 03:47:55