Sync. w. JSBSim cvs
This commit is contained in:
parent
3930967645
commit
27a7305736
23 changed files with 208 additions and 172 deletions
|
@ -172,6 +172,7 @@ FGFDMExec::FGFDMExec(FGPropertyManager* root) : Root(root)
|
|||
typedef int (FGFDMExec::*iPMF)(void) const;
|
||||
// instance->Tie("simulation/do_trim_analysis", this, (iPMF)0, &FGFDMExec::DoTrimAnalysis);
|
||||
instance->Tie("simulation/do_simple_trim", this, (iPMF)0, &FGFDMExec::DoTrim);
|
||||
instance->Tie("simulation/reset", this, (iPMF)0, &FGFDMExec::ResetToInitialConditions);
|
||||
instance->Tie("simulation/terminate", (int *)&Terminate);
|
||||
Constructing = false;
|
||||
}
|
||||
|
@ -388,6 +389,16 @@ bool FGFDMExec::RunIC(void)
|
|||
return true;
|
||||
}
|
||||
|
||||
//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
|
||||
//
|
||||
// A private, internal function call for Tie-ing to a property, so it needs an
|
||||
// argument. Nothing is done with the argument, yet.
|
||||
|
||||
void FGFDMExec::ResetToInitialConditions(int mode)
|
||||
{
|
||||
ResetToInitialConditions();
|
||||
}
|
||||
|
||||
//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
|
||||
|
||||
void FGFDMExec::ResetToInitialConditions(void)
|
||||
|
|
|
@ -507,6 +507,7 @@ private:
|
|||
bool ReadFileHeader(Element*);
|
||||
bool ReadSlave(Element*);
|
||||
bool ReadPrologue(Element*);
|
||||
void ResetToInitialConditions(int mode);
|
||||
bool Allocate(void);
|
||||
bool DeAllocate(void);
|
||||
|
||||
|
|
|
@ -43,6 +43,7 @@ INCLUDES
|
|||
#include <string>
|
||||
#include <sstream>
|
||||
#include <cmath>
|
||||
#include <cstdlib>
|
||||
|
||||
using std::fabs;
|
||||
using std::string;
|
||||
|
@ -334,6 +335,31 @@ protected:
|
|||
return Property + "[" + tmp + "]";
|
||||
}
|
||||
|
||||
static double GaussianRandomNumber(void)
|
||||
{
|
||||
static double V1, V2, S;
|
||||
static int phase = 0;
|
||||
double X;
|
||||
|
||||
if (phase == 0) {
|
||||
do {
|
||||
double U1 = (double)rand() / RAND_MAX;
|
||||
double U2 = (double)rand() / RAND_MAX;
|
||||
|
||||
V1 = 2 * U1 - 1;
|
||||
V2 = 2 * U2 - 1;
|
||||
S = V1 * V1 + V2 * V2;
|
||||
} while(S >= 1 || S == 0);
|
||||
|
||||
X = V1 * sqrt(-2 * log(S) / S);
|
||||
} else
|
||||
X = V2 * sqrt(-2 * log(S) / S);
|
||||
|
||||
phase = 1 - phase;
|
||||
|
||||
return X;
|
||||
}
|
||||
|
||||
public:
|
||||
/// Moments L, M, N
|
||||
enum {eL = 1, eM, eN };
|
||||
|
|
|
@ -60,7 +60,7 @@ FGColumnVector3::FGColumnVector3(void)
|
|||
string FGColumnVector3::Dump(string delimeter) const
|
||||
{
|
||||
char buffer[256];
|
||||
sprintf(buffer, "%13.6e%s%13.6e%s%13.6e", Entry(1), delimeter.c_str(), Entry(2), delimeter.c_str(), Entry(3));
|
||||
sprintf(buffer, "%18.16f%s%18.16f%s%18.16f", Entry(1), delimeter.c_str(), Entry(2), delimeter.c_str(), Entry(3));
|
||||
return string(buffer);
|
||||
}
|
||||
|
||||
|
|
|
@ -330,33 +330,6 @@ string FGFunction::GetValueAsString(void) const
|
|||
|
||||
//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
|
||||
|
||||
double FGFunction::GaussianRandomNumber(void) const
|
||||
{
|
||||
static double V1, V2, S;
|
||||
static int phase = 0;
|
||||
double X;
|
||||
|
||||
if (phase == 0) {
|
||||
do {
|
||||
double U1 = (double)rand() / RAND_MAX;
|
||||
double U2 = (double)rand() / RAND_MAX;
|
||||
|
||||
V1 = 2 * U1 - 1;
|
||||
V2 = 2 * U2 - 1;
|
||||
S = V1 * V1 + V2 * V2;
|
||||
} while(S >= 1 || S == 0);
|
||||
|
||||
X = V1 * sqrt(-2 * log(S) / S);
|
||||
} else
|
||||
X = V2 * sqrt(-2 * log(S) / S);
|
||||
|
||||
phase = 1 - phase;
|
||||
|
||||
return X;
|
||||
}
|
||||
|
||||
//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
|
||||
|
||||
void FGFunction::bind(void)
|
||||
{
|
||||
if ( !Name.empty() ) {
|
||||
|
|
|
@ -227,7 +227,6 @@ private:
|
|||
eExp, eAbs, eSin, eCos, eTan, eASin, eACos, eATan, eATan2,
|
||||
eMin, eMax, eAvg, eFrac, eInteger, eMod, eRandom} Type;
|
||||
string Name;
|
||||
double GaussianRandomNumber(void) const;
|
||||
void bind(void);
|
||||
void Debug(int from);
|
||||
};
|
||||
|
|
|
@ -257,15 +257,15 @@ FGMatrix33& FGAerodynamics::GetTw2b(void)
|
|||
cb = cos(beta);
|
||||
sb = sin(beta);
|
||||
|
||||
mTw2b(1,1) = ca*cb;
|
||||
mTw2b(1,1) = ca*cb;
|
||||
mTw2b(1,2) = -ca*sb;
|
||||
mTw2b(1,3) = -sa;
|
||||
mTw2b(2,1) = sb;
|
||||
mTw2b(2,2) = cb;
|
||||
mTw2b(2,3) = 0.0;
|
||||
mTw2b(3,1) = sa*cb;
|
||||
mTw2b(2,1) = sb;
|
||||
mTw2b(2,2) = cb;
|
||||
mTw2b(2,3) = 0.0;
|
||||
mTw2b(3,1) = sa*cb;
|
||||
mTw2b(3,2) = -sa*sb;
|
||||
mTw2b(3,3) = ca;
|
||||
mTw2b(3,3) = ca;
|
||||
|
||||
return mTw2b;
|
||||
}
|
||||
|
|
|
@ -80,7 +80,8 @@ FGAtmosphere::FGAtmosphere(FGFDMExec* fdmex) : FGModel(fdmex)
|
|||
htab[7]=278385.0; //ft.
|
||||
|
||||
MagnitudedAccelDt = MagnitudeAccel = Magnitude = 0.0;
|
||||
SetTurbType( ttCulp );
|
||||
// SetTurbType( ttCulp );
|
||||
SetTurbType( ttNone );
|
||||
TurbGain = 0.0;
|
||||
TurbRate = 1.7;
|
||||
Rhythmicity = 0.1;
|
||||
|
@ -274,6 +275,7 @@ void FGAtmosphere::CalculateDerived(void)
|
|||
|
||||
vTotalWindNED = vWindNED + vGustNED + vTurbulenceNED;
|
||||
|
||||
// psiw (Wind heading) is the direction the wind is blowing towards
|
||||
if (vWindNED(eX) != 0.0) psiw = atan2( vWindNED(eY), vWindNED(eX) );
|
||||
if (psiw < 0) psiw += 2*M_PI;
|
||||
|
||||
|
@ -336,6 +338,8 @@ static inline double square_signed (double value)
|
|||
}
|
||||
|
||||
//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
|
||||
//
|
||||
// psi is the angle that the wind is blowing *towards*
|
||||
|
||||
void FGAtmosphere::SetWindspeed(double speed)
|
||||
{
|
||||
|
@ -357,6 +361,8 @@ double FGAtmosphere::GetWindspeed(void) const
|
|||
}
|
||||
|
||||
//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
|
||||
//
|
||||
// psi is the angle that the wind is blowing *towards*
|
||||
|
||||
void FGAtmosphere::SetWindPsi(double dir)
|
||||
{
|
||||
|
@ -578,7 +584,7 @@ void FGAtmosphere::bind(void)
|
|||
PropertyManager->Tie("atmosphere/sigma", this, &FGAtmosphere::GetDensityRatio);
|
||||
PropertyManager->Tie("atmosphere/delta", this, &FGAtmosphere::GetPressureRatio);
|
||||
PropertyManager->Tie("atmosphere/a-ratio", this, &FGAtmosphere::GetSoundSpeedRatio);
|
||||
PropertyManager->Tie("atmosphere/psiw-rad", this, &FGAtmosphere::GetWindPsi);
|
||||
PropertyManager->Tie("atmosphere/psiw-rad", this, &FGAtmosphere::GetWindPsi, &FGAtmosphere::SetWindPsi);
|
||||
PropertyManager->Tie("atmosphere/delta-T", this, &FGAtmosphere::GetDeltaT, &FGAtmosphere::SetDeltaT);
|
||||
PropertyManager->Tie("atmosphere/T-sl-dev-F", this, &FGAtmosphere::GetSLTempDev, &FGAtmosphere::SetSLTempDev);
|
||||
PropertyManager->Tie("atmosphere/density-altitude", this, &FGAtmosphere::GetDensityAltitude);
|
||||
|
@ -589,8 +595,6 @@ void FGAtmosphere::bind(void)
|
|||
(PMFd)&FGAtmosphere::SetWindNED);
|
||||
PropertyManager->Tie("atmosphere/wind-down-fps", this, eDown, (PMF)&FGAtmosphere::GetWindNED,
|
||||
(PMFd)&FGAtmosphere::SetWindNED);
|
||||
PropertyManager->Tie("atmosphere/wind-from-cw", this, &FGAtmosphere::GetWindFromClockwise,
|
||||
&FGAtmosphere::SetWindFromClockwise);
|
||||
PropertyManager->Tie("atmosphere/wind-mag-fps", this, &FGAtmosphere::GetWindspeed,
|
||||
&FGAtmosphere::SetWindspeed);
|
||||
PropertyManager->Tie("atmosphere/total-wind-north-fps", this, eNorth, (PMF)&FGAtmosphere::GetTotalWindNED);
|
||||
|
|
|
@ -216,11 +216,6 @@ public:
|
|||
void SetRhythmicity(double r) {Rhythmicity=r;}
|
||||
double GetRhythmicity() const {return Rhythmicity;}
|
||||
|
||||
/** Sets wind vortex, clockwise as seen from a point in front of aircraft,
|
||||
looking aft. Units are radians/second. */
|
||||
void SetWindFromClockwise(double wC) { wind_from_clockwise=wC; }
|
||||
double GetWindFromClockwise(void) const {return wind_from_clockwise;}
|
||||
|
||||
double GetTurbPQR(int idx) const {return vTurbPQR(idx);}
|
||||
double GetTurbMagnitude(void) const {return Magnitude;}
|
||||
FGColumnVector3& GetTurbDirection(void) {return vDirection;}
|
||||
|
|
|
@ -170,11 +170,12 @@ bool FGAuxiliary::Run()
|
|||
vAeroUVW = vUVW;
|
||||
} else if (GroundReactions->GetWOW() && vUVW(eU) < 30) {
|
||||
double factor = (vUVW(eU) - 10.0)/20.0;
|
||||
vAeroPQR = vPQR + factor*Atmosphere->GetTurbPQR();
|
||||
vAeroUVW = vUVW + factor*Propagate->GetTl2b()*Atmosphere->GetTotalWindNED();
|
||||
vAeroPQR = vPQR - factor*Atmosphere->GetTurbPQR();
|
||||
vAeroUVW = vUVW - factor*Propagate->GetTl2b()*Atmosphere->GetTotalWindNED();
|
||||
} else {
|
||||
vAeroPQR = vPQR + Atmosphere->GetTurbPQR();
|
||||
vAeroUVW = vUVW + Propagate->GetTl2b()*Atmosphere->GetTotalWindNED();
|
||||
FGColumnVector3 wind = Propagate->GetTl2b()*Atmosphere->GetTotalWindNED();
|
||||
vAeroPQR = vPQR - Atmosphere->GetTurbPQR();
|
||||
vAeroUVW = vUVW - wind;
|
||||
}
|
||||
|
||||
Vt = vAeroUVW.Magnitude();
|
||||
|
@ -289,6 +290,9 @@ bool FGAuxiliary::Run()
|
|||
}
|
||||
|
||||
//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
|
||||
//
|
||||
// A positive headwind is blowing with you, a negative headwind is blowing against you.
|
||||
// psi is the direction the wind is blowing *towards*.
|
||||
|
||||
double FGAuxiliary::GetHeadWind(void) const
|
||||
{
|
||||
|
@ -301,6 +305,10 @@ double FGAuxiliary::GetHeadWind(void) const
|
|||
}
|
||||
|
||||
//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
|
||||
//
|
||||
// A positive crosswind is blowing towards the right (from teh perspective of the
|
||||
// pilot). A negative crosswind is blowing towards the -Y direction (left).
|
||||
// psi is the direction the wind is blowing *towards*.
|
||||
|
||||
double FGAuxiliary::GetCrossWind(void) const
|
||||
{
|
||||
|
|
|
@ -139,6 +139,46 @@ bool FGFCS::InitModel(void)
|
|||
DfPos[i] = DsbPos[i] = DspPos[i] = 0.0;
|
||||
}
|
||||
|
||||
for (int i=0; i<Systems.size(); i++) {
|
||||
if (Systems[i]->GetType() == "LAG" ||
|
||||
Systems[i]->GetType() == "LEAD_LAG" ||
|
||||
Systems[i]->GetType() == "WASHOUT" ||
|
||||
Systems[i]->GetType() == "SECOND_ORDER_FILTER" ||
|
||||
Systems[i]->GetType() == "INTEGRATOR")
|
||||
{
|
||||
((FGFilter*)Systems[i])->ResetPastStates();
|
||||
} else if (Systems[i]->GetType() == "PID" ) {
|
||||
((FGPID*)Systems[i])->ResetPastStates();
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
for (int i=0; i<FCSComponents.size(); i++) {
|
||||
if (FCSComponents[i]->GetType() == "LAG" ||
|
||||
FCSComponents[i]->GetType() == "LEAD_LAG" ||
|
||||
FCSComponents[i]->GetType() == "WASHOUT" ||
|
||||
FCSComponents[i]->GetType() == "SECOND_ORDER_FILTER" ||
|
||||
FCSComponents[i]->GetType() == "INTEGRATOR")
|
||||
{
|
||||
((FGFilter*)FCSComponents[i])->ResetPastStates();
|
||||
} else if (FCSComponents[i]->GetType() == "PID" ) {
|
||||
((FGPID*)FCSComponents[i])->ResetPastStates();
|
||||
}
|
||||
}
|
||||
|
||||
for (int i=0; i<APComponents.size(); i++) {
|
||||
if (APComponents[i]->GetType() == "LAG" ||
|
||||
APComponents[i]->GetType() == "LEAD_LAG" ||
|
||||
APComponents[i]->GetType() == "WASHOUT" ||
|
||||
APComponents[i]->GetType() == "SECOND_ORDER_FILTER" ||
|
||||
APComponents[i]->GetType() == "INTEGRATOR")
|
||||
{
|
||||
((FGFilter*)APComponents[i])->ResetPastStates();
|
||||
} else if (APComponents[i]->GetType() == "PID" ) {
|
||||
((FGPID*)APComponents[i])->ResetPastStates();
|
||||
}
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
|
@ -541,13 +581,18 @@ bool FGFCS::Load(Element* el, SystemType systype)
|
|||
property_element = document->FindElement("property");
|
||||
if (property_element) cout << endl << " Declared properties" << endl << endl;
|
||||
while (property_element) {
|
||||
double value=0.0;
|
||||
if ( ! property_element->GetAttributeValue("value").empty())
|
||||
value = property_element->GetAttributeValueAsNumber("value");
|
||||
interface_properties.push_back(new double(value));
|
||||
interface_property_string = property_element->GetDataLine();
|
||||
PropertyManager->Tie(interface_property_string, interface_properties.back());
|
||||
cout << " " << interface_property_string << " (initial value: " << value << ")" << endl;
|
||||
if (PropertyManager->HasNode(interface_property_string)) {
|
||||
cout << " Property " << interface_property_string << " is already defined." << endl;
|
||||
} else {
|
||||
double value=0.0;
|
||||
if ( ! property_element->GetAttributeValue("value").empty())
|
||||
value = property_element->GetAttributeValueAsNumber("value");
|
||||
interface_properties.push_back(new double(value));
|
||||
interface_property_string = property_element->GetDataLine();
|
||||
PropertyManager->Tie(interface_property_string, interface_properties.back());
|
||||
cout << " " << interface_property_string << " (initial value: " << value << ")" << endl;
|
||||
}
|
||||
property_element = document->FindNextElement("property");
|
||||
}
|
||||
|
||||
|
@ -558,27 +603,25 @@ bool FGFCS::Load(Element* el, SystemType systype)
|
|||
|
||||
if (!fname.empty()) {
|
||||
property_element = el->FindElement("property");
|
||||
if (property_element && debug_lvl > 0) cout << endl << " Declared properties" << endl << endl;
|
||||
if (property_element && debug_lvl > 0) cout << endl << " Overriding properties" << endl << endl;
|
||||
while (property_element) {
|
||||
double value=0.0;
|
||||
if ( ! property_element->GetAttributeValue("value").empty())
|
||||
value = property_element->GetAttributeValueAsNumber("value");
|
||||
|
||||
interface_property_string = property_element->GetDataLine();
|
||||
|
||||
FGPropertyManager* node = PropertyManager->GetNode(interface_property_string);
|
||||
if (node) {
|
||||
if (PropertyManager->HasNode(interface_property_string)) {
|
||||
FGPropertyManager* node = PropertyManager->GetNode(interface_property_string);
|
||||
cout << " " << "Overriding value for property " << interface_property_string
|
||||
<< " (old value: " << node->getDoubleValue() << " new value: " << value << ")" << endl;
|
||||
node->setDoubleValue(value);
|
||||
} else {
|
||||
interface_properties.push_back(new double(value));
|
||||
PropertyManager->Tie(interface_property_string, interface_properties.back());
|
||||
if (debug_lvl > 0)
|
||||
if (debug_lvl > 0)
|
||||
cout << " " << interface_property_string << " (initial value: " << value << ")" << endl;
|
||||
}
|
||||
|
||||
|
||||
property_element = el->FindNextElement("property");
|
||||
}
|
||||
}
|
||||
|
|
|
@ -246,86 +246,18 @@ FGLGear::FGLGear(Element* el, FGFDMExec* fdmex, int number) :
|
|||
SinWheel = 0.0;
|
||||
CosWheel = 0.0;
|
||||
|
||||
// Set Pacejka terms
|
||||
|
||||
Stiffness = 0.06;
|
||||
Shape = 2.8;
|
||||
Peak = staticFCoeff;
|
||||
Curvature = 1.03;
|
||||
|
||||
Debug(0);
|
||||
}
|
||||
|
||||
//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
|
||||
|
||||
FGLGear::FGLGear(const FGLGear& lgear)
|
||||
{
|
||||
GearNumber = lgear.GearNumber;
|
||||
State = lgear.State;
|
||||
Aircraft = lgear.Aircraft;
|
||||
Propagate = lgear.Propagate;
|
||||
Auxiliary = lgear.Auxiliary;
|
||||
Exec = lgear.Exec;
|
||||
FCS = lgear.FCS;
|
||||
MassBalance = lgear.MassBalance;
|
||||
|
||||
vXYZ = lgear.vXYZ;
|
||||
vMoment = lgear.vMoment;
|
||||
vWhlBodyVec = lgear.vWhlBodyVec;
|
||||
vLocalGear = lgear.vLocalGear;
|
||||
|
||||
WOW = lgear.WOW;
|
||||
lastWOW = lgear.lastWOW;
|
||||
ReportEnable = lgear.ReportEnable;
|
||||
FirstContact = lgear.FirstContact;
|
||||
StartedGroundRun = lgear.StartedGroundRun;
|
||||
LandingDistanceTraveled = lgear.LandingDistanceTraveled;
|
||||
TakeoffDistanceTraveled = lgear.TakeoffDistanceTraveled;
|
||||
TakeoffDistanceTraveled50ft = lgear.TakeoffDistanceTraveled50ft;
|
||||
MaximumStrutForce = lgear.MaximumStrutForce;
|
||||
MaximumStrutTravel = lgear.MaximumStrutTravel;
|
||||
SideForce = lgear.SideForce;
|
||||
RollingForce = lgear.RollingForce;
|
||||
|
||||
kSpring = lgear.kSpring;
|
||||
bDamp = lgear.bDamp;
|
||||
bDampRebound = lgear.bDampRebound;
|
||||
compressLength = lgear.compressLength;
|
||||
compressSpeed = lgear.compressSpeed;
|
||||
staticFCoeff = lgear.staticFCoeff;
|
||||
dynamicFCoeff = lgear.dynamicFCoeff;
|
||||
rollingFCoeff = lgear.rollingFCoeff;
|
||||
brakePct = lgear.brakePct;
|
||||
maxCompLen = lgear.maxCompLen;
|
||||
SinkRate = lgear.SinkRate;
|
||||
GroundSpeed = lgear.GroundSpeed;
|
||||
LandingReported = lgear.LandingReported;
|
||||
TakeoffReported = lgear.TakeoffReported;
|
||||
name = lgear.name;
|
||||
sSteerType = lgear.sSteerType;
|
||||
sRetractable = lgear.sRetractable;
|
||||
sContactType = lgear.sContactType;
|
||||
eContactType = lgear.eContactType;
|
||||
sBrakeGroup = lgear.sBrakeGroup;
|
||||
eSteerType = lgear.eSteerType;
|
||||
eBrakeGrp = lgear.eBrakeGrp;
|
||||
maxSteerAngle = lgear.maxSteerAngle;
|
||||
isRetractable = lgear.isRetractable;
|
||||
GearUp = lgear.GearUp;
|
||||
GearDown = lgear.GearDown;
|
||||
GearPos = lgear.GearPos;
|
||||
useFCSGearPos = lgear.useFCSGearPos;
|
||||
WheelSlip = lgear.WheelSlip;
|
||||
TirePressureNorm = lgear.TirePressureNorm;
|
||||
Servicable = lgear.Servicable;
|
||||
ForceY_Table = lgear.ForceY_Table;
|
||||
CosWheel = lgear.CosWheel;
|
||||
SinWheel = lgear.SinWheel;
|
||||
RFRV = lgear.RFRV;
|
||||
SFRV = lgear.SFRV;
|
||||
LongForceLagFilterCoeff = lgear.LongForceLagFilterCoeff;
|
||||
LatForceLagFilterCoeff = lgear.LatForceLagFilterCoeff;
|
||||
WheelSlipLagFilterCoeff = lgear.WheelSlipLagFilterCoeff;
|
||||
WheelSlipFilter = lgear.WheelSlipFilter;
|
||||
LongForceFilter = lgear.LongForceFilter;
|
||||
LatForceFilter = lgear.LatForceFilter;
|
||||
}
|
||||
|
||||
//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
|
||||
|
||||
FGLGear::~FGLGear()
|
||||
{
|
||||
Debug(1);
|
||||
|
@ -624,27 +556,22 @@ void FGLGear::ComputeBrakeForceCoefficient(void)
|
|||
}
|
||||
|
||||
//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
|
||||
// Compute the sideforce coefficients using similar assumptions to LaRCSim for now.
|
||||
// Allow a maximum of 10 degrees tire slip angle before wheel slides. At that point,
|
||||
// transition from static to dynamic friction. There are more complicated formulations
|
||||
// of this that avoid the discrete jump (similar to Pacejka). Will fix this later.
|
||||
// Compute the sideforce coefficients using Pacejka's Magic Formula.
|
||||
//
|
||||
// y(x) = D sin {C arctan [Bx - E(Bx - arctan Bx)]}
|
||||
//
|
||||
// Where: B = Stiffness Factor (0.06, here)
|
||||
// C = Shape Factor (2.8, here)
|
||||
// D = Peak Factor (0.8, here)
|
||||
// E = Curvature Factor (1.03, here)
|
||||
|
||||
void FGLGear::ComputeSideForceCoefficient(void)
|
||||
{
|
||||
if (ForceY_Table) {
|
||||
|
||||
FCoeff = ForceY_Table->GetValue(WheelSlip);
|
||||
|
||||
} else {
|
||||
|
||||
if (fabs(WheelSlip) <= 10.0) {
|
||||
FCoeff = staticFCoeff*WheelSlip/10.0;
|
||||
} else if (fabs(WheelSlip) <= 40.0) {
|
||||
FCoeff = (dynamicFCoeff*(fabs(WheelSlip) - 10.0)/10.0
|
||||
+ staticFCoeff*(40.0 - fabs(WheelSlip))/10.0)*(WheelSlip>=0?1.0:-1.0);
|
||||
} else {
|
||||
FCoeff = dynamicFCoeff*(WheelSlip>=0?1.0:-1.0);
|
||||
}
|
||||
double StiffSlip = Stiffness*WheelSlip;
|
||||
FCoeff = Peak * sin(Shape*atan(StiffSlip - Curvature*(StiffSlip - atan(StiffSlip))));
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -713,6 +640,8 @@ void FGLGear::bind(void)
|
|||
&FGLGear::GetZPosition, &FGLGear::SetZPosition);
|
||||
property_name = base_property_name + "/compression-ft";
|
||||
Exec->GetPropertyManager()->Tie( property_name.c_str(), &compressLength );
|
||||
property_name = base_property_name + "/side_friction_coeff";
|
||||
Exec->GetPropertyManager()->Tie( property_name.c_str(), &FCoeff );
|
||||
}
|
||||
|
||||
if( isRetractable ) {
|
||||
|
|
|
@ -218,9 +218,6 @@ public:
|
|||
@param number integer identifier for this instance of FGLGear
|
||||
*/
|
||||
FGLGear(Element* el, FGFDMExec* Executive, int number);
|
||||
/** Constructor
|
||||
@param lgear a reference to an existing FGLGear object */
|
||||
FGLGear(const FGLGear& lgear);
|
||||
/// Destructor
|
||||
~FGLGear();
|
||||
|
||||
|
@ -313,6 +310,7 @@ private:
|
|||
double compressLength;
|
||||
double compressSpeed;
|
||||
double staticFCoeff, dynamicFCoeff, rollingFCoeff;
|
||||
double Stiffness, Shape, Peak, Curvature; // Pacejka factors
|
||||
double brakePct;
|
||||
double BrakeFCoeff;
|
||||
double maxCompLen;
|
||||
|
|
|
@ -46,6 +46,8 @@ INCLUDES
|
|||
#include "FGFCS.h"
|
||||
#include "FGAerodynamics.h"
|
||||
#include "FGGroundReactions.h"
|
||||
#include "FGExternalReactions.h"
|
||||
#include "FGBuoyantForces.h"
|
||||
#include "FGAircraft.h"
|
||||
#include "FGMassBalance.h"
|
||||
#include "FGPropagate.h"
|
||||
|
@ -258,11 +260,21 @@ void FGOutput::DelimitedOutput(string fname)
|
|||
outstream << delimeter;
|
||||
outstream << "F_{Drag} (lbs)" + delimeter + "F_{Side} (lbs)" + delimeter + "F_{Lift} (lbs)" + delimeter;
|
||||
outstream << "L/D" + delimeter;
|
||||
outstream << "F_X (lbs)" + delimeter + "F_Y (lbs)" + delimeter + "F_Z (lbs)";
|
||||
outstream << "F_{Aero x} (lbs)" + delimeter + "F_{Aero y} (lbs)" + delimeter + "F_{Aero z} (lbs)" + delimeter;
|
||||
outstream << "F_{Prop x} (lbs)" + delimeter + "F_{Prop y} (lbs)" + delimeter + "F_{Prop z} (lbs)" + delimeter;
|
||||
outstream << "F_{Gear x} (lbs)" + delimeter + "F_{Gear y} (lbs)" + delimeter + "F_{Gear z} (lbs)" + delimeter;
|
||||
outstream << "F_{Ext x} (lbs)" + delimeter + "F_{Ext y} (lbs)" + delimeter + "F_{Ext z} (lbs)" + delimeter;
|
||||
outstream << "F_{Buoyant x} (lbs)" + delimeter + "F_{Buoyant y} (lbs)" + delimeter + "F_{Buoyant z} (lbs)" + delimeter;
|
||||
outstream << "F_{Total x} (lbs)" + delimeter + "F_{Total y} (lbs)" + delimeter + "F_{Total z} (lbs)";
|
||||
}
|
||||
if (SubSystems & ssMoments) {
|
||||
outstream << delimeter;
|
||||
outstream << "L (ft-lbs)" + delimeter + "M (ft-lbs)" + delimeter + "N (ft-lbs)";
|
||||
outstream << "L_{Aero} (ft-lbs)" + delimeter + "M_{Aero} ( ft-lbs)" + delimeter + "N_{Aero} (ft-lbs)" + delimeter;
|
||||
outstream << "L_{Prop} (ft-lbs)" + delimeter + "M_{Prop} (ft-lbs)" + delimeter + "N_{Prop} (ft-lbs)" + delimeter;
|
||||
outstream << "L_{Gear} (ft-lbs)" + delimeter + "M_{Gear} (ft-lbs)" + delimeter + "N_{Gear} (ft-lbs)" + delimeter;
|
||||
outstream << "L_{ext} (ft-lbs)" + delimeter + "M_{ext} (ft-lbs)" + delimeter + "N_{ext} (ft-lbs)" + delimeter;
|
||||
outstream << "L_{Buoyant} (ft-lbs)" + delimeter + "M_{Buoyant} (ft-lbs)" + delimeter + "N_{Buoyant} (ft-lbs)" + delimeter;
|
||||
outstream << "L_{Total} (ft-lbs)" + delimeter + "M_{Total} (ft-lbs)" + delimeter + "N_{Total} (ft-lbs)";
|
||||
}
|
||||
if (SubSystems & ssAtmosphere) {
|
||||
outstream << delimeter;
|
||||
|
@ -358,15 +370,26 @@ void FGOutput::DelimitedOutput(string fname)
|
|||
outstream << setprecision(12) << Propagate->GetUVW().Dump(delimeter) << delimeter;
|
||||
outstream << Auxiliary->GetAeroUVW().Dump(delimeter) << delimeter;
|
||||
outstream << Propagate->GetVel().Dump(delimeter);
|
||||
outstream.precision(10);
|
||||
}
|
||||
if (SubSystems & ssForces) {
|
||||
outstream << delimeter;
|
||||
outstream << Aerodynamics->GetvFw() << delimeter;
|
||||
outstream << Aerodynamics->GetLoD() << delimeter;
|
||||
outstream << Aerodynamics->GetForces() << delimeter;
|
||||
outstream << Propulsion->GetForces() << delimeter;
|
||||
outstream << GroundReactions->GetForces() << delimeter;
|
||||
outstream << ExternalReactions->GetForces() << delimeter;
|
||||
outstream << BuoyantForces->GetForces() << delimeter;
|
||||
outstream << Aircraft->GetForces().Dump(delimeter);
|
||||
}
|
||||
if (SubSystems & ssMoments) {
|
||||
outstream << delimeter;
|
||||
outstream << Aerodynamics->GetMoments() << delimeter;
|
||||
outstream << Propulsion->GetMoments() << delimeter;
|
||||
outstream << GroundReactions->GetMoments() << delimeter;
|
||||
outstream << ExternalReactions->GetMoments() << delimeter;
|
||||
outstream << BuoyantForces->GetMoments() << delimeter;
|
||||
outstream << Aircraft->GetMoments().Dump(delimeter);
|
||||
}
|
||||
if (SubSystems & ssAtmosphere) {
|
||||
|
@ -388,6 +411,7 @@ void FGOutput::DelimitedOutput(string fname)
|
|||
outstream << MassBalance->GetXYZcg();
|
||||
}
|
||||
if (SubSystems & ssPropagate) {
|
||||
outstream.precision(14);
|
||||
outstream << delimeter;
|
||||
outstream << Propagate->Geth() << delimeter;
|
||||
outstream << (radtodeg*Propagate->GetEuler()).Dump(delimeter) << delimeter;
|
||||
|
@ -395,10 +419,13 @@ void FGOutput::DelimitedOutput(string fname)
|
|||
outstream << Auxiliary->Getbeta(inDegrees) << delimeter;
|
||||
outstream << Propagate->GetLocation().GetLatitudeDeg() << delimeter;
|
||||
outstream << Propagate->GetLocation().GetLongitudeDeg() << delimeter;
|
||||
outstream.precision(18);
|
||||
outstream << ((FGColumnVector3)Propagate->GetLocation()).Dump(delimeter) << delimeter;
|
||||
outstream.precision(14);
|
||||
outstream << Inertial->GetEarthPositionAngleDeg() << delimeter;
|
||||
outstream << Propagate->GetDistanceAGL() << delimeter;
|
||||
outstream << Propagate->GetRunwayRadius();
|
||||
outstream.precision(10);
|
||||
}
|
||||
if (SubSystems & ssCoefficients) {
|
||||
scratch = Aerodynamics->GetCoefficientValues(delimeter);
|
||||
|
|
|
@ -82,6 +82,10 @@ FGPropagate::FGPropagate(FGFDMExec* fdmex) : FGModel(fdmex)
|
|||
last_vPQRdot.InitMatrix();
|
||||
vPQRdot.InitMatrix();
|
||||
|
||||
last2_vQtrndot = FGQuaternion(0,0,0);
|
||||
last_vQtrndot = FGQuaternion(0,0,0);
|
||||
vQtrndot = FGQuaternion(0,0,0);
|
||||
|
||||
last2_vUVWdot.InitMatrix();
|
||||
last_vUVWdot.InitMatrix();
|
||||
vUVWdot.InitMatrix();
|
||||
|
@ -93,8 +97,8 @@ FGPropagate::FGPropagate(FGFDMExec* fdmex) : FGModel(fdmex)
|
|||
vOmegaLocal.InitMatrix();
|
||||
|
||||
integrator_rotational_rate = eAdamsBashforth2;
|
||||
integrator_translational_rate = eAdamsBashforth2;
|
||||
integrator_rotational_position = eTrapezoidal;
|
||||
integrator_translational_rate = eTrapezoidal;
|
||||
integrator_rotational_position = eAdamsBashforth2;
|
||||
integrator_translational_position = eTrapezoidal;
|
||||
|
||||
bind();
|
||||
|
@ -125,6 +129,10 @@ bool FGPropagate::InitModel(void)
|
|||
last_vPQRdot.InitMatrix();
|
||||
vPQRdot.InitMatrix();
|
||||
|
||||
last2_vQtrndot = FGQuaternion(0,0,0);
|
||||
last_vQtrndot = FGQuaternion(0,0,0);
|
||||
vQtrndot = FGQuaternion(0,0,0);
|
||||
|
||||
last2_vUVWdot.InitMatrix();
|
||||
last_vUVWdot.InitMatrix();
|
||||
vUVWdot.InitMatrix();
|
||||
|
@ -136,8 +144,8 @@ bool FGPropagate::InitModel(void)
|
|||
vOmegaLocal.InitMatrix();
|
||||
|
||||
integrator_rotational_rate = eAdamsBashforth2;
|
||||
integrator_translational_rate = eAdamsBashforth2;
|
||||
integrator_rotational_position = eTrapezoidal;
|
||||
integrator_translational_rate = eTrapezoidal;
|
||||
integrator_rotational_position = eAdamsBashforth2;
|
||||
integrator_translational_position = eTrapezoidal;
|
||||
|
||||
return true;
|
||||
|
|
|
@ -194,7 +194,10 @@ void FGActuator::Deadband(void)
|
|||
|
||||
void FGActuator::bind(void)
|
||||
{
|
||||
string tmp = "fcs/" + PropertyManager->mkPropertyName(Name, true);
|
||||
string tmp = Name;
|
||||
if (Name.find("/") == string::npos) {
|
||||
tmp = "fcs/" + PropertyManager->mkPropertyName(Name, true);
|
||||
}
|
||||
const string tmp_zero = tmp + "/malfunction/fail_zero";
|
||||
const string tmp_hardover = tmp + "/malfunction/fail_hardover";
|
||||
const string tmp_stuck = tmp + "/malfunction/fail_stuck";
|
||||
|
|
|
@ -244,7 +244,8 @@ public:
|
|||
/** When true, causes previous values to be set to current values. This
|
||||
is particularly useful for first pass. */
|
||||
bool Initialize;
|
||||
|
||||
void ResetPastStates(void) {Input = 0.0; Initialize = true;}
|
||||
|
||||
enum {eLag, eLeadLag, eOrder2, eWashout, eIntegrator, eUnknown} FilterType;
|
||||
|
||||
private:
|
||||
|
|
|
@ -102,6 +102,7 @@ public:
|
|||
~FGPID();
|
||||
|
||||
bool Run (void);
|
||||
void ResetPastStates(void) {Input_prev = Input_prev2 = Output = I_out_total = 0.0;}
|
||||
|
||||
private:
|
||||
double dt;
|
||||
|
|
|
@ -206,7 +206,10 @@ void FGSensor::Lag(void)
|
|||
|
||||
void FGSensor::bind(void)
|
||||
{
|
||||
string tmp = "fcs/" + PropertyManager->mkPropertyName(Name, true);
|
||||
string tmp = Name;
|
||||
if (Name.find("/") == string::npos) {
|
||||
tmp = "fcs/" + PropertyManager->mkPropertyName(Name, true);
|
||||
}
|
||||
const string tmp_low = tmp + "/malfunction/fail_low";
|
||||
const string tmp_high = tmp + "/malfunction/fail_high";
|
||||
const string tmp_stuck = tmp + "/malfunction/fail_stuck";
|
||||
|
|
|
@ -109,7 +109,8 @@ FGSwitch::FGSwitch(FGFCS* fcs, Element* element) : FGFCSComponent(fcs, element)
|
|||
tests.push_back(current_test);
|
||||
}
|
||||
|
||||
if (test_element->GetName() != "output") { // this is not an output element
|
||||
if (test_element->GetName() != "output"
|
||||
&& test_element->GetName() != "description") { // this is not an output element
|
||||
value = test_element->GetAttributeValue("value");
|
||||
if (value.empty()) {
|
||||
cerr << "No VALUE supplied for switch component: " << Name << endl;
|
||||
|
|
|
@ -222,11 +222,13 @@ FGPiston::FGPiston(FGFDMExec* exec, Element* el, int engine_number)
|
|||
string property_name, base_property_name;
|
||||
base_property_name = CreateIndexedPropertyName("propulsion/engine", EngineNumber);
|
||||
property_name = base_property_name + "/power-hp";
|
||||
PropertyManager->Tie(property_name.c_str(), &HP);
|
||||
PropertyManager->Tie(property_name, &HP);
|
||||
property_name = base_property_name + "/bsfc-lbs_hphr";
|
||||
PropertyManager->Tie(property_name.c_str(), &BSFC);
|
||||
PropertyManager->Tie(property_name, &BSFC);
|
||||
property_name = base_property_name + "/volumetric-efficiency";
|
||||
PropertyManager->Tie(property_name.c_str(), &volumetric_efficiency);
|
||||
PropertyManager->Tie(property_name, &volumetric_efficiency);
|
||||
property_name = base_property_name + "/map-inhg";
|
||||
PropertyManager->Tie(property_name, &ManifoldPressure_inHg);
|
||||
minMAP = MinManifoldPressure_inHg * inhgtopa; // inHg to Pa
|
||||
maxMAP = MaxManifoldPressure_inHg * inhgtopa;
|
||||
StarterHP = sqrt(MaxHP) * 0.4;
|
||||
|
@ -607,9 +609,6 @@ void FGPiston::doFuelFlow(void)
|
|||
void FGPiston::doEnginePower(void)
|
||||
{
|
||||
if (Running) {
|
||||
double T_amb_degF = KelvinToFahrenheit(T_amb);
|
||||
double T_amb_sea_lev_degF = KelvinToFahrenheit(288);
|
||||
|
||||
// FIXME: this needs to be generalized
|
||||
double ME, friction, percent_RPM, power; // Convienience term for use in the calculations
|
||||
ME = Mixture_Efficiency_Correlation->GetValue(m_dot_fuel/m_dot_air);
|
||||
|
@ -729,7 +728,6 @@ void FGPiston::doCHT(void)
|
|||
|
||||
void FGPiston::doOilTemperature(void)
|
||||
{
|
||||
double idle_percentage_power = 0.023; // approximately
|
||||
double target_oil_temp; // Steady state oil temp at the current engine conditions
|
||||
double time_constant; // The time constant for the differential equation
|
||||
double efficiency = 0.667; // The aproximate oil cooling system efficiency // FIXME: may vary by engine
|
||||
|
|
|
@ -68,6 +68,7 @@ FGTurbine::FGTurbine(FGFDMExec* exec, Element *el, int engine_number)
|
|||
Augmented = AugMethod = Injected = 0;
|
||||
BypassRatio = BleedDemand = 0.0;
|
||||
IdleThrustLookup = MilThrustLookup = MaxThrustLookup = InjectionLookup = 0;
|
||||
N1_spinup = 1.0; N2_spinup = 3.0;
|
||||
|
||||
ResetToIC();
|
||||
|
||||
|
@ -255,8 +256,8 @@ double FGTurbine::SpinUp(void)
|
|||
{
|
||||
Running = false;
|
||||
FuelFlow_pph = 0.0;
|
||||
N2 = Seek(&N2, 25.18, 3.0, N2/2.0);
|
||||
N1 = Seek(&N1, 5.21, 1.0, N1/2.0);
|
||||
N2 = Seek(&N2, 25.18, N2_spinup, N2/2.0);
|
||||
N1 = Seek(&N1, 5.21, N1_spinup, N1/2.0);
|
||||
EGT_degC = Seek(&EGT_degC, TAT, 11.7, 7.3);
|
||||
OilPressure_psi = N2 * 0.62;
|
||||
OilTemp_degK = Seek(&OilTemp_degK, TAT + 273.0, 0.2, 0.2);
|
||||
|
@ -419,6 +420,10 @@ bool FGTurbine::Load(FGFDMExec* exec, Element *el)
|
|||
MaxN1 = el->FindElementValueAsNumber("maxn1");
|
||||
if (el->FindElement("maxn2"))
|
||||
MaxN2 = el->FindElementValueAsNumber("maxn2");
|
||||
if (el->FindElement("n1spinup"))
|
||||
N1_spinup = el->FindElementValueAsNumber("n1spinup");
|
||||
if (el->FindElement("n2spinup"))
|
||||
N2_spinup = el->FindElementValueAsNumber("n2spinup");
|
||||
if (el->FindElement("augmented"))
|
||||
Augmented = (int)el->FindElementValueAsNumber("augmented");
|
||||
if (el->FindElement("augmethod"))
|
||||
|
|
|
@ -234,6 +234,8 @@ private:
|
|||
double ThrottlePos; ///< FCS-supplied throttle position
|
||||
double AugmentCmd; ///< modulated afterburner command (0.0 to 1.0)
|
||||
double TAT; ///< total air temperature (deg C)
|
||||
double N1_spinup; ///< N1 spin up rate from starter (per second)
|
||||
double N2_spinup; ///< N2 spin up rate from starter (per second)
|
||||
bool Stalled; ///< true if engine is compressor-stalled
|
||||
bool Seized; ///< true if inner spool is seized
|
||||
bool Overtemp; ///< true if EGT exceeds limits
|
||||
|
|
Loading…
Add table
Reference in a new issue