JSBSim Flight Dynamics Model 1.2.2 (22 Mar 2025)
An Open Source Flight Dynamics and Control Software Library in C++
Loading...
Searching...
No Matches
FGTrimAxis Class Reference

Detailed Description

Definition at line 86 of file FGTrimAxis.h.

+ Inheritance diagram for FGTrimAxis:
+ Collaboration diagram for FGTrimAxis:

Public Member Functions

 FGTrimAxis (FGFDMExec *fdmex, FGInitialCondition *IC, State state, Control control)
 Constructor for Trim Axis class.
 
 ~FGTrimAxis ()
 Destructor.
 
void AxisReport (void)
 
double GetAvgStability (void)
 
double GetControl (void)
 
double GetControlMax (void)
 
double GetControlMin (void)
 
std::string GetControlName (void)
 
Control GetControlType (void)
 
int GetIterationLimit (void)
 
int GetRunCount (void)
 
double GetSolverEps (void)
 
int GetStability (void)
 
double GetState (void)
 
std::string GetStateName (void)
 
double GetStateTarget (void)
 
State GetStateType (void)
 
double GetTolerance (void)
 
bool InTolerance (void)
 
void Run (void)
 This function iterates through a call to the FGFDMExec::RunIC() function until the desired trimming condition falls inside a tolerance.
 
void SetControl (double value)
 
void SetControlLimits (double min, double max)
 
void SetControlToMax (void)
 
void SetControlToMin (void)
 
void SetIterationLimit (int ii)
 
void SetSolverEps (double ff)
 
void SetStateTarget (double target)
 
void SetTolerance (double ff)
 
- Public Member Functions inherited from FGJSBBase
 FGJSBBase ()
 Constructor for FGJSBBase.
 
virtual ~FGJSBBase ()
 Destructor for FGJSBBase.
 
void disableHighLighting (void)
 Disables highlighting in the console output.
 

Additional Inherited Members

- Public Types inherited from FGJSBBase
enum  { eL = 1 , eM , eN }
 Moments L, M, N. More...
 
enum  { eP = 1 , eQ , eR }
 Rates P, Q, R. More...
 
enum  { eU = 1 , eV , eW }
 Velocities U, V, W. More...
 
enum  { eX = 1 , eY , eZ }
 Positions X, Y, Z. More...
 
enum  { ePhi = 1 , eTht , ePsi }
 Euler angles Phi, Theta, Psi. More...
 
enum  { eDrag = 1 , eSide , eLift }
 Stability axis forces, Drag, Side force, Lift. More...
 
enum  { eRoll = 1 , ePitch , eYaw }
 Local frame orientation Roll, Pitch, Yaw. More...
 
enum  { eNorth = 1 , eEast , eDown }
 Local frame position North, East, Down. More...
 
enum  { eLat = 1 , eLong , eRad }
 Locations Radius, Latitude, Longitude. More...
 
enum  {
  inNone = 0 , inDegrees , inRadians , inMeters ,
  inFeet
}
 Conversion specifiers. More...
 
- Static Public Member Functions inherited from FGJSBBase
static const std::string & GetVersion (void)
 Returns the version number of JSBSim.
 
static constexpr double KelvinToFahrenheit (double kelvin)
 Converts from degrees Kelvin to degrees Fahrenheit.
 
static constexpr double CelsiusToRankine (double celsius)
 Converts from degrees Celsius to degrees Rankine.
 
static constexpr double RankineToCelsius (double rankine)
 Converts from degrees Rankine to degrees Celsius.
 
static constexpr double KelvinToRankine (double kelvin)
 Converts from degrees Kelvin to degrees Rankine.
 
static constexpr double RankineToKelvin (double rankine)
 Converts from degrees Rankine to degrees Kelvin.
 
static constexpr double FahrenheitToCelsius (double fahrenheit)
 Converts from degrees Fahrenheit to degrees Celsius.
 
static constexpr double CelsiusToFahrenheit (double celsius)
 Converts from degrees Celsius to degrees Fahrenheit.
 
static constexpr double CelsiusToKelvin (double celsius)
 Converts from degrees Celsius to degrees Kelvin.
 
static constexpr double KelvinToCelsius (double kelvin)
 Converts from degrees Kelvin to degrees Celsius.
 
static constexpr double FeetToMeters (double measure)
 Converts from feet to meters.
 
static bool EqualToRoundoff (double a, double b)
 Finite precision comparison.
 
static bool EqualToRoundoff (float a, float b)
 Finite precision comparison.
 
static bool EqualToRoundoff (float a, double b)
 Finite precision comparison.
 
static bool EqualToRoundoff (double a, float b)
 Finite precision comparison.
 
static constexpr double Constrain (double min, double value, double max)
 Constrain a value between a minimum and a maximum value.
 
static constexpr double sign (double num)
 
- Static Public Attributes inherited from FGJSBBase
static char highint [5] = {27, '[', '1', 'm', '\0' }
 highlights text
 
static char halfint [5] = {27, '[', '2', 'm', '\0' }
 low intensity text
 
static char normint [6] = {27, '[', '2', '2', 'm', '\0' }
 normal intensity text
 
static char reset [5] = {27, '[', '0', 'm', '\0' }
 resets text properties
 
static char underon [5] = {27, '[', '4', 'm', '\0' }
 underlines text
 
static char underoff [6] = {27, '[', '2', '4', 'm', '\0' }
 underline off
 
static char fgblue [6] = {27, '[', '3', '4', 'm', '\0' }
 blue text
 
static char fgcyan [6] = {27, '[', '3', '6', 'm', '\0' }
 cyan text
 
static char fgred [6] = {27, '[', '3', '1', 'm', '\0' }
 red text
 
static char fggreen [6] = {27, '[', '3', '2', 'm', '\0' }
 green text
 
static char fgdef [6] = {27, '[', '3', '9', 'm', '\0' }
 default text
 
static short debug_lvl = 1
 
- Static Protected Member Functions inherited from FGJSBBase
static std::string CreateIndexedPropertyName (const std::string &Property, int index)
 
- Static Protected Attributes inherited from FGJSBBase
static constexpr double radtodeg = 180. / M_PI
 
static constexpr double degtorad = M_PI / 180.
 
static constexpr double hptoftlbssec = 550.0
 
static constexpr double psftoinhg = 0.014138
 
static constexpr double psftopa = 47.88
 
static constexpr double fttom = 0.3048
 
static constexpr double ktstofps = 1852./(3600*fttom)
 
static constexpr double fpstokts = 1.0 / ktstofps
 
static constexpr double inchtoft = 1.0/12.0
 
static constexpr double m3toft3 = 1.0/(fttom*fttom*fttom)
 
static constexpr double in3tom3 = inchtoft*inchtoft*inchtoft/m3toft3
 
static constexpr double inhgtopa = 3386.38
 
static constexpr double slugtolb = 32.174049
 Note that definition of lbtoslug by the inverse of slugtolb and not to a different constant you can also get from some tables will make lbtoslug*slugtolb == 1 up to the magnitude of roundoff.
 
static constexpr double lbtoslug = 1.0/slugtolb
 
static constexpr double kgtolb = 2.20462
 
static constexpr double kgtoslug = 0.06852168
 
static const std::string needed_cfg_version = "2.0"
 
static const std::string JSBSim_version = JSBSIM_VERSION " " __DATE__ " " __TIME__
 

Constructor & Destructor Documentation

◆ FGTrimAxis()

FGTrimAxis ( FGFDMExec fdmex,
FGInitialCondition IC,
State  state,
Control  control 
)

Constructor for Trim Axis class.

Parameters
fdmexFGFDMExec pointer
ICpointer to initial conditions instance
statea State type (enum)
controla Control type (enum)

Definition at line 61 of file FGTrimAxis.cpp.

62 {
63
64 fdmex=fdex;
65 fgic=ic;
66 state=st;
67 control=ctrl;
68 max_iterations=10;
69 control_value=0;
70 its_to_stable_value=0;
71 total_iterations=0;
72 total_stability_iterations=0;
73 state_convert=1.0;
74 control_convert=1.0;
75 state_value=0;
76 state_target=0;
77 switch(state) {
78 case tUdot: tolerance = DEFAULT_TOLERANCE; break;
79 case tVdot: tolerance = DEFAULT_TOLERANCE; break;
80 case tWdot: tolerance = DEFAULT_TOLERANCE; break;
81 case tQdot: tolerance = DEFAULT_TOLERANCE / 10; break;
82 case tPdot: tolerance = DEFAULT_TOLERANCE / 10; break;
83 case tRdot: tolerance = DEFAULT_TOLERANCE / 10; break;
84 case tHmgt: tolerance = 0.01; break;
85 case tNlf: state_target=1.0; tolerance = 1E-5; break;
86 case tAll: break;
87 }
88
89 solver_eps=tolerance;
90 switch(control) {
91 case tThrottle:
92 control_min=0;
93 control_max=1;
94 control_value=0.5;
95 break;
96 case tBeta:
97 control_min=-30*degtorad;
98 control_max=30*degtorad;
99 control_convert=radtodeg;
100 break;
101 case tAlpha:
102 control_min=fdmex->GetAerodynamics()->GetAlphaCLMin();
103 control_max=fdmex->GetAerodynamics()->GetAlphaCLMax();
104 if(control_max <= control_min) {
105 control_max=20*degtorad;
106 control_min=-5*degtorad;
107 }
108 control_value= (control_min+control_max)/2;
109 control_convert=radtodeg;
110 solver_eps=tolerance/100;
111 break;
112 case tPitchTrim:
113 case tElevator:
114 case tRollTrim:
115 case tAileron:
116 case tYawTrim:
117 case tRudder:
118 control_min=-1;
119 control_max=1;
120 state_convert=radtodeg;
121 solver_eps=tolerance/100;
122 break;
123 case tAltAGL:
124 control_min=0;
125 control_max=30;
126 control_value=ic->GetAltitudeAGLFtIC();
127 solver_eps=tolerance/100;
128 break;
129 case tTheta:
130 control_min=ic->GetThetaRadIC() - 5*degtorad;
131 control_max=ic->GetThetaRadIC() + 5*degtorad;
132 state_convert=radtodeg;
133 break;
134 case tPhi:
135 control_min=ic->GetPhiRadIC() - 30*degtorad;
136 control_max=ic->GetPhiRadIC() + 30*degtorad;
137 state_convert=radtodeg;
138 control_convert=radtodeg;
139 break;
140 case tGamma:
141 solver_eps=tolerance/100;
142 control_min=-80*degtorad;
143 control_max=80*degtorad;
144 control_convert=radtodeg;
145 break;
146 case tHeading:
147 control_min=ic->GetPsiRadIC() - 30*degtorad;
148 control_max=ic->GetPsiRadIC() + 30*degtorad;
149 state_convert=radtodeg;
150 break;
151 }
152
153
154 Debug(0);
155}
std::shared_ptr< FGAerodynamics > GetAerodynamics(void) const
Returns the FGAerodynamics pointer.
+ Here is the call graph for this function:

◆ ~FGTrimAxis()

~FGTrimAxis ( void  )

Destructor.

Definition at line 159 of file FGTrimAxis.cpp.

160{
161 Debug(1);
162}

Member Function Documentation

◆ AxisReport()

void AxisReport ( void  )

Definition at line 291 of file FGTrimAxis.cpp.

291 {
292 // Save original cout format characteristics
293 std::ios_base::fmtflags originalFormat = cout.flags();
294 std::streamsize originalPrecision = cout.precision();
295 std::streamsize originalWidth = cout.width();
296 cout << " " << setw(20) << GetControlName() << ": ";
297 cout << setw(6) << setprecision(2) << GetControl()*control_convert << ' ';
298 cout << setw(5) << GetStateName() << ": ";
299 cout << setw(9) << setprecision(2) << scientific << GetState()+state_target;
300 cout << " Tolerance: " << setw(3) << setprecision(0) << scientific << GetTolerance();
301
302 if( fabs(GetState()+state_target) < fabs(GetTolerance()) )
303 cout << " Passed" << endl;
304 else
305 cout << " Failed" << endl;
306 // Restore original cout format characteristics
307 cout.flags(originalFormat);
308 cout.precision(originalPrecision);
309 cout.width(originalWidth);
310}

◆ GetAvgStability()

double GetAvgStability ( void  )

Definition at line 314 of file FGTrimAxis.cpp.

314 {
315 if(total_iterations > 0) {
316 return double(total_stability_iterations)/double(total_iterations);
317 }
318 return 0;
319}

◆ GetControl()

double GetControl ( void  )
inline

Definition at line 108 of file FGTrimAxis.h.

108{ return control_value; }

◆ GetControlMax()

double GetControlMax ( void  )
inline

Definition at line 117 of file FGTrimAxis.h.

117{ return control_max; }

◆ GetControlMin()

double GetControlMin ( void  )
inline

Definition at line 116 of file FGTrimAxis.h.

116{ return control_min; }

◆ GetControlName()

std::string GetControlName ( void  )
inline

Definition at line 114 of file FGTrimAxis.h.

114{ return ControlNames[control]; }

◆ GetControlType()

Control GetControlType ( void  )
inline

Definition at line 111 of file FGTrimAxis.h.

111{ return control; }

◆ GetIterationLimit()

int GetIterationLimit ( void  )
inline

Definition at line 133 of file FGTrimAxis.h.

133{ return max_iterations; }

◆ GetRunCount()

int GetRunCount ( void  )
inline

Definition at line 137 of file FGTrimAxis.h.

137{ return total_stability_iterations; }

◆ GetSolverEps()

double GetSolverEps ( void  )
inline

Definition at line 130 of file FGTrimAxis.h.

130{ return solver_eps; }

◆ GetStability()

int GetStability ( void  )
inline

Definition at line 136 of file FGTrimAxis.h.

136{ return its_to_stable_value; }

◆ GetState()

double GetState ( void  )
inline

Definition at line 105 of file FGTrimAxis.h.

105{ getState(); return state_value; }

◆ GetStateName()

std::string GetStateName ( void  )
inline

Definition at line 113 of file FGTrimAxis.h.

113{ return StateNames[state]; }

◆ GetStateTarget()

double GetStateTarget ( void  )
inline

Definition at line 141 of file FGTrimAxis.h.

141{ return state_target; }

◆ GetStateType()

State GetStateType ( void  )
inline

Definition at line 110 of file FGTrimAxis.h.

110{ return state; }

◆ GetTolerance()

double GetTolerance ( void  )
inline

Definition at line 128 of file FGTrimAxis.h.

128{ return tolerance; }

◆ InTolerance()

bool InTolerance ( void  )
inline

Definition at line 145 of file FGTrimAxis.h.

145{ getState(); return (fabs(state_value) <= tolerance); }

◆ Run()

void Run ( void  )

This function iterates through a call to the FGFDMExec::RunIC() function until the desired trimming condition falls inside a tolerance.

Definition at line 245 of file FGTrimAxis.cpp.

245 {
246
247 double last_state_value;
248 int i;
249 setControl();
250 //cout << "FGTrimAxis::Run: " << control_value << endl;
251 i=0;
252 bool stable=false;
253 while(!stable) {
254 i++;
255 last_state_value=state_value;
256 fdmex->Initialize(fgic);
257 fdmex->Run();
258 getState();
259 if(i > 1) {
260 if((fabs(last_state_value - state_value) < tolerance) || (i >= 100) )
261 stable=true;
262 }
263 }
264
265 its_to_stable_value=i;
266 total_stability_iterations+=its_to_stable_value;
267 total_iterations++;
268}
bool Run(void)
This function executes each scheduled model in succession.
void Initialize(const FGInitialCondition *FGIC)
Initializes the simulation with initial conditions.
+ Here is the call graph for this function:

◆ SetControl()

void SetControl ( double  value)
inline

Definition at line 107 of file FGTrimAxis.h.

107{ control_value=value; }

◆ SetControlLimits()

void SetControlLimits ( double  min,
double  max 
)
inline

Definition at line 122 of file FGTrimAxis.h.

122 {
123 control_min=min;
124 control_max=max;
125 }

◆ SetControlToMax()

void SetControlToMax ( void  )
inline

Definition at line 120 of file FGTrimAxis.h.

120{ control_value=control_max; }

◆ SetControlToMin()

void SetControlToMin ( void  )
inline

Definition at line 119 of file FGTrimAxis.h.

119{ control_value=control_min; }

◆ SetIterationLimit()

void SetIterationLimit ( int  ii)
inline

Definition at line 134 of file FGTrimAxis.h.

134{ max_iterations=ii; }

◆ SetSolverEps()

void SetSolverEps ( double  ff)
inline

Definition at line 131 of file FGTrimAxis.h.

131{ solver_eps=ff; }

◆ SetStateTarget()

void SetStateTarget ( double  target)
inline

Definition at line 140 of file FGTrimAxis.h.

140{ state_target=target; }

◆ SetTolerance()

void SetTolerance ( double  ff)
inline

Definition at line 127 of file FGTrimAxis.h.

127{ tolerance=ff;}

The documentation for this class was generated from the following files: