#include <FDM/JSBSim/FGAuxiliary.h>
#include <FDM/JSBSim/FGDefs.h>
#include <FDM/JSBSim/FGInitialCondition.h>
+#include <FDM/JSBSim/FGTrim.h>
#include <FDM/JSBSim/FGAtmosphere.h>
#include "JSBSim.hxx"
FDMExec.GetAtmosphere()->SetWindNED(get_V_north_airmass(),
get_V_east_airmass(),
get_V_down_airmass());
-
+
FDMExec.GetAtmosphere()->UseInternal();
+
+
+ FDMExec.GetPosition()->SetRunwayRadius(scenery.cur_radius*METER_TO_FEET);
+ FDMExec.GetPosition()->SetSeaLevelRadius(get_Sea_level_radius());
FG_LOG( FG_FLIGHT, FG_INFO, " Initializing JSBSim with:" );
-
+
FGInitialCondition *fgic = new FGInitialCondition(&FDMExec);
- fgic->SetAltitudeFtIC(get_Altitude());
+ fgic->SetAltitudeAGLFtIC(get_Altitude());
if((current_options.get_mach() < 0) && (current_options.get_vc() < 0 )) {
fgic->SetUBodyFpsIC(current_options.get_uBody());
fgic->SetVBodyFpsIC(current_options.get_vBody());
//current_options.get_vc() will return zero by default
}
-
+ //fgic->SetFlightPathAngleDegIC(current_options.get_Gamma());
fgic->SetRollAngleRadIC(get_Phi());
fgic->SetPitchAngleRadIC(get_Theta());
fgic->SetHeadingRadIC(get_Psi());
-// fgic->SetLatitudeRadIC(get_Latitude());
fgic->SetLatitudeRadIC(get_Lat_geocentric());
fgic->SetLongitudeRadIC(get_Longitude());
- FDMExec.GetPosition()->SetRunwayRadius(scenery.cur_radius*METER_TO_FEET);
- FDMExec.GetPosition()->SetSeaLevelRadius(get_Sea_level_radius());
- FDMExec.GetPosition()->SetRunwayNormal( scenery.cur_normal[0],
- scenery.cur_normal[1],
- scenery.cur_normal[2] );
-
+
+
+
+ //FG_LOG( FG_FLIGHT, FG_INFO, " gamma: " << current_options.get_Gamma());
FG_LOG( FG_FLIGHT, FG_INFO, " phi: " << get_Phi());
- FG_LOG( FG_FLIGHT, FG_INFO, " theta: " << get_Theta() );
+ //FG_LOG( FG_FLIGHT, FG_INFO, " theta: " << get_Theta() );
FG_LOG( FG_FLIGHT, FG_INFO, " psi: " << get_Psi() );
FG_LOG( FG_FLIGHT, FG_INFO, " lat: " << get_Latitude() );
FG_LOG( FG_FLIGHT, FG_INFO, " lon: " << get_Longitude() );
- FG_LOG( FG_FLIGHT, FG_INFO, " alt: " << get_Altitude() );
-
+
+ FG_LOG( FG_FLIGHT, FG_INFO, " Pressure Altiude: " << get_Altitude() );
+ FG_LOG( FG_FLIGHT, FG_INFO, " Terrain Altitude: "
+ << scenery.cur_radius*METER_TO_FEET );
+ FG_LOG( FG_FLIGHT, FG_INFO, " AGL Altitude: "
+ << get_Altitude() + get_Sea_level_radius()
+ - scenery.cur_radius*METER_TO_FEET );
+
+ FG_LOG( FG_FLIGHT, FG_INFO, " current_options.get_altitude(): "
+ << current_options.get_altitude() );
//must check > 0, != 0 will give bad result if --notrim set
if(current_options.get_trim_mode() > 0) {
FDMExec.RunIC(fgic);
FG_LOG( FG_FLIGHT, FG_INFO, " Starting trim..." );
-// FGTrimLong *fgtrim=new FGTrimLong(&FDMExec,fgic);
-// fgtrim->DoTrim();
-// fgtrim->Report();
-// fgtrim->TrimStats();
-// fgtrim->ReportState();
+ FGTrim *fgtrim=new FGTrim(&FDMExec,fgic,tLongitudinal);
+ fgtrim->DoTrim();
+ fgtrim->Report();
+ fgtrim->TrimStats();
+ fgtrim->ReportState();
+
controls.set_elevator_trim(FDMExec.GetFCS()->GetPitchTrimCmd());
controls.set_throttle(FGControls::ALL_ENGINES,FDMExec.GetFCS()->GetThrottleCmd(0)/100);
double save_alt = 0.0;
double time_step = (1.0 / current_options.get_model_hz()) * multiloop;
double start_elev = get_Altitude();
-
+
+
// lets try to avoid really screwing up the JSBsim model
if ( get_Altitude() < -9000 ) {
save_alt = get_Altitude();
set_Altitude( 0.0 );
}
- // copy control positions into the JSBsim structure
-
- FDMExec.GetFCS()->SetDaCmd( controls.get_aileron());
- FDMExec.GetFCS()->SetDeCmd( controls.get_elevator());
- FDMExec.GetFCS()->SetPitchTrimCmd(controls.get_elevator_trim());
- FDMExec.GetFCS()->SetDrCmd( controls.get_rudder());
- FDMExec.GetFCS()->SetDfCmd( controls.get_flaps() );
- FDMExec.GetFCS()->SetDsbCmd( 0.0 ); //speedbrakes
- FDMExec.GetFCS()->SetDspCmd( 0.0 ); //spoilers
- FDMExec.GetFCS()->SetThrottleCmd( FGControls::ALL_ENGINES,
- controls.get_throttle( 0 ) * 100.0 );
-
- // FCS->SetBrake( controls.get_brake( 0 ) );
-
- // Inform JSBsim of the local terrain altitude; uncommented 5/3/00
- // FDMExec.GetPosition()->SetRunwayElevation(get_Runway_altitude()); // seems to work
- FDMExec.GetPosition()->SetRunwayRadius(scenery.cur_radius*METER_TO_FEET);
- FDMExec.GetPosition()->SetSeaLevelRadius(get_Sea_level_radius());
- FDMExec.GetPosition()->SetRunwayNormal( scenery.cur_normal[0],
- scenery.cur_normal[1],
- scenery.cur_normal[2] );
-
- FDMExec.GetAtmosphere()->SetExTemperature(get_Static_temperature());
- FDMExec.GetAtmosphere()->SetExPressure(get_Static_pressure());
- FDMExec.GetAtmosphere()->SetExDensity(get_Density());
- FDMExec.GetAtmosphere()->SetWindNED(get_V_north_airmass(),
- get_V_east_airmass(),
- get_V_down_airmass());
+ copy_to_JSBsim();
for ( int i = 0; i < multiloop; i++ ) {
FDMExec.Run();
}
double end_elev = get_Altitude();
- //if ( time_step > 0.0 ) {
- // feet per second
- // set_Climb_Rate( (end_elev - start_elev) / time_step );
- //}
return 1;
}
// Convert from the FGInterface struct to the JSBsim generic_ struct
int FGJSBsim::copy_to_JSBsim() {
+ // copy control positions into the JSBsim structure
+
+ FDMExec.GetFCS()->SetDaCmd( controls.get_aileron());
+ FDMExec.GetFCS()->SetDeCmd( controls.get_elevator());
+ FDMExec.GetFCS()->SetPitchTrimCmd(controls.get_elevator_trim());
+ FDMExec.GetFCS()->SetDrCmd( controls.get_rudder());
+ FDMExec.GetFCS()->SetDfCmd( controls.get_flaps() );
+ FDMExec.GetFCS()->SetDsbCmd( 0.0 ); //speedbrakes
+ FDMExec.GetFCS()->SetDspCmd( 0.0 ); //spoilers
+ FDMExec.GetFCS()->SetThrottleCmd( FGControls::ALL_ENGINES,
+ controls.get_throttle( 0 ) * 100.0 );
+
+ FDMExec.GetFCS()->SetLBrake( controls.get_brake( 0 ) );
+ FDMExec.GetFCS()->SetRBrake( controls.get_brake( 1 ) );
+ FDMExec.GetFCS()->SetCBrake( controls.get_brake( 2 ) );
+
+ // Inform JSBsim of the local terrain altitude; uncommented 5/3/00
+ // FDMExec.GetPosition()->SetRunwayElevation(get_Runway_altitude()); // seems to work
+ FDMExec.GetPosition()->SetRunwayRadius(scenery.cur_radius*METER_TO_FEET);
+ FDMExec.GetPosition()->SetSeaLevelRadius(get_Sea_level_radius());
+
+ FDMExec.GetAtmosphere()->SetExTemperature(get_Static_temperature());
+ FDMExec.GetAtmosphere()->SetExPressure(get_Static_pressure());
+ FDMExec.GetAtmosphere()->SetExDensity(get_Density());
+ FDMExec.GetAtmosphere()->SetWindNED(get_V_north_airmass(),
+ get_V_east_airmass(),
+ get_V_down_airmass());
+
return 1;
}
FDMExec.GetState()->GetParameter(FG_PITCHRATE),
FDMExec.GetState()->GetParameter(FG_YAWRATE) );
- /* HUH!?! */ set_Euler_Rates( FDMExec.GetRotation()->Getphi(),
- FDMExec.GetRotation()->Gettht(),
- FDMExec.GetRotation()->Getpsi() );
+ set_Euler_Rates( FDMExec.GetRotation()->GetEulerRates()(2),
+ FDMExec.GetRotation()->GetEulerRates()(1),
+ FDMExec.GetRotation()->GetEulerRates()(3));
// ***FIXME*** set_Geocentric_Rates( Latitude_dot, Longitude_dot, Radius_dot );
FGAircraft::~FGAircraft(void) {
unsigned int i,j;
+
cout << " ~FGAircraft" << endl;
- if(Engine != NULL) {
- for(i=0;i<numEngines; i++)
+ if (Engine != NULL) {
+ for (i=0; i<numEngines; i++)
delete Engine[i];
}
cout << " Engine" << endl;
- if(Tank != NULL) {
- for(i=0;i<numTanks; i++)
+
+ if (Tank != NULL) {
+ for (i=0; i<numTanks; i++)
delete Tank[i];
}
cout << " Tank" << endl;
+
cout << " NumAxes: " << 6 << endl;
- for(i=0;i<6;i++) {
+ for (i=0; i<6; i++) {
cout << " NumCoeffs: " << Coeff[i].size() << " " << &Coeff[i] << endl;
- for(j=0;j<Coeff[i].size();j++) {
+ for (j=0; j<Coeff[i].size(); j++) {
cout << " Coeff[" << i << "][" << j << "]: " << Coeff[i][j] << endl;
delete Coeff[i][j];
}
- }
+ }
+
delete[] Coeff;
cout << " Coeffs" << endl;
- for(i=0;i<lGear.size();i++) {
+
+ for (i=0; i<lGear.size(); i++) {
delete lGear[i];
}
}
if (GearUp) {
// crash routine
} else {
+
+// iGear = lGear.begin();
+// while (iGear != lGear.end()) {
+// vForces += iGear->Force();
+// vMoments += iGear->Moment();
+// iGear++;
+// }
+
for (unsigned int i=0;i<lGear.size();i++) {
vForces += lGear[i]->Force();
vMoments += lGear[i]->Moment();
# include <simgear/compiler.h>
# ifdef FG_HAVE_STD_INCLUDES
# include <vector>
+# include <iterator>
# include <map>
# else
# include <vector.h>
+# include <iterator.h>
# include <map.h>
# endif
#else
# include <vector>
+# include <iterator>
# include <map>
#endif
string GetGroundReactionStrings(void);
string GetGroundReactionValues(void);
+ vector <FGLGear>::iterator iGear;
+
enum { ssSimulation = 1,
ssAerosurfaces = 2,
ssRates = 4,
string Axis[6];
vector <FGLGear*> lGear;
+
string AircraftPath;
string EnginePath;
void ReadMetrics(FGConfigFile*);
// $Log$
-// Revision 1.15 2000/10/02 21:07:31 curt
-// Oct 2, 2000 JSBSim sync.
+// Revision 1.16 2000/10/09 19:16:22 curt
+// Oct. 9, 2000 - synced with latest JSBsim code.
//
// Revision 1.3 2000/04/26 10:55:57 jsb
// Made changes as required by Curt to install JSBSim into FGFS
// $Log$
-// Revision 1.14 2000/10/02 21:07:31 curt
-// Oct 2, 2000 JSBSim sync.
+// Revision 1.15 2000/10/09 19:16:22 curt
+// Oct. 9, 2000 - synced with latest JSBsim code.
//
// Revision 1.6 2000/06/03 13:59:52 jsb
// Changes for compatibility with MSVC
#define FPSTOKTS 0.592484
#define INCHTOFT 0.08333333
#define OMEGA_EARTH .00007272205217
-#define NEEDED_CFG_VERSION "1.30"
+#define NEEDED_CFG_VERSION "1.35"
#define HPTOFTLBSSEC 550
#define METERS_TO_FEET 3.2808
enum eParam {
- FG_NOTHING = 0,
+ FG_UNDEF = 0,
FG_QBAR,
FG_WINGAREA,
FG_WINGSPAN,
FGFCS::FGFCS(FGFDMExec* fdmex) : FGModel(fdmex) {
Name = "FGFCS";
- for (int i=0; i < MAX_ENGINES; i++) {
+ for (int i=0; i < MAX_ENGINES; i++) { // needs to be changed: no limit
ThrottleCmd[i] = 0.0;
ThrottlePos[i] = 0.0;
}
/******************************************************************************/
+void FGFCS::SetLBrake(float setting) {
+
+}
+
+/******************************************************************************/
+
+void FGFCS::SetRBrake(float setting) {
+}
+
+/******************************************************************************/
+void FGFCS::SetCBrake(float setting) {
+}
+
+/******************************************************************************/
bool FGFCS::LoadFCS(FGConfigFile* AC_cfg) {
string token;
float DaCmd, DeCmd, DrCmd, DfCmd, DsbCmd, DspCmd;
float DaPos, DePos, DrPos, DfPos, DsbPos, DspPos;
float PTrimCmd;
- float ThrottleCmd[MAX_ENGINES];
- float ThrottlePos[MAX_ENGINES];
+ float ThrottleCmd[MAX_ENGINES]; // Needs to be changed: no limit
+ float ThrottlePos[MAX_ENGINES]; // Needs to be changed: no limit
vector <FGFCSComponent*> Components;
inline void SetDsbPos(float tt) { DsbPos = tt; }
inline void SetDspPos(float tt) { DspPos = tt; }
+ void SetLBrake(float);
+ void SetRBrake(float);
+ void SetCBrake(float);
void SetThrottlePos(int ii, float tt);
FGFDMExec::~FGFDMExec(void){
- cout << "~FGFDMExec" << endl;
if ( Atmosphere != NULL ) delete Atmosphere;
- cout << "Atmosphere" << endl;
if ( FCS != NULL ) delete FCS;
- cout << "FCS" << endl;
if ( Aircraft != NULL ) delete Aircraft;
- cout << "Aircraft" << endl;
if ( Translation != NULL ) delete Translation;
- cout << "Translation" << endl;
if ( Rotation != NULL ) delete Rotation;
- cout << "Rotation" << endl;
if ( Position != NULL ) delete Position;
- cout << "Position" << endl;
if ( Auxiliary != NULL ) delete Auxiliary;
- cout << "Auxiliary" << endl;
if ( Output != NULL ) delete Output;
- cout << "Output" << endl;
if ( State != NULL ) delete State;
- cout << "State" << endl;
}
#endif
#include "FGModel.h"
+#include "FGConfigFile.h"
/*******************************************************************************
CLASS DECLARATION
theta=phi=psi=0;
altitude=hdot=0;
latitude=longitude=0;
- u=v=w=0;
+ u=v=w=0;
+ vnorth=veast=vdown=0;
lastSpeedSet=setvt;
if(FDMExec != NULL ) {
fdmex=FDMExec;
fdmex->GetPosition()->Seth(altitude);
fdmex->GetAtmosphere()->Run();
} else {
- cout << "FGInitialCondition: This class requires a pointer to an valid FGFDMExec object" << endl;
+ cout << "FGInitialCondition: This class requires a pointer to a valid FGFDMExec object" << endl;
}
}
//cout << "Vt: " << vt*FPSTOKTS << " Vc: " << vc*FPSTOKTS << endl;
}
-
-
void FGInitialCondition::SetClimbRateFpmIC(float tt) {
+ SetClimbRateFpsIC(tt/60.0);
+}
+
+void FGInitialCondition::SetClimbRateFpsIC(float tt) {
if(vt > 0.1) {
- hdot=tt/60;
+ hdot=tt;
gamma=asin(hdot/vt);
}
}
}
-
void FGInitialCondition::SetVBodyFpsIC(float tt) {
v=tt;
vt=sqrt(u*u+v*v+w*w);
fdmex->GetPosition()->SetDistanceAGL(tt);
altitude=fdmex->GetPosition()->Geth();
SetAltitudeFtIC(altitude);
-}
+}
+
+void FGInitialCondition::calcUVWfromNED(void) {
+ u=vnorth*cos(theta)*cos(psi) +
+ veast*cos(theta)*sin(psi) -
+ vdown*sin(theta);
+ v=vnorth*(sin(phi)*sin(theta)*cos(psi) - cos(phi)*sin(psi)) +
+ veast*(sin(phi)*sin(theta)*sin(psi) + cos(phi)*cos(psi)) +
+ vdown*sin(phi)*cos(theta);
+ w=vnorth*(cos(phi)*sin(theta)*cos(psi) + sin(phi)*sin(psi)) +
+ veast*(cos(phi)*sin(theta)*sin(psi) - sin(phi)*cos(psi)) +
+ vdown*cos(phi)*cos(theta);
+}
+
+void FGInitialCondition::SetVnorthFpsIC(float tt) {
+ vnorth=tt;
+ calcUVWfromNED();
+ vt=sqrt(u*u + v*v + w*w);
+ lastSpeedSet=setvt;
+}
+
+void FGInitialCondition::SetVeastFpsIC(float tt) {
+ veast=tt;
+ calcUVWfromNED();
+ vt=sqrt(u*u + v*v + w*w);
+ lastSpeedSet=setvt;
+}
+
+void FGInitialCondition::SetVdownFpsIC(float tt) {
+ vdown=tt;
+ calcUVWfromNED();
+ vt=sqrt(u*u + v*v + w*w);
+ SetClimbRateFpsIC(-1*vdown);
+ lastSpeedSet=setvt;
+}
bool FGInitialCondition::getMachFromVcas(float *Mach,float vcas) {
Alpha,Gamma, and Theta:
This class assumes that it will be used to set up the sim for a
- steady, zero pitch rate condition. This entails the assumption
- that alpha=theta-gamma. Since any two of those angles specifies
- the third (again, for zero pitch rate) gamma (flight path angle)
- is favored when setting alpha and theta and alpha is favored when
- setting gamma. i.e.
- set alpha : recalculate theta using gamma as currently set
+ steady, zero pitch rate condition. Since any two of those angles
+ specifies the third gamma (flight path angle) is favored when setting
+ alpha and theta and alpha is favored when setting gamma. i.e.
+ set alpha : recalculate theta using gamma as currently set
set theta : recalculate alpha using gamma as currently set
set gamma : recalculate theta using alpha as currently set
void SetUBodyFpsIC(float tt);
void SetVBodyFpsIC(float tt);
void SetWBodyFpsIC(float tt);
-
+
+ void SetVnorthFpsIC(float tt);
+ void SetVeastFpsIC(float tt);
+ void SetVdownFpsIC(float tt);
+
void SetAltitudeFtIC(float tt);
void SetAltitudeAGLFtIC(float tt);
void SetFlightPathAngleRadIC(float tt);
//set speed first
void SetClimbRateFpmIC(float tt);
+ void SetClimbRateFpsIC(float tt);
//use currently stored gamma, recalcualte theta
inline void SetAlphaDegIC(float tt) { alpha=tt*DEGTORAD; getTheta(); }
inline void SetAlphaRadIC(float tt) { alpha=tt; getTheta(); }
float altitude,hdot;
float latitude,longitude;
float u,v,w;
+ float vnorth,veast,vdown;
float xlo, xhi,xmin,xmax;
float GammaEqOfTheta(float Theta);
float GammaEqOfAlpha(float Alpha);
float calcVcas(float Mach);
+ void calcUVWfromNED(void);
bool findInterval(float x,float guess);
bool solve(float *y, float x);
{
string tmp;
*AC_cfg >> tmp >> name >> vXYZ(1) >> vXYZ(2) >> vXYZ(3)
- >> kSpring >> bDamp >> statFCoeff >> brakeCoeff;
-
-
+ >> kSpring >> bDamp>> dynamicFCoeff >> staticFCoeff
+ >> SteerType >> BrakeType >> GroupMember >> maxSteerAngle;
+
cout << " Name: " << name << endl;
cout << " Location: " << vXYZ << endl;
- cout << " Spring Constant: " << kSpring << endl;
+ cout << " Spring Constant: " << kSpring << endl;
cout << " Damping Constant: " << bDamp << endl;
- cout << " Rolling Resistance: " << statFCoeff << endl;
- cout << " Braking Coeff: " << brakeCoeff << endl;
+ cout << " Dynamic Friction: " << dynamicFCoeff << endl;
+ cout << " Static Friction: " << staticFCoeff << endl;
+ cout << " Brake Type: " << BrakeType << endl;
+ cout << " Grouping: " << GroupMember << endl;
+ cout << " Steering Type: " << SteerType << endl;
+ cout << " Max Steer Angle: " << maxSteerAngle << endl;
State = Exec->GetState();
Aircraft = Exec->GetAircraft();
Position = Exec->GetPosition();
Rotation = Exec->GetRotation();
-
WOW = false;
ReportEnable=true;
FirstContact = false;
GroundSpeed = Position->GetVel().Magnitude();
}
+ // The following code normalizes the wheel velocity vector, reverses it, and zeroes out
+ // the z component of the velocity. The question is, should the Z axis velocity be zeroed
+ // out first before the normalization takes place or not? Subsequent to that, the Wheel
+ // Velocity vector now points as a unit vector backwards and parallel to the wheel
+ // velocity vector. It acts AT the wheel.
+
vWhlVelVec = -1.0 * vWhlVelVec.Normalize();
vWhlVelVec(eZ) = 0.00;
+// the following needs work regarding friction coefficients and braking and steering
+
vLocalForce(eZ) = min(-compressLength * kSpring - compressSpeed * bDamp, (float)0.0);
- vLocalForce(eX) = fabs(vLocalForce(eZ) * statFCoeff) * vWhlVelVec(eX);
- vLocalForce(eY) = fabs(vLocalForce(eZ) * statFCoeff) * vWhlVelVec(eY);
+ vLocalForce(eX) = fabs(vLocalForce(eZ) * staticFCoeff) * vWhlVelVec(eX);
+ vLocalForce(eY) = fabs(vLocalForce(eZ) * staticFCoeff) * vWhlVelVec(eY);
MaximumStrutForce = max(MaximumStrutForce, fabs(vLocalForce(eZ)));
MaximumStrutTravel = max(MaximumStrutTravel, fabs(compressLength));
cout << " Force: " << vForce << endl;
cout << " Moment: " << vMoment << endl;
-
} else {
WOW = false;
inline float GetCompVel(void) {return compressSpeed; }
inline float GetCompForce(void) {return Force()(3); }
+ inline void SetBrake(double bp) {brakePct = bp;}
+
inline void SetReport(bool bb) { ReportEnable=bb; }
inline bool GetReport(void) { return ReportEnable; }
FGColumnVector vXYZ;
FGColumnVector vMoment;
FGColumnVector vWhlBodyVec;
- float kSpring, bDamp, compressLength, compressSpeed;
- float statFCoeff, rollFCoeff, skidFCoeff;
- float frictionForce, compForce;
- float brakePct, brakeForce, brakeCoeff;
+ float kSpring;
+ float bDamp;
+ float compressLength;
+ float compressSpeed;
+ float staticFCoeff, dynamicFCoeff;
+ float brakePct;
float maxCompLen;
double SinkRate;
double GroundSpeed;
bool Reported;
bool ReportEnable;
string name;
+ string BrakeType;
+ string SteerType;
+ string GroupMember;
+ float maxSteerAngle;
FGFDMExec* Exec;
FGState* State;
*******************************************************************************/
-FGMassBalance::FGMassBalance() : FGModel()
+FGMassBalance::FGMassBalance(FGFDMExec* fdmex) : FGModel(fdmex)
{
//
}
{
public:
- FGMassBalance();
+ FGMassBalance(FGFDMExec*);
~FGMassBalance();
bool Run(void);
*******************************************************************************/
-FGPiston::FGPiston() : FGEngine()
+FGPiston::FGPiston(FGFDMExec* fdex, string enginePath, string engineName, int num) :
+ FGEngine(fdex, enginePath, engineName, num)
{
//
}
{
public:
- FGPiston();
+ FGPiston(FGFDMExec*, string, string, int);
~FGPiston();
};
*******************************************************************************/
-FGRocket::FGRocket() : FGEngine()
+FGRocket::FGRocket(FGFDMExec* fdex, string enginePath, string engineName, int num) :
+ FGEngine(fdex, enginePath, engineName, num)
{
//
}
{
public:
- FGRocket();
+ FGRocket(FGFDMExec*, string, string, int);
~FGRocket();
};
sprintf(gear,"Down");
sprintf(out, " Flaps: %3s Gear: %4s\n",flap,gear);
cout << out;
- sprintf(out, " Speed: %4.0f KCAS Mach: %5.2f Altitude: %7.0f ft.\n",
+ sprintf(out, " Speed: %4.0f KCAS Mach: %5.2f\n",
fdmex->GetAuxiliary()->GetVcalibratedKTS(),
fdmex->GetState()->GetParameter(FG_MACH),
fdmex->GetPosition()->Geth() );
cout << out;
+ sprintf(out, " Altitude: %7.0f ft. AGL Altitude: %7.0f ft.\n",
+ fdmex->GetPosition()->Geth(),
+ fdmex->GetPosition()->GetDistanceAGL() );
+ cout << out;
sprintf(out, " Angle of Attack: %6.2f deg Pitch Angle: %6.2f deg\n",
fdmex->GetState()->GetParameter(FG_ALPHA)*RADTODEG,
fdmex->GetRotation()->Gettht()*RADTODEG );
*******************************************************************************/
-FGTurboJet::FGTurboJet() : FGEngine()
+FGTurboJet::FGTurboJet(FGFDMExec* fdex, string enginePath, string engineName, int num) :
+ FGEngine(fdex, enginePath, engineName, num)
{
//
}
{
public:
- FGTurboJet();
+ FGTurboJet(FGFDMExec*, string, string, int);
~FGTurboJet();
};
*******************************************************************************/
-FGTurboShaft::FGTurboShaft() : FGEngine()
+FGTurboShaft::FGTurboShaft(FGFDMExec* fdex, string enginePath, string engineName, int num) :
+ FGEngine(fdex, enginePath, engineName, num)
{
//
}
{
public:
- FGTurboShaft();
+ FGTurboShaft(FGFDMExec*, string, string, int);
~FGTurboShaft();
};
USEUNIT("filtersjb\FGGradient.cpp");
USEUNIT("filtersjb\FGSummer.cpp");
USEUNIT("filtersjb\FGDeadBand.cpp");
-USEUNIT("FGTrimLong.cpp");
USEUNIT("filtersjb\FGFlaps.cpp");
USEFILE("JSBSim.cxx");
USEUNIT("FGForce.cpp");
Type = "";
ID = 0;
Input = 0.0;
- InputIdx = FG_NOTHING;
+ InputIdx = FG_UNDEF;
Output = 0.0;
sOutputIdx = "";
- OutputIdx = FG_NOTHING;
+ OutputIdx = FG_UNDEF;
IsOutput = false;
}
Schedule.clear();
Gain = 1.000;
Min = Max = 0;
- ScheduledBy = FG_NOTHING;
+ ScheduledBy = FG_UNDEF;
Type = AC_cfg->GetValue("TYPE");
Name = AC_cfg->GetValue("NAME");