46#include "models/FGInertial.h"
47#include "models/FGAccelerations.h"
48#include "models/FGMassBalance.h"
49#include "models/FGFCS.h"
52#pragma warning (disable : 4786 4788)
67 max_sub_iterations=100;
69 A_Tolerance = Tolerance / 10;
73 fgic = *fdmex->
GetIC();
81 if (debug_lvl & 2) cout <<
"Instantiated: FGTrim" << endl;
86FGTrim::~FGTrim(
void) {
87 if (debug_lvl & 2) cout <<
"Destroyed: FGTrim" << endl;
94 cout << endl <<
" Trim Statistics: " << endl;
95 cout <<
" Total Iterations: " << total_its << endl;
97 cout <<
" Sub-iterations:" << endl;
98 for (
unsigned int current_axis=0; current_axis<TrimAxes.size(); current_axis++) {
99 run_sum += TrimAxes[current_axis].GetRunCount();
100 cout <<
" " << setw(5) << TrimAxes[current_axis].GetStateName().c_str()
101 <<
": " << setprecision(3) << sub_iterations[current_axis]
102 <<
" average: " << setprecision(5) << sub_iterations[current_axis]/double(total_its)
103 <<
" successful: " << setprecision(3) << successful[current_axis]
104 <<
" stability: " << setprecision(5) << TrimAxes[current_axis].GetAvgStability()
107 cout <<
" Run Count: " << run_sum << endl;
114 cout <<
" Trim Results: " << endl;
115 for(
unsigned int current_axis=0; current_axis<TrimAxes.size(); current_axis++)
116 TrimAxes[current_axis].AxisReport();
132 vector <FGTrimAxis>::iterator iAxes = TrimAxes.begin();
133 for (; iAxes != TrimAxes.end(); ++iAxes) {
134 if (iAxes->GetStateType() == state)
138 TrimAxes.push_back(
FGTrimAxis(fdmex,&fgic,state,control));
139 sub_iterations.resize(TrimAxes.size());
140 successful.resize(TrimAxes.size());
141 solution.resize(TrimAxes.size());
152 vector <FGTrimAxis>::iterator iAxes = TrimAxes.begin();
153 while (iAxes != TrimAxes.end()) {
154 if( iAxes->GetStateType() == state ) {
155 iAxes = TrimAxes.erase(iAxes);
162 sub_iterations.resize(TrimAxes.size());
163 successful.resize(TrimAxes.size());
164 solution.resize(TrimAxes.size());
173 vector <FGTrimAxis>::iterator iAxes = TrimAxes.begin();
174 while (iAxes != TrimAxes.end()) {
175 if( iAxes->GetStateType() == state ) {
176 *iAxes =
FGTrimAxis(fdmex,&fgic,state,new_control);
187 bool trim_failed=
false;
189 unsigned int axis_count = 0;
190 auto FCS = fdmex->
GetFCS();
192 vector<double> throttle0 = FCS->GetThrottleCmd();
193 double elevator0 = FCS->GetDeCmd();
194 double aileron0 = FCS->GetDaCmd();
195 double rudder0 = FCS->GetDrCmd();
196 double PitchTrim0 = FCS->GetPitchTrimCmd();
198 for(
int i=0;i < GroundReactions->GetNumGearUnits();i++)
199 GroundReactions->GetGearUnit(i)->SetReport(
false);
201 fdmex->SetTrimStatus(
true);
208 if (mode == tGround) {
217 TrimAxes[1].SetControlLimits(theta - 5.0 * degtorad, theta + 5.0 * degtorad);
218 TrimAxes[2].SetControlLimits(phi - 30.0 * degtorad, phi + 30.0 * degtorad);
222 for(
unsigned int current_axis=0;current_axis<TrimAxes.size();current_axis++) {
225 xlo=TrimAxes[current_axis].GetControlMin();
226 xhi=TrimAxes[current_axis].GetControlMax();
227 TrimAxes[current_axis].SetControl((xlo+xhi)/2);
228 TrimAxes[current_axis].Run();
230 sub_iterations[current_axis]=0;
231 successful[current_axis]=0;
232 solution[current_axis]=
false;
235 if(mode == tPullup ) {
236 cout <<
"Setting pitch rate and nlf... " << endl;
238 cout <<
"pitch rate done ... " << endl;
239 TrimAxes[0].SetStateTarget(targetNlf);
240 cout <<
"nlf done" << endl;
241 }
else if (mode == tTurn) {
248 for(
unsigned int current_axis=0;current_axis<TrimAxes.size();current_axis++) {
249 setDebug(TrimAxes[current_axis]);
252 if(!solution[current_axis]) {
253 if(checkLimits(TrimAxes[current_axis])) {
254 solution[current_axis]=
true;
255 solve(TrimAxes[current_axis]);
257 }
else if(findInterval(TrimAxes[current_axis])) {
258 solve(TrimAxes[current_axis]);
260 solution[current_axis]=
false;
262 sub_iterations[current_axis]+=Nsub;
264 for(
unsigned int current_axis=0;current_axis<TrimAxes.size();current_axis++) {
266 if(Debug > 0) TrimAxes[current_axis].AxisReport();
267 if(TrimAxes[current_axis].InTolerance()) {
269 successful[current_axis]++;
273 if((axis_count == TrimAxes.size()-1) && (TrimAxes.size() > 1)) {
280 for(
unsigned int current_axis=0;current_axis<TrimAxes.size();current_axis++) {
282 if(!TrimAxes[current_axis].InTolerance()) {
283 if(!checkLimits(TrimAxes[current_axis])) {
286 if( (gamma_fallback) &&
287 (TrimAxes[current_axis].GetStateType() == tUdot) &&
288 (TrimAxes[current_axis].GetControlType() == tThrottle)) {
289 cout <<
" Can't trim udot with throttle, trying flight"
290 <<
" path angle. (" << N <<
")" << endl;
291 if(TrimAxes[current_axis].GetState() > 0)
292 TrimAxes[current_axis].SetControlToMin();
294 TrimAxes[current_axis].SetControlToMax();
295 TrimAxes[current_axis].Run();
296 TrimAxes[current_axis]=
FGTrimAxis(fdmex,&fgic,tUdot,tGamma);
298 cout <<
" Sorry, " << TrimAxes[current_axis].GetStateName()
299 <<
" doesn't appear to be trimmable" << endl;
308 if(N > max_iterations)
310 }
while((axis_count < TrimAxes.size()) && (!trim_failed));
312 if((!trim_failed) && (axis_count >= TrimAxes.size())) {
315 cout << endl <<
" Trim successful" << endl;
320 fgic = *fdmex->
GetIC();
321 FCS->SetDeCmd(elevator0);
322 FCS->SetDaCmd(aileron0);
323 FCS->SetDrCmd(rudder0);
324 FCS->SetPitchTrimCmd(PitchTrim0);
325 for (
unsigned int i=0; i < throttle0.size(); i++)
326 FCS->SetThrottleCmd(i, throttle0[i]);
332 if (GroundReactions->GetWOW())
336 cout << endl <<
" Trim failed" << endl;
341 fdmex->SetTrimStatus(
false);
343 for(
int i=0;i < GroundReactions->GetNumGearUnits();i++)
344 GroundReactions->GetGearUnit(i)->SetReport(
true);
373void FGTrim::trimOnGround(
void)
379 vector<ContactPoints> contacts;
380 FGLocation CGLocation = Propagate->GetLocation();
388 for (
int i = 0; i < GroundReactions->GetNumGearUnits(); ++i) {
390 auto gear = GroundReactions->GetGearUnit(i);
393 if (!gear->GetGearUnitDown())
396 c.location = gear->GetBodyLocation();
401 double height = fdmex->
GetInertial()->GetContactPoint(gearLoc, lDummy,
405 if (gear->IsBogey() && !GroundReactions->GetSolid())
408 c.normal = Tec2b * normal;
409 contacts.push_back(c);
413 contactRef = contacts.size() - 1;
417 if (contacts.size() < 3)
424 FGColumnVector3 contact0 = contacts[contactRef].location;
425 contacts.erase(contacts.begin() + contactRef);
435 FGColumnVector3 force = MassBalance->GetMass() * Accelerations->GetUVWdot();
436 FGColumnVector3 moment = MassBalance->GetJ() * Accelerations->GetPQRdot()
438 FGColumnVector3 rotationAxis = moment.Normalize();
442 RotationParameters rParam = calcRotation(contacts, rotationAxis, contact0);
443 FGQuaternion q0(rParam.angleMin, rotationAxis);
446 FGMatrix33 rot = q0.GetTInv();
447 vector<ContactPoints>::iterator iter;
448 for (iter = contacts.begin(); iter != contacts.end(); ++iter)
449 iter->location = contact0 + rot * (iter->location - contact0);
454 FGColumnVector3 contact1 = rParam.contactRef->location;
455 contacts.erase(rParam.contactRef);
460 rotationAxis = contact1 - contact0;
462 if (DotProduct(rotationAxis, moment) < 0.0)
463 rotationAxis = contact0 - contact1;
465 rotationAxis.Normalize();
468 rParam = calcRotation(contacts, rotationAxis, contact0);
469 FGQuaternion q1(rParam.angleMin, rotationAxis);
472 FGColumnVector3 euler = (fgic.
GetOrientation() * q0 * q1).GetEuler();
488FGTrim::RotationParameters FGTrim::calcRotation(vector<ContactPoints>& contacts,
489 const FGColumnVector3& u,
490 const FGColumnVector3& GM0)
492 RotationParameters rParam;
493 vector<ContactPoints>::iterator iter;
495 rParam.angleMin = 3.0 * M_PI;
497 for (iter = contacts.begin(); iter != contacts.end(); ++iter) {
501 FGColumnVector3 t = u * iter->normal;
502 double length = t.Magnitude();
504 FGColumnVector3 v = t * u;
505 FGColumnVector3 MM0 = GM0 - iter->location;
507 double d0 = DotProduct(MM0, u);
510 double sqrRadius = DotProduct(MM0, MM0) - d0 * d0;
513 double DistPlane = d0 * DotProduct(u, iter->normal) / length;
516 double mag = sqrRadius - DistPlane * DistPlane;
518 cout <<
"FGTrim::calcRotation DistPlane^2 larger than sqrRadius" << endl;
520 double alpha = sqrt(max(mag, 0.0));
521 FGColumnVector3 CP = alpha * t + DistPlane * v;
525 double cosine = -DotProduct(MM0, CP) / sqrRadius;
526 double sine = DotProduct(MM0 * u, CP) / sqrRadius;
527 double angle = atan2(sine, cosine);
528 if (angle < 0.0) angle += 2.0 * M_PI;
529 if (angle < rParam.angleMin) {
530 rParam.angleMin = angle;
531 rParam.contactRef = iter;
540bool FGTrim::solve(FGTrimAxis& axis) {
542 double x1,x2,x3,f1,f2,f3,d,d0;
543 const double relax =0.9;
544 double eps=axis.GetSolverEps();
550 if( solutionDomain != 0) {
561 while ( (axis.InTolerance() ==
false )
562 && (fabs(d) > eps) && (Nsub < max_sub_iterations)) {
565 x2=x1-d*d0*f1/(f3-f1);
570 cout <<
"FGTrim::solve Nsub,x1,x2,x3: " << Nsub <<
", " << x1
571 <<
", " << x2 <<
", " << x3 << endl;
572 cout <<
" " << f1 <<
", " << f2 <<
", " << f3 << endl;
580 else if(f2*f3 <= 0.0) {
591 if(Nsub < max_sub_iterations) success=
true;
621bool FGTrim::findInterval(FGTrimAxis& axis) {
624 double current_control=axis.GetControl();
625 double current_accel=axis.GetState();;
626 double xmin=axis.GetControlMin();
627 double xmax=axis.GetControlMax();
628 double lastxlo,lastxhi,lastalo,lastahi;
630 step=0.025*fabs(xmax);
631 xlo=xhi=current_control;
632 alo=ahi=current_accel;
633 lastxlo=xlo;lastxhi=xhi;
634 lastalo=alo;lastahi=ahi;
640 if(xlo < xmin) xlo=xmin;
642 if(xhi > xmax) xhi=xmax;
643 axis.SetControl(xlo);
646 axis.SetControl(xhi);
649 if(fabs(ahi-alo) <= axis.GetTolerance())
continue;
652 if(alo*current_accel <= 0) {
666 lastxlo=xlo;lastxhi=xhi;
667 lastalo=alo;lastahi=ahi;
668 if( !found && xlo==xmin && xhi==xmax )
continue;
670 cout <<
"FGTrim::findInterval: Nsub=" << Nsub <<
" Lo= " << xlo
671 <<
" Hi= " << xhi <<
" alo*ahi: " << alo*ahi << endl;
672 }
while(!found && (Nsub <= max_sub_iterations) );
691bool FGTrim::checkLimits(FGTrimAxis& axis)
694 double current_control=axis.GetControl();
695 double current_accel=axis.GetState();
696 xlo=axis.GetControlMin();
697 xhi=axis.GetControlMax();
699 axis.SetControl(xlo);
702 axis.SetControl(xhi);
706 cout <<
"checkLimits() xlo,xhi,alo,ahi: " << xlo <<
", " << xhi <<
", "
707 << alo <<
", " << ahi << endl;
709 solutionExists=
false;
710 if(fabs(ahi-alo) > axis.GetTolerance()) {
711 if(alo*current_accel <= 0) {
716 }
else if(current_accel*ahi < 0){
723 axis.SetControl(current_control);
725 return solutionExists;
730void FGTrim::setupPullup() {
734 cout <<
"setPitchRateInPullup(): " << g <<
", " << cgamma <<
", "
737 cout << targetNlf <<
", " << q << endl;
739 cout <<
"setPitchRateInPullup() complete" << endl;
745void FGTrim::setupTurn(
void){
748 if( fabs(phi) > 0.001 && fabs(phi) < 1.56 ) {
749 targetNlf = 1 / cos(phi);
750 g = fdmex->
GetInertial()->GetGravity().Magnitude();
752 cout << targetNlf <<
", " << psidot << endl;
759void FGTrim::updateRates(
void){
760 if( mode == tTurn ) {
762 double g = fdmex->
GetInertial()->GetGravity().Magnitude();
764 if(fabs(phi) > 0.001 && fabs(phi) < 1.56 ) {
768 p=-psidot*sin(theta);
769 q=psidot*cos(theta)*sin(phi);
770 r=psidot*cos(theta)*cos(phi);
777 }
else if( mode == tPullup && fabs(targetNlf-1) > 0.01) {
788void FGTrim::setDebug(FGTrimAxis& axis) {
789 if(debug_axis == tAll ||
790 axis.GetStateType() == debug_axis ) {
807 cout <<
" Full Trim" << endl;
808 TrimAxes.push_back(
FGTrimAxis(fdmex,&fgic,tWdot,tAlpha));
809 TrimAxes.push_back(
FGTrimAxis(fdmex,&fgic,tUdot,tThrottle ));
810 TrimAxes.push_back(
FGTrimAxis(fdmex,&fgic,tQdot,tPitchTrim ));
812 TrimAxes.push_back(
FGTrimAxis(fdmex,&fgic,tVdot,tPhi ));
813 TrimAxes.push_back(
FGTrimAxis(fdmex,&fgic,tPdot,tAileron ));
814 TrimAxes.push_back(
FGTrimAxis(fdmex,&fgic,tRdot,tRudder ));
818 cout <<
" Longitudinal Trim" << endl;
819 TrimAxes.push_back(
FGTrimAxis(fdmex,&fgic,tWdot,tAlpha ));
820 TrimAxes.push_back(
FGTrimAxis(fdmex,&fgic,tUdot,tThrottle ));
821 TrimAxes.push_back(
FGTrimAxis(fdmex,&fgic,tQdot,tPitchTrim ));
825 cout <<
" Ground Trim" << endl;
826 TrimAxes.push_back(
FGTrimAxis(fdmex,&fgic,tWdot,tAltAGL ));
827 TrimAxes.push_back(
FGTrimAxis(fdmex,&fgic,tQdot,tTheta ));
828 TrimAxes.push_back(
FGTrimAxis(fdmex,&fgic,tPdot,tPhi ));
831 TrimAxes.push_back(
FGTrimAxis(fdmex,&fgic,tNlf,tAlpha ));
832 TrimAxes.push_back(
FGTrimAxis(fdmex,&fgic,tUdot,tThrottle ));
833 TrimAxes.push_back(
FGTrimAxis(fdmex,&fgic,tQdot,tPitchTrim ));
834 TrimAxes.push_back(
FGTrimAxis(fdmex,&fgic,tHmgt,tBeta ));
835 TrimAxes.push_back(
FGTrimAxis(fdmex,&fgic,tVdot,tPhi ));
836 TrimAxes.push_back(
FGTrimAxis(fdmex,&fgic,tPdot,tAileron ));
837 TrimAxes.push_back(
FGTrimAxis(fdmex,&fgic,tRdot,tRudder ));
840 TrimAxes.push_back(
FGTrimAxis(fdmex,&fgic,tWdot,tAlpha ));
841 TrimAxes.push_back(
FGTrimAxis(fdmex,&fgic,tUdot,tThrottle ));
842 TrimAxes.push_back(
FGTrimAxis(fdmex,&fgic,tQdot,tPitchTrim ));
843 TrimAxes.push_back(
FGTrimAxis(fdmex,&fgic,tVdot,tBeta ));
844 TrimAxes.push_back(
FGTrimAxis(fdmex,&fgic,tPdot,tAileron ));
845 TrimAxes.push_back(
FGTrimAxis(fdmex,&fgic,tRdot,tRudder ));
852 sub_iterations.resize(TrimAxes.size());
853 successful.resize(TrimAxes.size());
854 solution.resize(TrimAxes.size());
This class implements a 3 element column vector.
Encapsulates the JSBSim simulation executive.
std::shared_ptr< FGInitialCondition > GetIC(void) const
Returns a pointer to the FGInitialCondition object.
std::shared_ptr< FGFCS > GetFCS(void) const
Returns the FGFCS pointer.
std::shared_ptr< FGPropagate > GetPropagate(void) const
Returns the FGPropagate pointer.
bool Run(void)
This function executes each scheduled model in succession.
std::shared_ptr< FGGroundReactions > GetGroundReactions(void) const
Returns the FGGroundReactions pointer.
std::shared_ptr< FGMassBalance > GetMassBalance(void) const
Returns the FGAircraft pointer.
void SuspendIntegration(void)
Suspends the simulation and sets the delta T to zero.
std::shared_ptr< FGInertial > GetInertial(void) const
Returns the FGInertial pointer.
void Initialize(const FGInitialCondition *FGIC)
Initializes the simulation with initial conditions.
std::shared_ptr< FGAccelerations > GetAccelerations(void) const
Returns the FGAccelerations pointer.
void ResumeIntegration(void)
Resumes the simulation by resetting delta T to the correct value.
void SetPsiRadIC(double psi)
Sets the initial heading angle.
double GetPhiRadIC(void) const
Gets the initial roll angle.
double GetAltitudeASLFtIC(void) const
Gets the initial altitude above sea level.
double GetTargetNlfIC(void) const
Gets the target normal load factor set from IC.
const FGQuaternion & GetOrientation(void) const
Gets the initial orientation.
void SetPRadpsIC(double P)
Sets the initial body axis roll rate.
double GetAltitudeAGLFtIC(void) const
Gets the initial altitude above ground level.
void SetThetaRadIC(double theta)
Sets the initial pitch angle.
double GetVtrueFpsIC(void) const
Gets the initial true velocity.
void SetRRadpsIC(double R)
Sets the initial body axis yaw rate.
void SetQRadpsIC(double Q)
Sets the initial body axis pitch rate.
double GetUBodyFpsIC(void) const
Gets the initial body axis X velocity.
double GetFlightPathAngleRadIC(void) const
Gets the initial flight path angle.
double GetThetaRadIC(void) const
Gets the initial pitch angle.
void SetPhiRadIC(double phi)
Sets the initial roll angle.
void SetAltitudeASLFtIC(double altitudeASL)
Sets the altitude above sea level initial condition in feet.
FGLocation holds an arbitrary location in the Earth centered Earth fixed reference frame (ECEF).
FGLocation LocalToLocation(const FGColumnVector3 &lvec) const
Conversion from Local frame coordinates to a location in the earth centered and fixed frame.
Handles matrix math operations.
bool AddState(State state, Control control)
Add a state-control pair to the current configuration.
void ClearStates(void)
Clear all state-control pairs from the current configuration.
bool RemoveState(State state)
Remove a specific state-control pair from the current configuration.
void Report(void)
Print the results of the trim.
void SetMode(TrimMode tm)
Clear all state-control pairs and set a predefined trim mode.
bool DoTrim(void)
Execute the trim.
bool EditState(State state, Control new_control)
Change the control used to zero a state previously configured.
FGTrim(FGFDMExec *FDMExec, TrimMode tm=tGround)
Initializes the trimming class.
void TrimStats()
Iteration statistics.