1
0
Fork 0

YASim: convert Atmosphere to a non-static class so we can pass around air parameters in one object instead of several variables.

This commit is contained in:
Henning Stahlke 2017-04-22 16:14:52 +02:00
parent 5e99f92a0f
commit 3457c3c61f
16 changed files with 199 additions and 203 deletions

View file

@ -38,13 +38,9 @@ Airplane::Airplane()
_wing = 0;
_tail = 0;
_ballast = 0;
_cruiseP = 0;
_cruiseT = 0;
_cruiseSpeed = 0;
_cruiseWeight = 0;
_cruiseGlideAngle = 0;
_approachP = 0;
_approachT = 0;
_approachSpeed = 0;
_approachAoA = 0;
_approachWeight = 0;
@ -149,8 +145,7 @@ void Airplane::updateGearState()
void Airplane::setApproach(float speed, float altitude, float aoa, float fuel, float gla)
{
_approachSpeed = speed;
_approachP = Atmosphere::getStdPressure(altitude);
_approachT = Atmosphere::getStdTemperature(altitude);
_approachAtmo.setStandard(altitude);
_approachAoA = aoa;
_approachFuel = fuel;
_approachGlideAngle = gla;
@ -159,8 +154,7 @@ void Airplane::setApproach(float speed, float altitude, float aoa, float fuel, f
void Airplane::setCruise(float speed, float altitude, float fuel, float gla)
{
_cruiseSpeed = speed;
_cruiseP = Atmosphere::getStdPressure(altitude);
_cruiseT = Atmosphere::getStdTemperature(altitude);
_cruiseAtmo.setStandard(altitude);
_cruiseAoA = 0;
_tailIncidence = 0;
_cruiseFuel = fuel;
@ -790,7 +784,7 @@ void Airplane::setupWeights(bool isApproach)
}
/// load values for controls as defined in cruise configuration
void Airplane::loadControls(Vector& controls)
void Airplane::loadControls(const Vector& controls)
{
_controls.reset();
for(int i=0; i < controls.size(); i++) {
@ -805,8 +799,7 @@ void Airplane::runCruise()
{
setupState(_cruiseAoA, _cruiseSpeed,_cruiseGlideAngle, &_cruiseState);
_model.setState(&_cruiseState);
_model.setAir(_cruiseP, _cruiseT,
Atmosphere::calcStdDensity(_cruiseP, _cruiseT));
_model.setAtmosphere(_cruiseAtmo);
// The control configuration
loadControls(_cruiseControls);
@ -822,10 +815,10 @@ void Airplane::runCruise()
// Set up the thruster parameters and iterate until the thrust
// stabilizes.
for(int i=0; i<_thrusters.size(); i++) {
Thruster* t = ((ThrustRec*)_thrusters.get(i))->thruster;
t->setWind(wind);
t->setAir(_cruiseP, _cruiseT,
Atmosphere::calcStdDensity(_cruiseP, _cruiseT));
Thruster* t = ((ThrustRec*)_thrusters.get(i))->thruster;
t->setWind(wind);
t->setAir(_cruiseAtmo);
//Atmosphere::calcStdDensity(_cruiseP, _cruiseT));
}
stabilizeThrust();
@ -843,8 +836,7 @@ void Airplane::runApproach()
{
setupState(_approachAoA, _approachSpeed,_approachGlideAngle, &_approachState);
_model.setState(&_approachState);
_model.setAir(_approachP, _approachT,
Atmosphere::calcStdDensity(_approachP, _approachT));
_model.setAtmosphere(_approachAtmo);
// The control configuration
loadControls(_approachControls);
@ -860,10 +852,9 @@ void Airplane::runApproach()
// Run the thrusters until they get to a stable setting. FIXME:
// this is lots of wasted work.
for(int i=0; i<_thrusters.size(); i++) {
Thruster* t = ((ThrustRec*)_thrusters.get(i))->thruster;
t->setWind(wind);
t->setAir(_approachP, _approachT,
Atmosphere::calcStdDensity(_approachP, _approachT));
Thruster* t = ((ThrustRec*)_thrusters.get(i))->thruster;
t->setWind(wind);
t->setAir(_approachAtmo);
}
stabilizeThrust();
@ -1108,9 +1099,7 @@ void Airplane::solveHelicopter()
setupWeights(true);
_controls.reset();
_model.getBody()->reset();
_model.setAir(_cruiseP, _cruiseT,
Atmosphere::calcStdDensity(_cruiseP, _cruiseT));
_model.setAtmosphere(_cruiseAtmo);
}
float Airplane::getCGMAC()

View file

@ -126,7 +126,7 @@ private:
struct SolveWeight { bool approach; int idx; float wgt; };
struct ContactRec { Gear* gear; float p[3]; };
void loadControls(Vector &controls);
void loadControls(const Vector& controls);
void runCruise();
void runApproach();
void solveGear();
@ -170,8 +170,7 @@ private:
Vector _cruiseControls;
State _cruiseState;
float _cruiseP;
float _cruiseT;
Atmosphere _cruiseAtmo;
float _cruiseSpeed;
float _cruiseWeight;
float _cruiseFuel;
@ -179,8 +178,7 @@ private:
Vector _approachControls;
State _approachState;
float _approachP;
float _approachT;
Atmosphere _approachAtmo;
float _approachSpeed;
float _approachAoA;
float _approachWeight;

View file

@ -1,7 +1,8 @@
#include <string>
#include "Math.hpp"
#include "Atmosphere.hpp"
namespace yasim {
namespace yasim {
// Copied from McCormick, who got it from "The ARDC Model Atmosphere"
// Note that there's an error in the text in the first entry,
// McCormick lists 299.16/101325/1.22500, but those don't agree with
@ -9,7 +10,7 @@ namespace yasim {
// pretty hot for a "standard" atmosphere.
// Numbers above 19000 meters calculated from src/Environment/environment.cxx
// meters kelvin Pa kg/m^3
float Atmosphere::data[][4] = {{ -900.0f, 293.91f, 111679.0f, 1.32353f },
float Atmosphere::data[][Atmosphere::numColumns] = {{ -900.0f, 293.91f, 111679.0f, 1.32353f },
{ 0.0f, 288.11f, 101325.0f, 1.22500f },
{ 900.0f, 282.31f, 90971.0f, 1.12260f },
{ 1800.0f, 276.46f, 81494.0f, 1.02690f },
@ -48,28 +49,34 @@ float Atmosphere::data[][4] = {{ -900.0f, 293.91f, 111679.0f, 1.32353f },
// Universal gas constant for air, in SI units. P = R * rho * T.
// P in pascals (N/m^2), rho is kg/m^3, T in kelvin.
const float R = 287.1f;
const float R = 287.058f;
// Specific heat ratio for air, at "low" temperatures.
const float GAMMA = 1.4f;
void Atmosphere::setStandard(float altitude)
{
_density = getStdDensity(altitude);
_pressure = getStdPressure(altitude);
_temperature = getStdTemperature(altitude);
}
float Atmosphere::getStdTemperature(float alt)
{
return getRecord(alt, 1);
return getRecord(alt, TEMPERATURE);
}
float Atmosphere::getStdPressure(float alt)
{
return getRecord(alt, 2);
return getRecord(alt, PRESSURE);
}
float Atmosphere::getStdDensity(float alt)
{
return getRecord(alt, 3);
return getRecord(alt, DENSITY);
}
float Atmosphere::calcVEAS(float spd,
float pressure, float temp, float density)
float Atmosphere::calcVEAS(float spd, float pressure, float temp, float density)
{
static float rho0 = getStdDensity(0);
float densityRatio = density / rho0;
@ -122,9 +129,14 @@ float Atmosphere::spdFromMach(float mach, float temp)
return mach * Math::sqrt(GAMMA * R * temp);
}
float Atmosphere::spdFromMach(float mach)
{
return spdFromMach(mach, _temperature);
}
float Atmosphere::spdFromVCAS(float vcas, float pressure, float temp)
{
// FIXME: does not account for supersonic
// FIXME: does not account for supersonic
float p0 = getStdPressure(0);
float rho0 = getStdDensity(0);
@ -136,6 +148,11 @@ float Atmosphere::spdFromVCAS(float vcas, float pressure, float temp)
return vtas;
}
float Atmosphere::spdFromVCAS(float vcas)
{
return spdFromVCAS(vcas, _pressure, _temperature);
}
void Atmosphere::calcStaticAir(float p0, float t0, float d0, float v,
float* pOut, float* tOut, float* dOut)
{
@ -147,14 +164,24 @@ void Atmosphere::calcStaticAir(float p0, float t0, float d0, float v,
*pOut = (*dOut) * R * (*tOut);
}
float Atmosphere::getRecord(float alt, int recNum)
void Atmosphere::calcStaticAir(float v, float* pOut, float* tOut, float* dOut)
{
int hi = (sizeof(data) / (4*sizeof(float))) - 1;
return calcStaticAir(_pressure, _temperature, _density, v, pOut, tOut, dOut);
}
float Atmosphere::getRecord(float alt, Column recNum)
{
int hi = maxTableIndex();
int lo = 0;
// safety valve, clamp to the edges of the table
if(alt < data[0][0]) hi=1;
else if(alt > data[hi][0]) lo = hi-1;
if(alt < data[0][ALTITUDE]) {
hi = 1;
}
else if(alt > data[hi][ALTITUDE]) {
lo = hi-1;
}
// binary search
while(1) {
@ -165,10 +192,38 @@ float Atmosphere::getRecord(float alt, int recNum)
}
// interpolate
float frac = (alt - data[lo][0])/(data[hi][0] - data[lo][0]);
float frac = (alt - data[lo][ALTITUDE])/(data[hi][ALTITUDE] - data[lo][ALTITUDE]);
float a = data[lo][recNum];
float b = data[hi][recNum];
return a + frac * (b-a);
}
int Atmosphere::maxTableIndex() {
return (sizeof(data) / (numColumns * sizeof(float))) - 1;
}
bool Atmosphere::test() {
bool passed = true;
int rows = maxTableIndex() + 1;
const float maxDeviation = 0.0002f;
fprintf(stderr, "Atmosphere::test()\n");
fprintf(stderr, "Columns = %d\n", numColumns);
fprintf(stderr, "Rows = %d\n", rows);
for (int alt = 0; alt < maxTableIndex(); alt++) {
float density = calcStdDensity(data[alt][PRESSURE], data[alt][TEMPERATURE]);
float delta = data[alt][DENSITY] - density;
fprintf(stderr, "%d : %f \n", alt, delta);
if (Math::abs(delta) > maxDeviation) {
passed = false;
fprintf(stderr,"FAIL: Deviation above limit of %1.6f\n", maxDeviation);
}
}
if (passed) {
fprintf(stderr,"Deviation below %1.6f for all rows.\n", maxDeviation);
}
return passed;
}
}; // namespace yasim

View file

@ -3,8 +3,28 @@
namespace yasim {
//constexpr int Atmosphere::numColumns {4};
class Atmosphere {
enum Column {
ALTITUDE,
TEMPERATURE,
PRESSURE,
DENSITY
};
static const int numColumns {4};
public:
void setTemperature(float t) { _temperature = t; }
void setPressure(float p) { _pressure = p; }
void setDensity(float d) { _density = d; }
//set temperature, pressure and density to standard values for given altitude
void setStandard(float altitude);
float getTemperature() const { return _temperature; }
float getPressure() const { return _pressure; }
float getDensity() const { return _density; }
static float getStdTemperature(float alt);
static float getStdPressure(float alt);
static float getStdDensity(float alt);
@ -16,6 +36,8 @@ public:
static float spdFromMach(float mach, float temp);
static float spdFromVCAS(float vcas, float pressure, float temp);
float spdFromMach(float mach);
float spdFromVCAS(float vcas);
// Given ambient ("0") pressure/density/temperature values,
// calculate the properties of static air (air accelerated to the
@ -23,10 +45,17 @@ public:
// compressibility, but not shock effects.
static void calcStaticAir(float p0, float t0, float d0, float v,
float* pOut, float* tOut, float* dOut);
void calcStaticAir(float v, float* pOut, float* tOut, float* dOut);
static bool test();
private:
static float getRecord(float alt, int idx);
static float data[][4];
static float getRecord(float alt, Atmosphere::Column recNum);
static float data[][numColumns];
static int maxTableIndex();
float _temperature = 288.11f;
float _pressure = 101325.0f;
float _density = 1.22500f;
};
}; // namespace yasim

View file

@ -22,7 +22,6 @@ set(COMMON
Rotorpart.cpp
SimpleJet.cpp
Surface.cpp
Thruster.cpp
TurbineEngine.cpp
Turbulence.cpp
Wing.cpp
@ -40,6 +39,7 @@ flightgear_component(YASim "${SOURCES}")
if(ENABLE_TESTS)
add_executable(yasim yasim-test.cpp ${COMMON})
add_executable(yasim-proptest proptest.cpp ${COMMON})
add_executable(yasim-atmotest yasim-atmotest.cpp Atmosphere.cpp )
target_link_libraries(yasim SimGearCore)
target_link_libraries(yasim-proptest SimGearCore)

View file

@ -59,21 +59,6 @@ void Jet::setMaxThrust(float thrust, float afterburner)
}
}
void Jet::setVMax(float spd)
{
_vMax = spd;
}
void Jet::setTSFC(float tsfc)
{
_tsfc = tsfc;
}
void Jet::setATSFC(float atsfc)
{
_atsfc = atsfc;
}
void Jet::setRPMs(float idleN1, float maxN1, float idleN2, float maxN2)
{
_n1Min = idleN1;
@ -82,16 +67,6 @@ void Jet::setRPMs(float idleN1, float maxN1, float idleN2, float maxN2)
_n2Max = maxN2;
}
void Jet::setEGT(float takeoffEGT)
{
_egt0 = takeoffEGT;
}
void Jet::setEPR(float takeoffEPR)
{
_epr0 = takeoffEPR;
}
void Jet::setSpooling(float time)
{
// 2.3 = -ln(0.1), i.e. x=2.3 is the 90% point we're defining
@ -100,11 +75,6 @@ void Jet::setSpooling(float time)
_decay = 1.5f * 2.3f / time;
}
void Jet::setVectorAngle(float angle)
{
_maxRot = angle;
}
void Jet::setReheat(float reheat)
{
_reheat = Math::clamp(reheat, 0, 1);
@ -112,9 +82,7 @@ void Jet::setReheat(float reheat)
void Jet::setRotation(float rot)
{
if(rot < 0) rot = 0;
if(rot > 1) rot = 1;
_rotControl = rot;
_rotControl = Math::clamp(rot, 0, 1);
}
float Jet::getN1()
@ -127,16 +95,12 @@ float Jet::getN2()
return _n2 * _tempCorrect;
}
float Jet::getEPR()
{
return _epr;
}
float Jet::getEGT()
{
// Exactly zero means "off" -- return the ambient temperature
if(_egt == 0) return _temp;
if(_egt == 0) {
return _atmo.getTemperature();
}
return _egt * _tempCorrect * _tempCorrect;
}
@ -155,8 +119,7 @@ void Jet::integrate(float dt)
float spd = -Math::dot3(_wind, _dir);
float statT, statP, statD;
Atmosphere::calcStaticAir(_pressure, _temp, _rho, spd,
&statP, &statT, &statD);
_atmo.calcStaticAir(spd, &statP, &statT, &statD);
_pressureCorrect = statP/P0;
_tempCorrect = Math::sqrt(statT/T0);
@ -175,8 +138,8 @@ void Jet::integrate(float dt)
// Now get a "beta" (i.e. EPR - 1) value. The output values are
// expressed as functions of beta.
float ibeta0 = 1/(_epr0 - 1);
float betaTarget = (_epr0 - 1) * (setThrust/_maxThrust) * (P0/_pressure)
* (_temp/statT);
float betaTarget = (_epr0 - 1) * (setThrust/_maxThrust) * (P0/_atmo.getPressure())
* (_atmo.getTemperature()/statT);
float n2Target = _n2Min + (betaTarget*ibeta0) * (_n2Max - _n2Min);
// Note that this "first" beta value is used to compute a target
@ -191,7 +154,7 @@ void Jet::integrate(float dt)
// The actual thrust produced is keyed to the N1 speed. Add the
// afterburners in at the end.
float betaN1 = (_epr0-1) * (_n1 - _n1Min) / (_n1Max - _n1Min);
_thrust = _maxThrust * betaN1/((_epr0-1)*(P0/_pressure)*(_temp/statT));
_thrust = _maxThrust * betaN1/((_epr0-1)*(P0/_atmo.getPressure())*(_atmo.getTemperature()/statT));
_thrust *= 1 + _reheat*(_abFactor-1);
// Finally, calculate the output variables. Use a 80/20 mix of
@ -214,16 +177,6 @@ void Jet::integrate(float dt)
if(_reverseThrust) _thrust *= -_reverseEff;
}
bool Jet::isRunning()
{
return _running;
}
bool Jet::isCranking()
{
return _cranking;
}
void Jet::getThrust(float* out)
{
Math::mul3(_thrust, _dir, out);
@ -240,13 +193,11 @@ void Jet::getThrust(float* out)
void Jet::getTorque(float* out)
{
out[0] = out[1] = out[2] = 0;
return;
}
void Jet::getGyro(float* out)
{
out[0] = out[1] = out[2] = 0;
return;
}
}; // namespace yasim

View file

@ -12,13 +12,13 @@ public:
virtual Jet* getJet() { return this; }
void setMaxThrust(float thrust, float afterburner=0);
void setVMax(float spd);
void setTSFC(float tsfc);
void setATSFC(float atsfc);
void setVMax(float spd) { _vMax = spd; };
void setTSFC(float tsfc) { _tsfc = tsfc; };
void setATSFC(float atsfc) { _atsfc = atsfc; };
void setRPMs(float idleN1, float maxN1, float idleN2, float maxN2);
void setEGT(float takeoffEGT);
void setEPR(float takeoffEPR);
void setVectorAngle(float angle);
void setEGT(float takeoffEGT) { _egt0 = takeoffEGT; };
void setEPR(float takeoffEPR) { _epr0 = takeoffEPR; };
void setVectorAngle(float angle) { _maxRot = angle; };
// The time it takes the engine to reach 90% thrust from idle
void setSpooling(float time);
@ -37,15 +37,15 @@ public:
float getN1();
float getN2();
float getEPR();
float getEPR() const { return _epr; };
float getEGT();
// Normalized "performance" number. Used for fuzzy numbers in FGFDM
float getPerfNorm() { return (_n1 - _n1Min) / (_n1Max - _n1Min); }
// From Thruster:
virtual bool isRunning();
virtual bool isCranking();
virtual bool isRunning() { return _running; };
virtual bool isCranking() { return _cranking; };
virtual void getThrust(float* out);
virtual void getTorque(float* out);
virtual void getGyro(float* out);

View file

@ -127,7 +127,7 @@ void Model::initIteration()
localWind(pos, _s, v, alt);
t->setWind(v);
t->setAir(_pressure, _temp, _rho);
t->setAir(_atmo);
t->integrate(_integrator.getInterval());
t->getTorque(v);
@ -186,7 +186,7 @@ void Model::iterate()
void Model::setState(State* s)
{
_integrator.setState(s);
_s = _integrator.getState();
_s = s;
}
@ -203,18 +203,9 @@ void Model::setGroundEffect(const float* pos, float span, float mul)
_groundEffect = mul;
}
void Model::setAir(float pressure, float temp, float density)
void Model::setStandardAtmosphere(float altitude)
{
_pressure = pressure;
_temp = temp;
_rho = density;
}
void Model::setAirFromStandardAtmosphere(float altitude)
{
_pressure = Atmosphere::getStdPressure(altitude);
_temp = Atmosphere::getStdTemperature(altitude);
_rho = Atmosphere::getStdDensity(altitude);
_atmo.setStandard(altitude);
}
void Model::updateGround(State* s)
@ -336,7 +327,7 @@ void Model::calcForces(State* s)
localWind(pos, s, vs, alt);
float force[3], torque[3];
sf->calcForce(vs, _rho, force, torque);
sf->calcForce(vs, _atmo.getDensity(), force, torque);
Math::add3(faero, force, faero);
_body.addForce(pos, force);
@ -349,7 +340,7 @@ void Model::calcForces(State* s)
float vs[3], pos[3];
r->getPosition(pos);
localWind(pos, s, vs, alt);
r->calcLiftFactor(vs, _rho,s);
r->calcLiftFactor(vs, _atmo.getDensity(), s);
float tq=0;
// total torque of rotor (scalar) for calculating new rotor rpm
@ -363,7 +354,7 @@ void Model::calcForces(State* s)
localWind(pos, s, vs, alt,true);
float force[3], torque[3];
rp->calcForce(vs, _rho, force, torque, &torque_scalar);
rp->calcForce(vs, _atmo.getDensity(), force, torque, &torque_scalar);
tq+=torque_scalar;
rp->getPositionForceAttac(pos);
@ -486,7 +477,7 @@ void Model::newState(State* s)
// Calculates the airflow direction at the given point and for the
// specified aircraft velocity.
void Model::localWind(const float* pos, yasim::State* s, float* out, float alt, bool is_rotor)
void Model::localWind(const float* pos, const yasim::State* s, float* out, float alt, bool is_rotor)
{
float tmp[3], lwind[3], lrot[3], lv[3];
@ -521,8 +512,6 @@ void Model::localWind(const float* pos, yasim::State* s, float* out, float alt,
_rotorgear.getDownWash(pos,lv,tmp);
Math::add3(out,tmp, out); // + downwash
}
}
}; // namespace yasim

View file

@ -7,6 +7,7 @@
#include "Vector.hpp"
#include "Turbulence.hpp"
#include "Rotor.hpp"
#include "Atmosphere.hpp"
#include <simgear/props/props.hxx>
namespace yasim {
@ -68,8 +69,8 @@ public:
//
void setGroundEffect(const float* pos, float span, float mul);
void setWind(float* wind) { Math::set3(wind, _wind); }
void setAir(float pressure, float temp, float density);
void setAirFromStandardAtmosphere(float altitude);
void setAtmosphere(Atmosphere a) { _atmo = a; };
void setStandardAtmosphere(float altitude);
void updateGround(State* s);
@ -81,7 +82,7 @@ private:
void initRotorIteration();
void calcGearForce(Gear* g, float* v, float* rot, float* ground);
float gearFriction(float wgt, float v, Gear* g);
void localWind(const float* pos, State* s, float* out, float alt, bool is_rotor = false);
void localWind(const float* pos, const yasim::State* s, float* out, float alt, bool is_rotor = false);
Integrator _integrator;
RigidBody _body;
@ -102,10 +103,9 @@ private:
Ground* _ground_cb;
double _global_ground[4];
float _pressure;
float _temp;
float _rho;
Atmosphere _atmo;
float _wind[3];
// Accumulators for the total internal gyro and engine torque
float _gyro[3];

View file

@ -123,8 +123,8 @@ void PropEngine::stabilize()
// If we cannot manage this in 100 iterations, give up.
for (int n = 0; n < 100; n++) {
float ptau, thrust;
_prop->calc(_rho, speed, _omega * _gearRatio, &thrust, &ptau);
_eng->calc(_pressure, _temp, _omega);
_prop->calc(_atmo.getDensity(), speed, _omega * _gearRatio, &thrust, &ptau);
_eng->calc(_atmo.getPressure(), _atmo.getTemperature(), _omega);
_eng->stabilize();
// Do it again -- the turbo sets the target MP in the first
@ -133,7 +133,7 @@ void PropEngine::stabilize()
// it works without side effects (other than solver
// performance). In the future, the Engine objects should
// store state to allow them to do the work themselves.
_eng->calc(_pressure, _temp, _omega);
_eng->calc(_atmo.getPressure(), _atmo.getTemperature(), _omega);
// Compute torque as seen by the engine's end of the gearbox.
// The propeller will be moving more slowly (for gear ratios
@ -185,11 +185,11 @@ void PropEngine::integrate(float dt)
_eng->setMixture(_mixture);
_eng->setFuelState(_fuel);
_prop->calc(_rho, speed, _omega * _gearRatio, &thrust, &propTorque);
_prop->calc(_atmo.getDensity(), speed, _omega * _gearRatio, &thrust, &propTorque);
if(_omega == 0.0)
_omega = 0.001; // hack to get around reports of NaNs somewhere...
propTorque *= _gearRatio;
_eng->calc(_pressure, _temp, _omega);
_eng->calc(_atmo.getPressure(), _atmo.getTemperature(), _omega);
_eng->integrate(dt);
engTorque = _eng->getTorque();
_fuelFlow = _eng->getFuelFlow();

View file

@ -1,27 +0,0 @@
#include "Math.hpp"
#include "Thruster.hpp"
namespace yasim {
Thruster::Thruster()
{
_dir[0] = 1; _dir[1] = 0; _dir[2] = 0;
int i;
for(i=0; i<3; i++) _pos[i] = _wind[i] = 0;
_throttle = 0;
_mixture = 0;
_starter = false;
_pressure = _temp = _rho = 0;
}
Thruster::~Thruster()
{
}
void Thruster::setAir(float pressure, float temp, float density)
{
_pressure = pressure;
_temp = temp;
_rho = density;
}
}; // namespace yasim

View file

@ -1,5 +1,7 @@
#ifndef _THRUSTER_HPP
#define _THRUSTER_HPP
#include "Atmosphere.hpp"
#include "Math.hpp"
namespace yasim {
@ -11,8 +13,8 @@ class Engine;
class Thruster {
public:
Thruster();
virtual ~Thruster();
Thruster() {};
virtual ~Thruster() {};
// Typing info, these are the possible sub-type (or sub-parts)
// that a thruster might have. Any might return null. A little
@ -44,25 +46,22 @@ public:
// Runtime instructions
void setWind(const float* wind) { Math::set3(wind, _wind); };
void setAir(float pressure, float temp, float density);
void setAir(Atmosphere a) { _atmo = a; };
virtual void init() {}
virtual void integrate(float dt)=0;
virtual void stabilize()=0;
protected:
float _pos[3];
float _dir[3];
float _throttle;
float _mixture;
bool _starter; // true=engaged, false=disengaged
float _pos[3] {0, 0, 0};
float _dir[3] {1, 0, 0};
float _throttle = 0;
float _mixture = 0;
bool _starter = false; // true=engaged, false=disengaged
bool _fuel; // true=available, false=out
float _wind[3];
float _pressure;
float _temp;
float _rho;
float _wind[3] {0, 0, 0};
Atmosphere _atmo;
};
}; // namespace yasim
#endif // _THRUSTER_HPP

View file

@ -312,7 +312,11 @@ void YASim::copyToYASim(bool copyState)
float temp = _temp_degc->getFloatValue() + 273.15;
float dens = _density_slugft3->getFloatValue() *
SLUG2KG * M2FT*M2FT*M2FT;
Atmosphere atmo;
atmo.setDensity(dens);
atmo.setTemperature(temp);
atmo.setPressure(pressure);
// Convert and set:
Model* model = _fdm->getAirplane()->getModel();
State s;
@ -332,7 +336,7 @@ void YASim::copyToYASim(bool copyState)
Math::mmul33(s.orient, xyz2ned, s.orient);
// Velocity
float v[3];
float v[3] {0, 0, 0};
bool needCopy = false;
switch (_speed_set) {
case NED:
@ -347,15 +351,14 @@ void YASim::copyToYASim(bool copyState)
Math::tmul33(s.orient, v, v);
break;
case KNOTS:
v[0] = Atmosphere::spdFromVCAS(get_V_calibrated_kts()/MPS2KTS,
pressure, temp);
v[0] = atmo.spdFromVCAS(get_V_calibrated_kts()/MPS2KTS);
v[1] = 0;
v[2] = 0;
Math::tmul33(s.orient, v, v);
needCopy = true;
break;
case MACH:
v[0] = Atmosphere::spdFromMach(get_Mach_number(), temp);
v[0] = atmo.spdFromMach(get_Mach_number());
v[1] = 0;
v[2] = 0;
Math::tmul33(s.orient, v, v);
@ -374,20 +377,18 @@ void YASim::copyToYASim(bool copyState)
if(copyState || needCopy)
model->setState(&s);
// wind
Math::tmul33(xyz2ned, wind, wind);
model->setWind(wind);
// air
model->setAir(pressure, temp, dens);
model->setAtmosphere(atmo);
// Query a ground plane for each gear/hook/launchbar and
// write that value into the corresponding class.
_fdm->getAirplane()->getModel()->updateGround(&s);
Launchbar* l = model->getLaunchbar();
if (l)
if (l) {
l->setLaunchCmd(0.0 < _catapult_launch_cmd->getFloatValue());
}
}
// All the settables:

View file

@ -71,9 +71,9 @@ int main(int argc, char** argv)
eng->setBoost(1);
float alt = (argc > 2 ? atof(argv[2]) : 0) * FT2M;
pe->setAir(Atmosphere::getStdPressure(alt),
Atmosphere::getStdTemperature(alt),
Atmosphere::getStdDensity(alt));
Atmosphere atmo;
atmo.setStandard(alt);
pe->setAir(atmo);
float speed = (argc > 3 ? atof(argv[3]) : 0) * KTS2MPS;
float wind[3];

View file

@ -0,0 +1,12 @@
#include "Atmosphere.hpp"
using namespace yasim;
int main(int argc, char** argv)
{
Atmosphere a;
if (a.test()) {
return 0;
}
return 1;
}

View file

@ -54,7 +54,7 @@ void yasim_graph(Airplane* a, const float alt, const float kts, int cfg = CONFIG
Model* m = a->getModel();
State s;
m->setAirFromStandardAtmosphere(alt);
m->setStandardAtmosphere(alt);
switch (cfg) {
case CONFIG_APPROACH:
@ -129,7 +129,7 @@ void yasim_drag(Airplane* a, const float aoa, const float alt, int cfg = CONFIG_
Model* m = a->getModel();
State s;
m->setAirFromStandardAtmosphere(alt);
m->setStandardAtmosphere(alt);
switch (cfg) {
case CONFIG_APPROACH:
@ -254,11 +254,11 @@ int main(int argc, char** argv)
float MACy = a->getWing()->getMACy();
printf(" Iterations: %d\n", a->getSolutionIterations());
printf(" Drag Coefficient: %f\n", drag);
printf(" Lift Ratio: %f\n", a->getLiftRatio());
printf(" Cruise AoA: %f deg\n", aoa);
printf(" Tail Incidence: %f deg\n", tail);
printf("Approach Elevator: %f\n\n", a->getApproachElevator());
printf(" Drag Coefficient: %.3f\n", drag);
printf(" Lift Ratio: %.3f\n", a->getLiftRatio());
printf(" Cruise AoA: %.2f deg\n", aoa);
printf(" Tail Incidence: %.2f deg\n", tail);
printf("Approach Elevator: %.3f\n\n", a->getApproachElevator());
printf(" CG: x:%.3f, y:%.3f, z:%.3f\n", cg[0], cg[1], cg[2]);
printf(" Wing MAC (*1): x:%.2f, y:%.2f, length:%.1f \n", MACx, MACy, MAC);
printf(" CG-x rel. MAC: %.3f\n", a->getCGMAC());