1
0
Fork 0

Updates from the Jon and Tony show.

Tony submitted:

JSBsim:
Added trimming routine, it is longitudinal & in-air only at this point
Added support for taking wind & weather data from external source
Added support for flaps.
Added independently settable pitch trim
Added alphamin and max to config file, stall modeling and warning to
follow

c172.cfg:
Flaps!
Adjusted Cmo, model should be speed stable now

FG:
Hooked up Christian's weather code, should be using it soon.
Hooked up the trimming routine.  Note that the X-15 will not trim.
  This is not a model or trimming routine deficiency, just the
  nature of the X-15
The trimming routine sets the pitch trim and and throttle at startup.
The throttle is set using Norman's code for the autothrottle so the
autothrottle is on by default.  --notrim will turn it off.
Added --vc, --mach, and --notrim switches
      (vc is airspeed in knots)
uBody, vBody, and wBody are still supported, last one entered
on the command line counts, i.e. you can set vc or mach or u,v,
and w but any combination will be ignored.
This commit is contained in:
curt 2000-05-16 21:35:11 +00:00
parent 90707efd3f
commit c4a1cc047e
54 changed files with 2411 additions and 1319 deletions

View file

@ -36,6 +36,7 @@ FGControls::FGControls() :
{
for ( int engine = 0; engine < MAX_ENGINES; engine++ ) {
throttle[engine] = 0.0;
trimmed_throttle[engine]=0.0;
}
for ( int wheel = 0; wheel < MAX_WHEELS; wheel++ ) {

View file

@ -57,6 +57,7 @@ private:
double rudder;
double flaps;
double throttle[MAX_ENGINES];
double trimmed_throttle[MAX_ENGINES];
double brake[MAX_WHEELS];
inline void CLAMP(double *x, double min, double max ) {
@ -80,6 +81,9 @@ public:
inline double get_flaps() const { return flaps; }
inline double get_throttle(int engine) const { return throttle[engine]; }
inline double get_brake(int wheel) const { return brake[wheel]; }
inline double get_trimmed_throttle(int engine) const {
return trimmed_throttle[engine];
}
// Update functions
inline void set_aileron( double pos ) {
@ -149,6 +153,19 @@ public:
}
}
}
inline void set_trimmed_throttle( int engine, double pos ) {
if ( engine == ALL_ENGINES ) {
for ( int i = 0; i < MAX_ENGINES; i++ ) {
trimmed_throttle[i] = pos;
CLAMP( &trimmed_throttle[i], 0.0, 1.0 );
}
} else {
if ( (engine >= 0) && (engine < MAX_ENGINES) ) {
trimmed_throttle[engine] = pos;
CLAMP( &trimmed_throttle[engine], 0.0, 1.0 );
}
}
}
inline void move_throttle( int engine, double amt ) {
if ( engine == ALL_ENGINES ) {
for ( int i = 0; i < MAX_ENGINES; i++ ) {

View file

@ -34,6 +34,8 @@
#include <simgear/math/fg_geodesy.hxx>
#include <simgear/misc/fgpath.hxx>
#include <Scenery/scenery.hxx>
#include <Aircraft/aircraft.hxx>
#include <Controls/controls.hxx>
#include <Main/options.hxx>
@ -47,263 +49,264 @@
#include <FDM/JSBsim/FGTranslation.h>
#include <FDM/JSBsim/FGAuxiliary.h>
#include <FDM/JSBsim/FGDefs.h>
#include <FDM/JSBsim/FGInitialCondition.h>
#include <FDM/JSBsim/FGTrimLong.h>
#include <FDM/JSBsim/FGAtmosphere.h>
#include "JSBsim.hxx"
double geocRwyRadius;
/******************************************************************************/
// Initialize the JSBsim flight model, dt is the time increment for
// each subsequent iteration through the EOM
int FGJSBsim::init( double dt ) {
FG_LOG( FG_FLIGHT, FG_INFO, "Starting and initializing JSBsim" );
FG_LOG( FG_FLIGHT, FG_INFO, " created FDMExec" );
FGPath aircraft_path( current_options.get_fg_root() );
aircraft_path.append( "Aircraft" );
FGPath engine_path( current_options.get_fg_root() );
engine_path.append( "Engine" );
FG_LOG( FG_FLIGHT, FG_INFO, "Starting and initializing JSBsim" );
FG_LOG( FG_FLIGHT, FG_INFO, " created FDMExec" );
FDMExec.GetState()->Setdt( dt );
FGPath aircraft_path( current_options.get_fg_root() );
aircraft_path.append( "Aircraft" );
FDMExec.GetAircraft()->LoadAircraft( aircraft_path.str(),
engine_path.str(),
current_options.get_aircraft() );
FG_LOG( FG_FLIGHT, FG_INFO, " loaded aircraft" <<
current_options.get_aircraft() );
FGPath engine_path( current_options.get_fg_root() );
engine_path.append( "Engine" );
FG_LOG( FG_FLIGHT, FG_INFO, "Initializing JSBsim with:" );
FG_LOG( FG_FLIGHT, FG_INFO, " U: " << current_options.get_uBody() );
FG_LOG( FG_FLIGHT, FG_INFO, " V: " <<current_options.get_vBody() );
FG_LOG( FG_FLIGHT, FG_INFO, " W: " <<current_options.get_wBody() );
FG_LOG( FG_FLIGHT, FG_INFO, " phi: " <<get_Phi() );
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() );
FDMExec.GetState()->Setdt( dt );
FDMExec.GetState()->Initialize(
current_options.get_uBody(),
current_options.get_vBody(),
current_options.get_wBody(),
get_Phi(),
get_Theta(),
get_Psi(),
get_Latitude(),
get_Longitude(),
get_Altitude()
);
FDMExec.GetAircraft()->LoadAircraft( aircraft_path.str(),
engine_path.str(),
current_options.get_aircraft() );
FG_LOG( FG_FLIGHT, FG_INFO, " loaded initial conditions" );
FG_LOG( FG_FLIGHT, FG_INFO, " loaded aircraft" <<
current_options.get_aircraft() );
FG_LOG( FG_FLIGHT, FG_INFO, " set dt" );
FDMExec.GetAtmosphere()->UseInternal();
FG_LOG( FG_FLIGHT, FG_INFO, "Finished initializing JSBsim" );
FG_LOG( FG_FLIGHT, FG_INFO, " Initializing JSBsim with:" );
copy_from_JSBsim();
FGInitialCondition *fgic = new FGInitialCondition(&FDMExec);
fgic->SetAltitudeFtIC(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());
fgic->SetWBodyFpsIC(current_options.get_wBody());
FG_LOG(FG_FLIGHT,FG_INFO, " u,v,w= " << current_options.get_uBody()
<< ", " << current_options.get_vBody()
<< ", " << current_options.get_wBody());
} else if (current_options.get_vc() < 0) {
fgic->SetMachIC(current_options.get_mach());
FG_LOG(FG_FLIGHT,FG_INFO, " mach: " << current_options.get_mach() );
} else {
fgic->SetVcalibratedKtsIC(current_options.get_vc());
FG_LOG(FG_FLIGHT,FG_INFO, " vc: " << current_options.get_vc() );
//this should cover the case in which no speed switches are used
//current_options.get_vc() will return zero by default
}
return 1;
fgic->SetRollAngleRadIC(get_Phi());
fgic->SetPitchAngleRadIC(get_Theta());
fgic->SetHeadingRadIC(get_Psi());
fgic->SetLatitudeRadIC(get_Latitude());
fgic->SetLongitudeRadIC(get_Longitude());
FDMExec.GetPosition()->SetRunwayRadius(geocRwyRadius);
FG_LOG( FG_FLIGHT, FG_INFO, " phi: " << get_Phi());
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() );
if(current_options.get_trim_mode() == true) {
FG_LOG( FG_FLIGHT, FG_INFO, " Starting trim..." );
FGTrimLong *fgtrim=new FGTrimLong(&FDMExec,fgic);
fgtrim->DoTrim();
fgtrim->Report();
fgtrim->TrimStats();
fgtrim->ReportState();
controls.set_elevator_trim(FDMExec.GetFCS()->GetDeCmd());
controls.set_trimmed_throttle(FGControls::ALL_ENGINES,FDMExec.GetFCS()->GetThrottleCmd(0)/100);
//the trimming routine only knows how to get 1 value for throttle
//for(int i=0;i<FDMExec.GetAircraft()->GetNumEngines();i++) {
// controls.set_throttle(i,FDMExec.GetFCS()->GetThrottleCmd(i)/100);
//}
delete fgtrim;
FG_LOG( FG_FLIGHT, FG_INFO, " Trim complete." );
} else {
FG_LOG( FG_FLIGHT, FG_INFO, " Initializing without trim" );
FDMExec.GetState()->Initialize(fgic);
}
delete fgic;
FG_LOG( FG_FLIGHT, FG_INFO, " loaded initial conditions" );
FG_LOG( FG_FLIGHT, FG_INFO, " set dt" );
FG_LOG( FG_FLIGHT, FG_INFO, "Finished initializing JSBsim" );
copy_from_JSBsim();
return 1;
}
/******************************************************************************/
// Run an iteration of the EOM (equations of motion)
int FGJSBsim::update( int multiloop ) {
double save_alt = 0.0;
double time_step = (1.0 / current_options.get_model_hz()) * multiloop;
double start_elev = get_Altitude();
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 );
}
// 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
// copy control positions into the JSBsim structure
FDMExec.GetFCS()->SetDaCmd( controls.get_aileron());
FDMExec.GetFCS()->SetDeCmd( controls.get_elevator()
+ controls.get_elevator_trim() );
FDMExec.GetFCS()->SetDrCmd( controls.get_rudder());
FDMExec.GetFCS()->SetDfCmd( 0.0 );
FDMExec.GetFCS()->SetDsbCmd( 0.0 );
FDMExec.GetFCS()->SetDspCmd( 0.0 );
FDMExec.GetFCS()->SetThrottleCmd( FGControls::ALL_ENGINES,
controls.get_throttle( 0 ) * 100.0 );
FDMExec.GetFCS()->SetThrottlePos( FGControls::ALL_ENGINES,
controls.get_throttle( 0 ) * 100.0 );
// FCS->SetBrake( controls.get_brake( 0 ) );
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 );
FDMExec.GetFCS()->SetDspCmd( 0.0 );
FDMExec.GetFCS()->SetThrottleCmd( FGControls::ALL_ENGINES,
controls.get_throttle( 0 ) * 100.0 );
// Inform JSBsim of the local terrain altitude
// Runway_altitude = get_Runway_altitude();
// FCS->SetBrake( controls.get_brake( 0 ) );
// old -- FGInterface_2_JSBsim() not needed except for Init()
// translate FG to JSBsim structure
// FGInterface_2_JSBsim(f);
// printf("FG_Altitude = %.2f\n", FG_Altitude * 0.3048);
// printf("Altitude = %.2f\n", Altitude * 0.3048);
// printf("Radius to Vehicle = %.2f\n", Radius_to_vehicle * 0.3048);
// Inform JSBsim of the local terrain altitude; uncommented 5/3/00
// FDMExec.GetPosition()->SetRunwayElevation(get_Runway_altitude()); // seems to work
FDMExec.GetPosition()->SetRunwayRadius(geocRwyRadius);
/* FDMExec.GetState()->Setsim_time(State->Getsim_time()
+ State->Getdt() * multiloop); */
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());
for ( int i = 0; i < multiloop; i++ ) {
FDMExec.Run();
}
for ( int i = 0; i < multiloop; i++ ) {
FDMExec.Run();
}
// printf("%d FG_Altitude = %.2f\n", i, FG_Altitude * 0.3048);
// printf("%d Altitude = %.2f\n", i, Altitude * 0.3048);
// translate JSBsim back to FG structure so that the
// autopilot (and the rest of the sim can use the updated
// values
// printf("%d FG_Altitude = %.2f\n", i, FG_Altitude * 0.3048);
// printf("%d Altitude = %.2f\n", i, Altitude * 0.3048);
copy_from_JSBsim();
// translate JSBsim back to FG structure so that the
// autopilot (and the rest of the sim can use the updated values
// but lets restore our original bogus altitude when we are done
if ( save_alt < -9000.0 ) {
set_Altitude( save_alt );
}
copy_from_JSBsim();
double end_elev = get_Altitude();
if ( time_step > 0.0 ) {
// feet per second
set_Climb_Rate( (end_elev - start_elev) / time_step );
}
// but lets restore our original bogus altitude when we are done
return 1;
if ( save_alt < -9000.0 ) {
set_Altitude( save_alt );
}
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() {
return 1;
return 1;
}
/******************************************************************************/
// Convert from the JSBsim generic_ struct to the FGInterface struct
int FGJSBsim::copy_from_JSBsim() {
// Velocities
set_Velocities_Local( FDMExec.GetPosition()->GetVn(),
FDMExec.GetPosition()->GetVe(),
FDMExec.GetPosition()->GetVd() );
// set_Velocities_Ground( V_north_rel_ground, V_east_rel_ground,
// V_down_rel_ground );
// set_Velocities_Local_Airmass( V_north_airmass, V_east_airmass,
// V_down_airmass );
// set_Velocities_Local_Rel_Airmass( V_north_rel_airmass,
// V_east_rel_airmass, V_down_rel_airmass );
// set_Velocities_Gust( U_gust, V_gust, W_gust );
// set_Velocities_Wind_Body( U_body, V_body, W_body );
// Velocities
// set_V_rel_wind( V_rel_wind );
// set_V_true_kts( V_true_kts );
// set_V_rel_ground( V_rel_ground );
// set_V_inertial( V_inertial );
// set_V_ground_speed( V_ground_speed );
// set_V_equiv( V_equiv );
set_Velocities_Local( FDMExec.GetPosition()->GetVn(),
FDMExec.GetPosition()->GetVe(),
FDMExec.GetPosition()->GetVd() );
set_V_equiv_kts( FDMExec.GetAuxiliary()->GetVequivalentKTS() );
//set_V_calibrated( FDMExec.GetAuxiliary()->GetVcalibratedFPS() );
set_V_calibrated_kts( FDMExec.GetAuxiliary()->GetVcalibratedKTS() );
set_V_equiv_kts( FDMExec.GetAuxiliary()->GetVequivalentKTS() );
set_Omega_Body( FDMExec.GetState()->GetParameter(FG_ROLLRATE),
FDMExec.GetState()->GetParameter(FG_PITCHRATE),
FDMExec.GetState()->GetParameter(FG_YAWRATE) );
// set_Omega_Local( P_local, Q_local, R_local );
// set_Omega_Total( P_total, Q_total, R_total );
//set_V_calibrated( FDMExec.GetAuxiliary()->GetVcalibratedFPS() );
set_Euler_Rates( FDMExec.GetRotation()->Getphi(),
FDMExec.GetRotation()->Gettht(),
FDMExec.GetRotation()->Getpsi() );
set_V_calibrated_kts( FDMExec.GetAuxiliary()->GetVcalibratedKTS() );
// ***FIXME*** set_Geocentric_Rates( Latitude_dot, Longitude_dot, Radius_dot );
set_Mach_number( FDMExec.GetTranslation()->GetMach());
set_Omega_Body( FDMExec.GetState()->GetParameter(FG_ROLLRATE),
FDMExec.GetState()->GetParameter(FG_PITCHRATE),
FDMExec.GetState()->GetParameter(FG_YAWRATE) );
// Positions
double lat_geoc = FDMExec.GetPosition()->GetLatitude();
double lon = FDMExec.GetPosition()->GetLongitude();
double alt = FDMExec.GetPosition()->Geth();
double lat_geod, tmp_alt, sl_radius1, sl_radius2, tmp_lat_geoc;
fgGeocToGeod( lat_geoc, EQUATORIAL_RADIUS_M + alt * FEET_TO_METER,
&lat_geod, &tmp_alt, &sl_radius1 );
fgGeodToGeoc( lat_geod, alt * FEET_TO_METER, &sl_radius2, &tmp_lat_geoc );
set_Euler_Rates( FDMExec.GetRotation()->Getphi(),
FDMExec.GetRotation()->Gettht(),
FDMExec.GetRotation()->Getpsi() );
FG_LOG( FG_FLIGHT, FG_DEBUG, "lon = " << lon << " lat_geod = " << lat_geod
<< " lat_geoc = " << lat_geoc
<< " alt = " << alt << " tmp_alt = " << tmp_alt * METER_TO_FEET
<< " sl_radius1 = " << sl_radius1 * METER_TO_FEET
<< " sl_radius2 = " << sl_radius2 * METER_TO_FEET
<< " Equator = " << EQUATORIAL_RADIUS_FT );
set_Geocentric_Position( lat_geoc, lon,
sl_radius2 * METER_TO_FEET + alt );
set_Geodetic_Position( lat_geod, lon, alt );
set_Euler_Angles( FDMExec.GetRotation()->Getphi(),
FDMExec.GetRotation()->Gettht(),
FDMExec.GetRotation()->Getpsi() );
// ***FIXME*** set_Geocentric_Rates( Latitude_dot, Longitude_dot, Radius_dot );
// Miscellaneous quantities
// set_T_Local_to_Body(T_local_to_body_m);
// set_Gravity( Gravity );
// set_Centrifugal_relief( Centrifugal_relief );
set_Mach_number( FDMExec.GetTranslation()->GetMach());
set_Alpha( FDMExec.GetTranslation()->Getalpha() );
set_Beta( FDMExec.GetTranslation()->Getbeta() );
// set_Alpha_dot( Alpha_dot );
// set_Beta_dot( Beta_dot );
// Positions
// set_Cos_alpha( Cos_alpha );
// set_Sin_alpha( Sin_alpha );
// set_Cos_beta( Cos_beta );
// set_Sin_beta( Sin_beta );
double lat_geoc = FDMExec.GetPosition()->GetLatitude();
double lon = FDMExec.GetPosition()->GetLongitude();
double alt = FDMExec.GetPosition()->Geth();
double lat_geod, tmp_alt, sl_radius1, sl_radius2, tmp_lat_geoc;
// set_Cos_phi( Cos_phi );
// set_Sin_phi( Sin_phi );
// set_Cos_theta( Cos_theta );
// set_Sin_theta( Sin_theta );
// set_Cos_psi( Cos_psi );
// set_Sin_psi( Sin_psi );
fgGeocToGeod( lat_geoc, EQUATORIAL_RADIUS_M + alt * FEET_TO_METER,
&lat_geod, &tmp_alt, &sl_radius1 );
fgGeodToGeoc( lat_geod, alt * FEET_TO_METER, &sl_radius2, &tmp_lat_geoc );
// ***ATTENDTOME*** set_Gamma_vert_rad( Gamma_vert_rad );
// set_Gamma_horiz_rad( Gamma_horiz_rad );
FG_LOG( FG_FLIGHT, FG_DEBUG, "lon = " << lon << " lat_geod = " << lat_geod
<< " lat_geoc = " << lat_geoc
<< " alt = " << alt << " tmp_alt = " << tmp_alt * METER_TO_FEET
<< " sl_radius1 = " << sl_radius1 * METER_TO_FEET
<< " sl_radius2 = " << sl_radius2 * METER_TO_FEET
<< " Equator = " << EQUATORIAL_RADIUS_FT );
// set_Sigma( Sigma );
// set_Density( Density );
// set_V_sound( V_sound );
// set_Mach_number( Mach_number );
set_Geocentric_Position( lat_geoc, lon,
sl_radius2 * METER_TO_FEET + alt );
set_Geodetic_Position( lat_geod, lon, alt );
set_Euler_Angles( FDMExec.GetRotation()->Getphi(),
FDMExec.GetRotation()->Gettht(),
FDMExec.GetRotation()->Getpsi() );
// set_Static_pressure( Static_pressure );
// set_Total_pressure( Total_pressure );
// set_Impact_pressure( Impact_pressure );
// set_Dynamic_pressure( Dynamic_pressure );
set_Alpha( FDMExec.GetTranslation()->Getalpha() );
set_Beta( FDMExec.GetTranslation()->Getbeta() );
// set_Static_temperature( Static_temperature );
// set_Total_temperature( Total_temperature );
set_Gamma_vert_rad( FDMExec.GetPosition()->GetGamma() );
// set_Gamma_horiz_rad( Gamma_horiz_rad );
/* **FIXME*** */ set_Sea_level_radius( sl_radius2 * METER_TO_FEET );
/* **FIXME*** */ set_Earth_position_angle( 0.0 );
/* **FIXME*** */ set_Sea_level_radius( sl_radius2 * METER_TO_FEET );
/* **FIXME*** */ set_Earth_position_angle( 0.0 );
/* ***FIXME*** */ set_Runway_altitude( 0.0 );
// set_Runway_latitude( Runway_latitude );
// set_Runway_longitude( Runway_longitude );
// set_Runway_heading( Runway_heading );
// set_Radius_to_rwy( Radius_to_rwy );
// /* ***FIXME*** */ set_Runway_altitude( 0.0 );
// set_CG_Rwy_Local( D_cg_north_of_rwy, D_cg_east_of_rwy, D_cg_above_rwy);
// set_CG_Rwy_Rwy( X_cg_rwy, Y_cg_rwy, H_cg_rwy );
// set_Pilot_Rwy_Local( D_pilot_north_of_rwy, D_pilot_east_of_rwy,
// D_pilot_above_rwy );
// set_Pilot_Rwy_Rwy( X_pilot_rwy, Y_pilot_rwy, H_pilot_rwy );
set_sin_lat_geocentric( lat_geoc );
set_cos_lat_geocentric( lat_geoc );
set_sin_cos_longitude( lon );
set_sin_cos_latitude( lat_geod );
set_sin_lat_geocentric( lat_geoc );
set_cos_lat_geocentric( lat_geoc );
set_sin_cos_longitude( lon );
set_sin_cos_latitude( lat_geod );
return 1;
return 1;
}
/******************************************************************************/

View file

@ -1,36 +1,36 @@
/*******************************************************************************
Module: FGAircraft.cpp
Author: Jon S. Berndt
Date started: 12/12/98
Purpose: Encapsulates an aircraft
Called by: FGFDMExec
------------- Copyright (C) 1999 Jon S. Berndt (jsb@hal-pc.org) -------------
This program is free software; you can redistribute it and/or modify it under
the terms of the GNU General Public License as published by the Free Software
Foundation; either version 2 of the License, or (at your option) any later
version.
This program is distributed in the hope that it will be useful, but WITHOUT
ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
FOR A PARTICULAR PURPOSE. See the GNU General Public License for more
details.
You should have received a copy of the GNU General Public License along with
this program; if not, write to the Free Software Foundation, Inc., 59 Temple
Place - Suite 330, Boston, MA 02111-1307, USA.
Further information about the GNU General Public License can also be found on
the world wide web at http://www.gnu.org.
FUNCTIONAL DESCRIPTION
--------------------------------------------------------------------------------
Models the aircraft reactions and forces. This class is instantiated by the
FGFDMExec class and scheduled as an FDM entry. LoadAircraft() is supplied with a
name of a valid, registered aircraft, and the data file is parsed.
HISTORY
--------------------------------------------------------------------------------
12/12/98 JSB Created
@ -40,7 +40,7 @@ HISTORY
9/17/99 TP Combined force and moment functions. Added aero reference
point to config file. Added calculations for moments due to
difference in cg and aero reference point
********************************************************************************
COMMENTS, REFERENCES, and NOTES
********************************************************************************
@ -55,9 +55,9 @@ COMMENTS, REFERENCES, and NOTES
Wiley & Sons, 1979 ISBN 0-471-03032-5
[5] Bernard Etkin, "Dynamics of Flight, Stability and Control", Wiley & Sons,
1982 ISBN 0-471-08936-2
The aerodynamic coefficients used in this model are:
Longitudinal
CL0 - Reference lift at zero alpha
CD0 - Reference drag at zero alpha
@ -67,36 +67,36 @@ Longitudinal
CLq - Lift due to pitch rate
CLM - Lift due to Mach
CLadt - Lift due to alpha rate
Cmadt - Pitching Moment due to alpha rate
Cm0 - Reference Pitching moment at zero alpha
Cma - Pitching moment slope (w.r.t. alpha)
Cmq - Pitch damping (pitch moment due to pitch rate)
CmM - Pitch Moment due to Mach
Lateral
Cyb - Side force due to sideslip
Cyr - Side force due to yaw rate
Clb - Dihedral effect (roll moment due to sideslip)
Clp - Roll damping (roll moment due to roll rate)
Clr - Roll moment due to yaw rate
Cnb - Weathercocking stability (yaw moment due to sideslip)
Cnp - Rudder adverse yaw (yaw moment due to roll rate)
Cnr - Yaw damping (yaw moment due to yaw rate)
Control
CLDe - Lift due to elevator
CDDe - Drag due to elevator
CyDr - Side force due to rudder
CyDa - Side force due to aileron
CmDe - Pitch moment due to elevator
ClDa - Roll moment due to aileron
ClDr - Roll moment due to rudder
CnDr - Yaw moment due to rudder
CnDa - Yaw moment due to aileron
********************************************************************************
INCLUDES
*******************************************************************************/
@ -105,9 +105,9 @@ INCLUDES
#include <sys/types.h>
#ifdef FGFS
# ifndef __BORLANDC__
# include <simgear/compiler.h>
# endif
# ifndef __BORLANDC__
# include <simgear/compiler.h>
# endif
# ifdef FG_HAVE_STD_INCLUDES
# include <cmath>
# else
@ -133,15 +133,14 @@ INCLUDES
*******************************************************************************/
FGAircraft::FGAircraft(FGFDMExec* fdmex) : FGModel(fdmex),
vMoments(3),
vForces(3),
vXYZrp(3),
vbaseXYZcg(3),
vXYZcg(3),
vXYZep(3),
vEuler(3),
vFs(3)
{
vMoments(3),
vForces(3),
vXYZrp(3),
vbaseXYZcg(3),
vXYZcg(3),
vXYZep(3),
vEuler(3),
vFs(3) {
Name = "FGAircraft";
AxisIdx["DRAG"] = 0;
@ -158,14 +157,11 @@ FGAircraft::FGAircraft(FGFDMExec* fdmex) : FGModel(fdmex),
/******************************************************************************/
FGAircraft::~FGAircraft(void)
{
}
FGAircraft::~FGAircraft(void) {}
/******************************************************************************/
bool FGAircraft::LoadAircraft(string aircraft_path, string engine_path, string fname)
{
bool FGAircraft::LoadAircraft(string aircraft_path, string engine_path, string fname) {
string path;
string filename;
string aircraftCfgFileName;
@ -181,8 +177,7 @@ bool FGAircraft::LoadAircraft(string aircraft_path, string engine_path, string f
ReadPrologue(&AC_cfg);
while ((AC_cfg.GetNextConfigLine() != "EOF") &&
(token = AC_cfg.GetValue()) != "/FDM_CONFIG")
{
(token = AC_cfg.GetValue()) != "/FDM_CONFIG") {
if (token == "METRICS") {
cout << " Reading Metrics" << endl;
ReadMetrics(&AC_cfg);
@ -208,8 +203,7 @@ bool FGAircraft::LoadAircraft(string aircraft_path, string engine_path, string f
/******************************************************************************/
bool FGAircraft::Run(void)
{
bool FGAircraft::Run(void) {
if (!FGModel::Run()) { // if false then execute this Run()
GetState();
@ -221,15 +215,18 @@ bool FGAircraft::Run(void)
FMAero();
FMGear();
FMMass();
nlf=vFs(eZ)/Weight;
} else { // skip Run() execution this time
}
return false;
}
/******************************************************************************/
void FGAircraft::MassChange()
{
void FGAircraft::MassChange() {
static FGColumnVector vXYZtank(3);
float Tw;
float IXXt, IYYt, IZZt, IXZt;
@ -323,8 +320,7 @@ void FGAircraft::MassChange()
/******************************************************************************/
void FGAircraft::FMAero(void)
{
void FGAircraft::FMAero(void) {
static FGColumnVector vDXYZcg(3);
unsigned int axis_ctr,ctr;
@ -361,21 +357,20 @@ void FGAircraft::FMAero(void)
/******************************************************************************/
void FGAircraft::FMGear(void)
{
void FGAircraft::FMGear(void) {
if (GearUp) {
// crash routine
} else {
}
else {
for (unsigned int i=0;i<lGear.size();i++) {
// lGear[i].
vForces += lGear[i]->Force();
}
}
}
/******************************************************************************/
void FGAircraft::FMMass(void)
{
void FGAircraft::FMMass(void) {
vForces(eX) += -GRAVITY*sin(vEuler(eTht)) * Mass;
vForces(eY) += GRAVITY*sin(vEuler(ePhi))*cos(vEuler(eTht)) * Mass;
vForces(eZ) += GRAVITY*cos(vEuler(ePhi))*cos(vEuler(eTht)) * Mass;
@ -383,8 +378,7 @@ void FGAircraft::FMMass(void)
/******************************************************************************/
void FGAircraft::FMProp(void)
{
void FGAircraft::FMProp(void) {
for (int i=0;i<numEngines;i++) {
vForces(eX) += Engine[i]->CalcThrust();
}
@ -392,8 +386,7 @@ void FGAircraft::FMProp(void)
/******************************************************************************/
void FGAircraft::GetState(void)
{
void FGAircraft::GetState(void) {
dt = State->Getdt();
alpha = Translation->Getalpha();
@ -403,8 +396,7 @@ void FGAircraft::GetState(void)
/******************************************************************************/
void FGAircraft::ReadMetrics(FGConfigFile* AC_cfg)
{
void FGAircraft::ReadMetrics(FGConfigFile* AC_cfg) {
string token = "";
string parameter;
@ -423,13 +415,13 @@ void FGAircraft::ReadMetrics(FGConfigFile* AC_cfg)
else if (parameter == "AC_CGLOC") *AC_cfg >> vbaseXYZcg(eX) >> vbaseXYZcg(eY) >> vbaseXYZcg(eZ);
else if (parameter == "AC_EYEPTLOC") *AC_cfg >> vXYZep(eX) >> vXYZep(eY) >> vXYZep(eZ);
else if (parameter == "AC_AERORP") *AC_cfg >> vXYZrp(eX) >> vXYZrp(eY) >> vXYZrp(eZ);
else if (parameter == "AC_ALPHALIMITS") *AC_cfg >> alphaclmin >> alphaclmax;
}
}
/******************************************************************************/
void FGAircraft::ReadPropulsion(FGConfigFile* AC_cfg)
{
void FGAircraft::ReadPropulsion(FGConfigFile* AC_cfg) {
string token;
string engine_name;
string parameter;
@ -463,8 +455,7 @@ void FGAircraft::ReadPropulsion(FGConfigFile* AC_cfg)
/******************************************************************************/
void FGAircraft::ReadFlightControls(FGConfigFile* AC_cfg)
{
void FGAircraft::ReadFlightControls(FGConfigFile* AC_cfg) {
string token;
FCS->LoadFCS(AC_cfg);
@ -472,8 +463,7 @@ void FGAircraft::ReadFlightControls(FGConfigFile* AC_cfg)
/******************************************************************************/
void FGAircraft::ReadAerodynamics(FGConfigFile* AC_cfg)
{
void FGAircraft::ReadAerodynamics(FGConfigFile* AC_cfg) {
string token, axis;
AC_cfg->GetNextConfigLine();
@ -500,21 +490,19 @@ void FGAircraft::ReadAerodynamics(FGConfigFile* AC_cfg)
/******************************************************************************/
void FGAircraft::ReadUndercarriage(FGConfigFile* AC_cfg)
{
void FGAircraft::ReadUndercarriage(FGConfigFile* AC_cfg) {
string token;
AC_cfg->GetNextConfigLine();
while ((token = AC_cfg->GetValue()) != "/UNDERCARRIAGE") {
lGear.push_back(new FGLGear(AC_cfg));
lGear.push_back(new FGLGear(AC_cfg, FDMExec));
}
}
/******************************************************************************/
void FGAircraft::ReadOutput(FGConfigFile* AC_cfg)
{
void FGAircraft::ReadOutput(FGConfigFile* AC_cfg) {
string token, parameter;
int OutRate = 0;
int subsystems = 0;
@ -578,28 +566,29 @@ void FGAircraft::ReadOutput(FGConfigFile* AC_cfg)
/******************************************************************************/
void FGAircraft::ReadPrologue(FGConfigFile* AC_cfg)
{
void FGAircraft::ReadPrologue(FGConfigFile* AC_cfg) {
string token = AC_cfg->GetValue();
string scratch;
AircraftName = AC_cfg->GetValue("NAME");
cout << "Reading Aircraft Configuration File: " << AircraftName << endl;
CFGVersion = strtod(AC_cfg->GetValue("VERSION").c_str(),NULL);
cout << " Version: " << CFGVersion << endl;
scratch=AC_cfg->GetValue("VERSION").c_str();
if (CFGVersion < NEEDED_CFG_VERSION) {
cout << endl << "YOU HAVE AN OLD CFG FILE FOR THIS AIRCRAFT."
" RESULTS WILL BE UNPREDICTABLE !!" << endl;
CFGVersion = AC_cfg->GetValue("VERSION");
cout << " Version: " << CFGVersion << endl;
if (CFGVersion != NEEDED_CFG_VERSION) {
cout << endl << "YOU HAVE AN INCOMPATIBLE CFG FILE FOR THIS AIRCRAFT."
" RESULTS WILL BE UNPREDICTABLE !!" << endl;
cout << "Current version needed is: " << NEEDED_CFG_VERSION << endl;
cout << " You have version: " << CFGVersion << endl << endl;
exit(-1);
//exit(-1);
}
}
/******************************************************************************/
void FGAircraft::DisplayCoeffFactors(int multipliers)
{
void FGAircraft::DisplayCoeffFactors(int multipliers) {
cout << " Non-Dimensionalized by: ";
if (multipliers & FG_QBAR) cout << "qbar ";
@ -638,8 +627,7 @@ void FGAircraft::DisplayCoeffFactors(int multipliers)
/******************************************************************************/
string FGAircraft::GetCoefficientStrings(void)
{
string FGAircraft::GetCoefficientStrings(void) {
string CoeffStrings = "";
bool firstime = true;
@ -659,8 +647,7 @@ string FGAircraft::GetCoefficientStrings(void)
/******************************************************************************/
string FGAircraft::GetCoefficientValues(void)
{
string FGAircraft::GetCoefficientValues(void) {
string SDValues = "";
char buffer[10];
bool firstime = true;
@ -677,7 +664,8 @@ string FGAircraft::GetCoefficientValues(void)
}
}
return SDValues;;
return SDValues;
;
}

View file

@ -1,32 +1,32 @@
/*******************************************************************************
Header: FGAircraft.h
Author: Jon S. Berndt
Date started: 12/12/98
------------- Copyright (C) 1999 Jon S. Berndt (jsb@hal-pc.org) -------------
This program is free software; you can redistribute it and/or modify it under
the terms of the GNU General Public License as published by the Free Software
Foundation; either version 2 of the License, or (at your option) any later
version.
This program is distributed in the hope that it will be useful, but WITHOUT
ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
FOR A PARTICULAR PURPOSE. See the GNU General Public License for more
details.
You should have received a copy of the GNU General Public License along with
this program; if not, write to the Free Software Foundation, Inc., 59 Temple
Place - Suite 330, Boston, MA 02111-1307, USA.
Further information about the GNU General Public License can also be found on
the world wide web at http://www.gnu.org.
HISTORY
--------------------------------------------------------------------------------
12/12/98 JSB Created
********************************************************************************
SENTRY
*******************************************************************************/
@ -39,7 +39,7 @@ COMMENTS, REFERENCES, and NOTES
*******************************************************************************/
/*
The aerodynamic coefficients used in this model typically are:
Longitudinal
CL0 - Reference lift at zero alpha
CD0 - Reference drag at zero alpha
@ -49,36 +49,36 @@ Longitudinal
CLq - Lift due to pitch rate
CLM - Lift due to Mach
CLadt - Lift due to alpha rate
Cmadt - Pitching Moment due to alpha rate
Cm0 - Reference Pitching moment at zero alpha
Cma - Pitching moment slope (w.r.t. alpha)
Cmq - Pitch damping (pitch moment due to pitch rate)
CmM - Pitch Moment due to Mach
Lateral
Cyb - Side force due to sideslip
Cyr - Side force due to yaw rate
Clb - Dihedral effect (roll moment due to sideslip)
Clp - Roll damping (roll moment due to roll rate)
Clr - Roll moment due to yaw rate
Cnb - Weathercocking stability (yaw moment due to sideslip)
Cnp - Rudder adverse yaw (yaw moment due to roll rate)
Cnr - Yaw damping (yaw moment due to yaw rate)
Control
CLDe - Lift due to elevator
CDDe - Drag due to elevator
CyDr - Side force due to rudder
CyDa - Side force due to aileron
CmDe - Pitch moment due to elevator
ClDa - Roll moment due to aileron
ClDr - Roll moment due to rudder
CnDr - Yaw moment due to rudder
CnDa - Yaw moment due to aileron
[1] Cooke, Zyda, Pratt, and McGhee, "NPSNET: Flight Simulation Dynamic Modeling
Using Quaternions", Presence, Vol. 1, No. 4, pp. 404-420 Naval Postgraduate
School, January 1994
@ -122,14 +122,11 @@ INCLUDES
DEFINITIONS
*******************************************************************************/
using namespace std;
/*******************************************************************************
CLASS DECLARATION
*******************************************************************************/
class FGAircraft : public FGModel
{
class FGAircraft : public FGModel {
enum {eL=1, eM, eN};
enum {eX=1, eY, eZ};
enum {eP=1, eQ, eR};
@ -141,25 +138,31 @@ public:
bool Run(void);
bool LoadAircraft(string, string, string);
inline string GetAircraftName(void) {return AircraftName;}
inline void SetGearUp(bool tt) {GearUp = tt;}
inline bool GetGearUp(void) {return GearUp;}
inline float GetWingArea(void) {return WingArea;}
inline float GetWingSpan(void) {return WingSpan;}
inline float Getcbar(void) {return cbar;}
inline FGEngine* GetEngine(int tt) {return Engine[tt];}
inline FGTank* GetTank(int tt) {return Tank[tt];}
inline float GetWeight(void) {return Weight;}
inline float GetMass(void) {return Mass;}
inline FGColumnVector GetMoments(void) {return vMoments;}
inline FGColumnVector GetForces(void) {return vForces;}
inline FGColumnVector GetvFs(void) {return vFs;}
inline float GetIxx(void) {return Ixx;}
inline float GetIyy(void) {return Iyy;}
inline float GetIzz(void) {return Izz;}
inline float GetIxz(void) {return Ixz;}
inline int GetNumEngines(void) {return numEngines;}
inline FGColumnVector GetXYZcg(void) {return vXYZcg;}
inline string GetAircraftName(void) { return AircraftName; }
inline void SetGearUp(bool tt) { GearUp = tt; }
inline bool GetGearUp(void) { return GearUp; }
inline float GetWingArea(void) { return WingArea; }
inline float GetWingSpan(void) { return WingSpan; }
inline float Getcbar(void) { return cbar; }
inline FGEngine* GetEngine(int tt) { return Engine[tt]; }
inline FGTank* GetTank(int tt) { return Tank[tt]; }
inline float GetWeight(void) { return Weight; }
inline float GetMass(void) { return Mass; }
inline FGColumnVector GetMoments(void) { return vMoments; }
inline FGColumnVector GetForces(void) { return vForces; }
inline FGColumnVector GetvFs(void) { return vFs; }
inline float GetIxx(void) { return Ixx; }
inline float GetIyy(void) { return Iyy; }
inline float GetIzz(void) { return Izz; }
inline float GetIxz(void) { return Ixz; }
inline int GetNumEngines(void) { return numEngines; }
inline FGColumnVector GetXYZcg(void) { return vXYZcg; }
inline float GetNlf(void) { return nlf; }
inline float GetAlphaCLMax(void) { return alphaclmax; }
inline float GetAlphaCLMin(void) { return alphaclmin; }
inline void SetAlphaCLMax(float tt) { alphaclmax=tt; }
inline void SetAlphaCLMin(float tt) { alphaclmin=tt; }
string GetCoefficientStrings(void);
string GetCoefficientValues(void);
@ -173,7 +176,7 @@ public:
ssMassProps = 128,
ssCoefficients = 256,
ssPosition = 512 } subsystems;
private:
void GetState(void);
void FMAero(void);
@ -195,10 +198,11 @@ private:
float alpha, beta;
float WingArea, WingSpan, cbar;
float Weight, EmptyWeight;
float nlf,alphaclmax,alphaclmin;
float dt;
double CFGVersion;
string CFGVersion;
string AircraftName;
int numTanks;
int numEngines;
int numSelectedOxiTanks;

View file

@ -57,22 +57,25 @@ INCLUDES
#include "FGAuxiliary.h"
#include "FGOutput.h"
#include "FGDefs.h"
#include "FGMatrix.h"
/*******************************************************************************
************************************ CODE **************************************
*******************************************************************************/
FGAtmosphere::FGAtmosphere(FGFDMExec* fdmex) : FGModel(fdmex)
FGAtmosphere::FGAtmosphere(FGFDMExec* fdmex) : FGModel(fdmex),vWindUVW(3),vWindNED(3)
{
Name = "FGAtmosphere";
h = 0;
Calculate(h);
SLtemperature = temperature;
SLpressure = pressure;
SLdensity = density;
SLsoundspeed = sqrt(SHRATIO*Reng*temperature);
useExternal=false;
Name = "FGAtmosphere";
h = 0;
Calculate(h);
SLtemperature = temperature;
SLpressure = pressure;
SLdensity = density;
SLsoundspeed = sqrt(SHRATIO*Reng*temperature);
useExternal=false;
vWindUVW(1)=0;vWindUVW(2)=0;vWindUVW(3)=0;
vWindNED(1)=0;vWindNED(2)=0;vWindNED(3)=0;
}
@ -83,105 +86,127 @@ FGAtmosphere::~FGAtmosphere()
bool FGAtmosphere::Run(void)
{
if (!FGModel::Run()) { // if false then execute this Run()
if (!useExternal) {
h = Position->Geth();
Calculate(h);
} else {
density = exDensity;
pressure = exPressure;
temperature = exTemperature;
//cout << "In FGAtmosphere::Run(void)" << endl;
if (!FGModel::Run()) { // if false then execute this Run()
//do temp, pressure, and density first
if (!useExternal) {
//cout << "Atmosphere: Using internal model, altitude= ";
h = Position->Geth();
Calculate(h);
} else {
density = exDensity;
pressure = exPressure;
temperature = exTemperature;
//switch sign of wind components so that they are
//in aircraft reference frame. The classic example is
//takeoff or landing where you always want to fly
//into the wind. Suppose that an aircraft is
//taking off into the wind on the runway heading
//of pure north. Into the wind means the wind is
//flowing to the south (or negative) direction,
//and we know that headwinds increase the relative
//velocity, so to make a positive delta U from the
//southerly wind the sign must be switched.
vWindNED*=-1;
vWindUVW=State->GetTl2b()*vWindNED;
}
soundspeed = sqrt(SHRATIO*Reng*temperature);
//cout << "Atmosphere: soundspeed: " << soundspeed << endl;
State->Seta(soundspeed);
} else { // skip Run() execution this time
}
soundspeed = sqrt(SHRATIO*Reng*temperature);
State->Seta(soundspeed);
} else { // skip Run() execution this time
}
return false;
return false;
}
void FGAtmosphere::Calculate(float altitude)
{
//see reference [1]
//see reference [1]
float slope,reftemp,refpress,refdens;
int i=0;
float htab[]={0,36089,82020,154198,173882,259183,295272,344484}; //ft.
// cout << "Atmosphere: h=" << altitude << " rho= " << density << endl;
// cout << "Atmosphere: h=" << altitude << " rho= " << density << endl;
if (altitude <= htab[0]) {
altitude=0;
altitude=0;
} else if (altitude >= htab[7]){
i = 7;
altitude = htab[7];
i = 7;
altitude = htab[7];
} else {
while (htab[i+1] < altitude) {
i++;
}
while (htab[i+1] < altitude) {
i++;
}
}
switch(i) {
case 0: // sea level
slope = -0.0035662; // R/ft.
reftemp = 518.688; // R
refpress = 2116.17; // psf
refdens = 0.0023765; // slugs/cubic ft.
break;
slope = -0.0035662; // R/ft.
reftemp = 518.688; // R
refpress = 2116.17; // psf
refdens = 0.0023765; // slugs/cubic ft.
break;
case 1: // 36089 ft.
slope = 0;
reftemp = 389.988;
refpress = 474.1;
refdens = 0.0007078;
break;
slope = 0;
reftemp = 389.988;
refpress = 474.1;
refdens = 0.0007078;
break;
case 2: // 82020 ft.
slope = 0.00164594;
reftemp = 389.988;
refpress = 52.7838;
refdens = 7.8849E-5;
break;
slope = 0.00164594;
reftemp = 389.988;
refpress = 52.7838;
refdens = 7.8849E-5;
break;
case 3: // 154198 ft.
slope = 0;
reftemp = 508.788;
refpress = 2.62274;
refdens = 3.01379E-6;
break;
slope = 0;
reftemp = 508.788;
refpress = 2.62274;
refdens = 3.01379E-6;
break;
case 4: // 173882 ft.
slope = -0.00246891;
reftemp = 508.788;
refpress = 1.28428;
refdens = 1.47035e-06;
break;
slope = -0.00246891;
reftemp = 508.788;
refpress = 1.28428;
refdens = 1.47035e-06;
break;
case 5: // 259183 ft.
slope = 0;
reftemp = 298.188;
refpress = 0.0222008;
refdens = 4.33396e-08;
break;
slope = 0;
reftemp = 298.188;
refpress = 0.0222008;
refdens = 4.33396e-08;
break;
case 6: // 295272 ft.
slope = 0.00219459;
reftemp = 298.188;
refpress = 0.00215742;
refdens = 4.21368e-09;
break;
slope = 0.00219459;
reftemp = 298.188;
refpress = 0.00215742;
refdens = 4.21368e-09;
break;
case 7: // 344484 ft.
slope = 0;
reftemp = 406.188;
refpress = 0.000153755;
refdens = 2.20384e-10;
break;
slope = 0;
reftemp = 406.188;
refpress = 0.000153755;
refdens = 2.20384e-10;
break;
}
if (slope == 0) {
temperature = reftemp;
pressure = refpress*exp(-GRAVITY/(reftemp*Reng)*(altitude-htab[i]));
density = refdens*exp(-GRAVITY/(reftemp*Reng)*(altitude-htab[i]));
temperature = reftemp;
pressure = refpress*exp(-GRAVITY/(reftemp*Reng)*(altitude-htab[i]));
density = refdens*exp(-GRAVITY/(reftemp*Reng)*(altitude-htab[i]));
} else {
temperature = reftemp+slope*(altitude-htab[i]);
pressure = refpress*pow(temperature/reftemp,-GRAVITY/(slope*Reng));
density = refdens*pow(temperature/reftemp,-(GRAVITY/(slope*Reng)+1));
temperature = reftemp+slope*(altitude-htab[i]);
pressure = refpress*pow(temperature/reftemp,-GRAVITY/(slope*Reng));
density = refdens*pow(temperature/reftemp,-(GRAVITY/(slope*Reng)+1));
}
//cout << "Atmosphere: h=" << altitude << " rho= " << density << endl;
//cout << "Atmosphere: h=" << altitude << " rho= " << density << endl;
}

View file

@ -1,36 +1,36 @@
/*******************************************************************************
Header: FGAtmosphere.h
Author: Jon Berndt
Implementation of 1959 Standard Atmosphere added by Tony Peden
Date started: 11/24/98
------------- Copyright (C) 1999 Jon S. Berndt (jsb@hal-pc.org) -------------
This program is free software; you can redistribute it and/or modify it under
the terms of the GNU General Public License as published by the Free Software
Foundation; either version 2 of the License, or (at your option) any later
version.
This program is distributed in the hope that it will be useful, but WITHOUT
ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
FOR A PARTICULAR PURPOSE. See the GNU General Public License for more
details.
You should have received a copy of the GNU General Public License along with
this program; if not, write to the Free Software Foundation, Inc., 59 Temple
Place - Suite 330, Boston, MA 02111-1307, USA.
Further information about the GNU General Public License can also be found on
the world wide web at http://www.gnu.org.
HISTORY
--------------------------------------------------------------------------------
11/24/98 JSB Created
07/23/99 TP Added implementation of 1959 Standard Atmosphere
Moved calculation of Mach number to FGTranslation
********************************************************************************
SENTRY
*******************************************************************************/
@ -43,30 +43,26 @@ INCLUDES
*******************************************************************************/
#include "FGModel.h"
#include "FGMatrix.h"
/*******************************************************************************
COMMENTS, REFERENCES, and NOTES
********************************************************************************
[1] Anderson, John D. "Introduction to Flight, Third Edition", McGraw-Hill,
1989, ISBN 0-07-001641-0
*******************************************************************************
CLASS DECLARATION
*******************************************************************************/
using namespace std;
class FGAtmosphere : public FGModel
{
class FGAtmosphere : public FGModel {
public:
FGAtmosphere(FGFDMExec*);
~FGAtmosphere(void);
bool Run(void);
inline float GetTemperature(void){return temperature;}
inline float GetTemperature(void) {return temperature;}
inline float GetDensity(void) {return density;} // use only after Run() has been called
inline float GetPressure(void) {return pressure;}
inline float GetSoundSpeed(void) {return soundspeed;}
@ -75,19 +71,27 @@ public:
inline float GetDensitySL(void) { return SLdensity; } //slugs/ft^3
inline float GetPressureSL(void) { return SLpressure; } //lbs/ft^2
inline float GetSoundSpeedSL(void) { return SLsoundspeed; } //ft/s
inline float GetPressureRatio(void) { return temperature/SLtemperature; }
inline float GetTemperatureRatio(void) { return temperature/SLtemperature; }
inline float GetDensityRatio(void) { return density/SLdensity; }
inline float GetTemperatureRatio(void) { return pressure/SLpressure; }
inline float GetPressureRatio(void) { return pressure/SLpressure; }
inline float GetSoundSpeedRatio(void) { return soundspeed/SLsoundspeed; }
inline void UseExternal(void) { useExternal=true; }
inline void UseInternal(void) { useExternal=false; } //this is the default
inline void UseInternal(void) { useExternal=false; } //this is the default
inline void SetExTemperature(float t) { exTemperature=t; }
inline void SetExDensity(float d) { exDensity=d; }
inline void SetExPressure(float p) { exPressure=p; }
inline void SetWindNED(float wN, float wE, float wD) { vWindNED(1)=wN; vWindNED(2)=wE; vWindNED(3)=wD;}
inline float GetWindN(void) { return vWindNED(1); }
inline float GetWindE(void) { return vWindNED(2); }
inline float GetWindD(void) { return vWindNED(3); }
inline FGColumnVector GetWindUVW(void) { return vWindUVW; }
protected:
private:
@ -98,10 +102,13 @@ private:
float temperature,density,pressure,soundspeed;
bool useExternal;
float exTemperature,exDensity,exPressure;
void Calculate(float altitude);
FGColumnVector vWindNED,vWindUVW;
void Calculate(float altitude);
};
/******************************************************************************/
#endif

View file

@ -1,41 +1,41 @@
/*******************************************************************************
Module: FGAuxiliary.cpp
Author: Jon Berndt
Date started: 01/26/99
Purpose: Calculates additional parameters needed by the visual system, etc.
Called by: FGSimExec
------------- Copyright (C) 1999 Jon S. Berndt (jsb@hal-pc.org) -------------
This program is free software; you can redistribute it and/or modify it under
the terms of the GNU General Public License as published by the Free Software
Foundation; either version 2 of the License, or (at your option) any later
version.
This program is distributed in the hope that it will be useful, but WITHOUT
ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
FOR A PARTICULAR PURPOSE. See the GNU General Public License for more
details.
You should have received a copy of the GNU General Public License along with
this program; if not, write to the Free Software Foundation, Inc., 59 Temple
Place - Suite 330, Boston, MA 02111-1307, USA.
Further information about the GNU General Public License can also be found on
the world wide web at http://www.gnu.org.
FUNCTIONAL DESCRIPTION
--------------------------------------------------------------------------------
This class calculates various auxiliary parameters.
REFERENCES
Anderson, John D. "Introduction to Flight", 3rd Edition, McGraw-Hill, 1989
pgs. 112-126
HISTORY
--------------------------------------------------------------------------------
01/26/99 JSB Created
********************************************************************************
INCLUDES
*******************************************************************************/
@ -55,59 +55,57 @@ INCLUDES
************************************ CODE **************************************
*******************************************************************************/
FGAuxiliary::FGAuxiliary(FGFDMExec* fdmex) : FGModel(fdmex)
{
FGAuxiliary::FGAuxiliary(FGFDMExec* fdmex) : FGModel(fdmex) {
Name = "FGAuxiliary";
vcas = veas = mach = qbar = pt = 0;
psl = rhosl = 1;
}
FGAuxiliary::~FGAuxiliary()
{
}
FGAuxiliary::~FGAuxiliary() {}
bool FGAuxiliary::Run()
{
bool FGAuxiliary::Run() {
float A,B,D;
if (!FGModel::Run()) {
GetState();
if(mach < 1) //calculate total pressure assuming isentropic flow
pt=p*pow((1 + 0.2*mach*mach),3.5);
else
{
// shock in front of pitot tube, we'll assume its normal and use
// the Rayleigh Pitot Tube Formula, i.e. the ratio of total
// pressure behind the shock to the static pressure in front
else {
// shock in front of pitot tube, we'll assume its normal and use
// the Rayleigh Pitot Tube Formula, i.e. the ratio of total
// pressure behind the shock to the static pressure in front
B = 5.76*mach*mach/(5.6*mach*mach - 0.8);
B = 5.76*mach*mach/(5.6*mach*mach - 0.8);
// The denominator above is zero for Mach ~ 0.38, for which
// we'll never be here, so we're safe
// The denominator above is zero for Mach ~ 0.38, for which
// we'll never be here, so we're safe
D = (2.8*mach*mach-0.4)*0.4167;
pt = p*pow(B,3.5)*D;
}
A = pow(((pt-p)/psl+1),0.28571);
vcas = sqrt(7*psl/rhosl*(A-1));
veas = sqrt(2*qbar/rhosl);
D = (2.8*mach*mach-0.4)*0.4167;
pt = p*pow(B,3.5)*D;
}
A = pow(((pt-p)/psl+1),0.28571);
vcas = sqrt(7*psl/rhosl*(A-1));
veas = sqrt(2*qbar/rhosl);
} else {
}
return false;
}
void FGAuxiliary::GetState(void)
{
void FGAuxiliary::GetState(void) {
qbar = Translation->Getqbar();
mach = Translation->GetMach();
p = Atmosphere->GetPressure();
rhosl = Atmosphere->GetDensitySL();
psl = Atmosphere->GetPressureSL();
}

View file

@ -1,33 +1,33 @@
/*******************************************************************************
Header: FGAuxiliary.h
Author: Jon Berndt
Date started: 01/26/99
------------- Copyright (C) 1999 Jon S. Berndt (jsb@hal-pc.org) -------------
This program is free software; you can redistribute it and/or modify it under
the terms of the GNU General Public License as published by the Free Software
Foundation; either version 2 of the License, or (at your option) any later
version.
This program is distributed in the hope that it will be useful, but WITHOUT
ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
FOR A PARTICULAR PURPOSE. See the GNU General Public License for more
details.
You should have received a copy of the GNU General Public License along with
this program; if not, write to the Free Software Foundation, Inc., 59 Temple
Place - Suite 330, Boston, MA 02111-1307, USA.
Further information about the GNU General Public License can also be found on
the world wide web at http://www.gnu.org.
HISTORY
--------------------------------------------------------------------------------
11/22/98 JSB Created
1/1/00 TP Added calcs and getters for VTAS, VCAS, VEAS, Vground, in knots
********************************************************************************
SENTRY
*******************************************************************************/
@ -44,27 +44,25 @@ INCLUDES
DEFINES
*******************************************************************************/
using namespace std;
/*******************************************************************************
CLASS DECLARATION
*******************************************************************************/
class FGAuxiliary : public FGModel
{
class FGAuxiliary : public FGModel {
public:
FGAuxiliary(FGFDMExec*);
~FGAuxiliary(void);
bool Run(void);
//use FGInitialCondition to set these speeds
inline float GetVcalibratedFPS(void) { return vcas; }
inline float GetVcalibratedKTS(void) { return vcas*FPSTOKTS; }
inline float GetVequivalentFPS(void) { return veas; }
inline float GetVequivalentKTS(void) { return veas*FPSTOKTS; }
protected:
private:
@ -72,7 +70,13 @@ private:
float veas;
float mach;
float qbar,rhosl,rho,p,psl,pt;
//Don't add a getter for pt!
//pt above is freestream total pressure for subsonic only
//for supersonic it is the 1D total pressure behind a normal shock
//if a general freestream total is needed, e-mail Tony Peden
// (apeden@earthlink.net) or you can add it your self using the
// isentropic flow equations
void GetState(void);
};

View file

@ -37,14 +37,12 @@ SENTRY
/*******************************************************************************
INCLUDES
*******************************************************************************/
#ifdef FGFS
# include <simgear/compiler.h>
# include STL_STRING
FG_USING_STD(string);
#else
# include <string>
#endif
#include <string>
#include <map>
#include "FGConfigFile.h"
#include "FGDefs.h"
@ -53,8 +51,6 @@ INCLUDES
DEFINES
*******************************************************************************/
using namespace std;
/*******************************************************************************
FORWARD DECLARATIONS
*******************************************************************************/

View file

@ -40,24 +40,24 @@ INCLUDES
#ifdef FGFS
# include <simgear/compiler.h>
# include STL_STRING
# ifdef FG_HAVE_STD_INCLUDES
# include <fstream>
# else
# include <fstream.h>
# endif
FG_USING_STD(string);
#else
# include <string>
# include <fstream>
#endif
#include <string>
/*******************************************************************************
DEFINES
*******************************************************************************/
#ifndef FGFS
using namespace std;
using std::string;
using std::ifstream;
#endif
/*******************************************************************************

View file

@ -51,8 +51,36 @@ FGControls::~FGControls() {
// $Log$
// Revision 1.9 2000/04/28 17:59:46 curt
// 0429 updates from Jon.
// Revision 1.10 2000/05/16 19:35:11 curt
// Updates from the Jon and Tony show.
//
// Tony submitted:
//
// JSBsim:
// Added trimming routine, it is longitudinal & in-air only at this point
// Added support for taking wind & weather data from external source
// Added support for flaps.
// Added independently settable pitch trim
// Added alphamin and max to config file, stall modeling and warning to
// follow
//
// c172.cfg:
// Flaps!
// Adjusted Cmo, model should be speed stable now
//
// FG:
// Hooked up Christian's weather code, should be using it soon.
// Hooked up the trimming routine. Note that the X-15 will not trim.
// This is not a model or trimming routine deficiency, just the
// nature of the X-15
// The trimming routine sets the pitch trim and and throttle at startup.
// The throttle is set using Norman's code for the autothrottle so the
// autothrottle is on by default. --notrim will turn it off.
// Added --vc, --mach, and --notrim switches
// (vc is airspeed in knots)
// uBody, vBody, and wBody are still supported, last one entered
// on the command line counts, i.e. you can set vc or mach or u,v,
// and w but any combination will be ignored.
//
// Revision 1.3 2000/04/26 10:55:57 jsb
// Made changes as required by Curt to install JSBSim into FGFS

View file

@ -30,8 +30,6 @@
# error This library requires C++
#endif
//using namespace std;
// Define a structure containing the control parameters
class FGControls {
@ -177,8 +175,39 @@ extern FGControls controls;
// $Log$
// Revision 1.8 2000/04/28 17:59:46 curt
// 0429 updates from Jon.
// Revision 1.9 2000/05/16 19:35:11 curt
// Updates from the Jon and Tony show.
//
// Tony submitted:
//
// JSBsim:
// Added trimming routine, it is longitudinal & in-air only at this point
// Added support for taking wind & weather data from external source
// Added support for flaps.
// Added independently settable pitch trim
// Added alphamin and max to config file, stall modeling and warning to
// follow
//
// c172.cfg:
// Flaps!
// Adjusted Cmo, model should be speed stable now
//
// FG:
// Hooked up Christian's weather code, should be using it soon.
// Hooked up the trimming routine. Note that the X-15 will not trim.
// This is not a model or trimming routine deficiency, just the
// nature of the X-15
// The trimming routine sets the pitch trim and and throttle at startup.
// The throttle is set using Norman's code for the autothrottle so the
// autothrottle is on by default. --notrim will turn it off.
// Added --vc, --mach, and --notrim switches
// (vc is airspeed in knots)
// uBody, vBody, and wBody are still supported, last one entered
// on the command line counts, i.e. you can set vc or mach or u,v,
// and w but any combination will be ignored.
//
// Revision 1.5 2000/05/12 22:45:35 jsb
// Removed extraneous namespace identifiers and header files
//
// Revision 1.4 2000/04/26 10:55:57 jsb
// Made changes as required by Curt to install JSBSim into FGFS

View file

@ -1,32 +1,32 @@
/*******************************************************************************
Header: FGDefs.h
Author: Jon S. Berndt
Date started: 02/01/99
------------- Copyright (C) 1999 Jon S. Berndt (jsb@hal-pc.org) -------------
This program is free software; you can redistribute it and/or modify it under
the terms of the GNU General Public License as published by the Free Software
Foundation; either version 2 of the License, or (at your option) any later
version.
This program is distributed in the hope that it will be useful, but WITHOUT
ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
FOR A PARTICULAR PURPOSE. See the GNU General Public License for more
details.
You should have received a copy of the GNU General Public License along with
this program; if not, write to the Free Software Foundation, Inc., 59 Temple
Place - Suite 330, Boston, MA 02111-1307, USA.
Further information about the GNU General Public License can also be found on
the world wide web at http://www.gnu.org.
HISTORY
--------------------------------------------------------------------------------
02/01/99 JSB Created
********************************************************************************
SENTRY
*******************************************************************************/
@ -37,6 +37,7 @@ SENTRY
#define MAX_ENGINES 10
#define MAX_TANKS 30
#define GRAVITY 32.174
#define INVGRAVITY 0.031081
#define EARTHRAD 20898908.00 // feet
#define OMEGAEARTH 7.2685E-3 // rad/sec
#define EARTHRADSQRD 437882827922500.0
@ -52,7 +53,7 @@ SENTRY
#define DEGTORAD 1.745329E-2
#define KTSTOFPS 1.68781
#define FPSTOKTS 0.592484
#define NEEDED_CFG_VERSION 1.30
#define NEEDED_CFG_VERSION "1.30"
#define HPTOFTLBSSEC 550
#define METERS_TO_FEET 3.2808
@ -84,10 +85,10 @@ SENTRY
#define FG_SPDBRAKE_CMD 16777216L
#define FG_SPOILERS_CMD 33554432L
#define FG_FLAPS_CMD 67108864L
#define FG_SPARE3 134217728L
#define FG_SPARE4 268435456L
#define FG_SPARE5 536870912L
#define FG_SPARE6 1073741824L
#define FG_THROTTLE_CMD 134217728L
#define FG_THROTTLE_POS 268435456L
#define FG_HOVERB 536870912L
#define FG_PITCH_TRIM_CMD 1073741824L
/******************************************************************************/
#endif

View file

@ -1,39 +1,39 @@
/*******************************************************************************
Module: FGEngine.cpp
Author: Jon Berndt
Date started: 01/21/99
Called by: FGAircraft
------------- Copyright (C) 1999 Jon S. Berndt (jsb@hal-pc.org) -------------
This program is free software; you can redistribute it and/or modify it under
the terms of the GNU General Public License as published by the Free Software
Foundation; either version 2 of the License, or (at your option) any later
version.
This program is distributed in the hope that it will be useful, but WITHOUT
ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
FOR A PARTICULAR PURPOSE. See the GNU General Public License for more
details.
You should have received a copy of the GNU General Public License along with
this program; if not, write to the Free Software Foundation, Inc., 59 Temple
Place - Suite 330, Boston, MA 02111-1307, USA.
Further information about the GNU General Public License can also be found on
the world wide web at http://www.gnu.org.
FUNCTIONAL DESCRIPTION
--------------------------------------------------------------------------------
See header file.
HISTORY
--------------------------------------------------------------------------------
01/21/99 JSB Created
09/03/99 JSB Changed Rocket thrust equation to correct -= Thrust instead of
+= Thrust (thanks to Tony Peden)
********************************************************************************
INCLUDES
*******************************************************************************/
@ -67,8 +67,7 @@ INCLUDES
*******************************************************************************/
FGEngine::FGEngine(FGFDMExec* fdex, string enginePath, string engineName, int num)
{
FGEngine::FGEngine(FGFDMExec* fdex, string enginePath, string engineName, int num) {
string fullpath;
string tag;
@ -97,8 +96,7 @@ FGEngine::FGEngine(FGFDMExec* fdex, string enginePath, string engineName, int nu
else if (tag == "TURBOJET") Type = etTurboJet;
else Type = etUnknown;
switch(Type)
{
switch(Type) {
case etUnknown:
cerr << "Unknown engine type: " << tag << endl;
break;
@ -139,13 +137,11 @@ FGEngine::FGEngine(FGFDMExec* fdex, string enginePath, string engineName, int nu
}
FGEngine::~FGEngine(void)
{
}
FGEngine::~FGEngine(void) {}
float FGEngine::CalcRocketThrust(void)
{
float FGEngine::CalcRocketThrust(void) {
float lastThrust;
Throttle = FCS->GetThrottlePos(EngineNumber);
@ -161,14 +157,14 @@ float FGEngine::CalcRocketThrust(void)
Flameout = false;
}
Thrust -= 0.8*(Thrust - lastThrust); // actual thrust
return Thrust;
}
float FGEngine::CalcPistonThrust(void)
{
float FGEngine::CalcPistonThrust(void) {
float v,h,pa;
Throttle = FCS->GetThrottlePos(EngineNumber);
@ -180,15 +176,16 @@ float FGEngine::CalcPistonThrust(void)
v=10;
if(h < 0)
h=0;
pa=(SpeedSlope*v + SpeedIntercept)*(1 +AltitudeSlope*h)*BrakeHorsePower;
Thrust= Throttle*(pa*HPTOFTLBSSEC)/v;
return Thrust;
}
float FGEngine::CalcThrust(void)
{
float FGEngine::CalcThrust(void) {
switch(Type) {
case etRocket:
return CalcRocketThrust();
@ -200,6 +197,7 @@ float FGEngine::CalcThrust(void)
return 9999.0;
// break;
}
}
float FGEngine::CalcFuelNeed() {

View file

@ -1,38 +1,38 @@
/*******************************************************************************
Header: FGEngine.h
Author: Jon S. Berndt
Date started: 01/21/99
------------- Copyright (C) 1999 Jon S. Berndt (jsb@hal-pc.org) -------------
This program is free software; you can redistribute it and/or modify it under
the terms of the GNU General Public License as published by the Free Software
Foundation; either version 2 of the License, or (at your option) any later
version.
This program is distributed in the hope that it will be useful, but WITHOUT
ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
FOR A PARTICULAR PURPOSE. See the GNU General Public License for more
details.
You should have received a copy of the GNU General Public License along with
this program; if not, write to the Free Software Foundation, Inc., 59 Temple
Place - Suite 330, Boston, MA 02111-1307, USA.
Further information about the GNU General Public License can also be found on
the world wide web at http://www.gnu.org.
FUNCTIONAL DESCRIPTION
--------------------------------------------------------------------------------
Based on Flightgear code, which is based on LaRCSim. This class simulates
a generic engine.
HISTORY
--------------------------------------------------------------------------------
01/21/99 JSB Created
********************************************************************************
SENTRY
*******************************************************************************/
@ -56,7 +56,7 @@ FG_USING_STD(string);
DEFINES
*******************************************************************************/
using namespace std;
using std::string;
/*******************************************************************************
CLASS DECLARATION
@ -73,23 +73,28 @@ class FGPosition;
class FGAuxiliary;
class FGOutput;
class FGEngine
{
class FGEngine {
public:
FGEngine(FGFDMExec*, string, string, int);
~FGEngine(void);
enum EngineType {etUnknown, etRocket, etPiston, etTurboProp, etTurboJet};
float GetThrottle(void) {return Throttle;}
float GetThrust(void) {return Thrust;}
bool GetStarved(void) {return Starved;}
bool GetFlameout(void) {return Flameout;}
int GetType(void) {return Type;}
string GetName() {return Name;}
float GetThrottle(void) { return Throttle; }
float GetThrust(void) { return Thrust; }
float GetThrottleMin(void) { return MinThrottle; }
float GetThrottleMax(void) { return MaxThrottle; }
bool GetStarved(void) { return Starved; }
bool GetFlameout(void) { return Flameout; }
int GetType(void) { return Type; }
string GetName() { return Name; }
void SetStarved(bool tt) {Starved = tt;}
void SetStarved(void) {Starved = true;}
void SetStarved(bool tt) {
Starved = tt;
}
void SetStarved(void) {
Starved = true;
}
float CalcThrust(void);
float CalcFuelNeed(void);

View file

@ -1,38 +1,38 @@
/*******************************************************************************
Module: FGFCS.cpp
Author: Jon Berndt
Date started: 12/12/98
Purpose: Model the flight controls
Called by: FDMExec
------------- Copyright (C) 1999 Jon S. Berndt (jsb@hal-pc.org) -------------
This program is free software; you can redistribute it and/or modify it under
the terms of the GNU General Public License as published by the Free Software
Foundation; either version 2 of the License, or (at your option) any later
version.
This program is distributed in the hope that it will be useful, but WITHOUT
ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
FOR A PARTICULAR PURPOSE. See the GNU General Public License for more
details.
You should have received a copy of the GNU General Public License along with
this program; if not, write to the Free Software Foundation, Inc., 59 Temple
Place - Suite 330, Boston, MA 02111-1307, USA.
Further information about the GNU General Public License can also be found on
the world wide web at http://www.gnu.org.
FUNCTIONAL DESCRIPTION
--------------------------------------------------------------------------------
This class models the flight controls for a specific airplane
HISTORY
--------------------------------------------------------------------------------
12/12/98 JSB Created
********************************************************************************
INCLUDES
*******************************************************************************/
@ -54,14 +54,14 @@ INCLUDES
#include "filtersjb/FGGradient.h"
#include "filtersjb/FGSwitch.h"
#include "filtersjb/FGSummer.h"
#include "filtersjb/FGFlaps.h"
/*******************************************************************************
************************************ CODE **************************************
*******************************************************************************/
FGFCS::FGFCS(FGFDMExec* fdmex) : FGModel(fdmex)
{
FGFCS::FGFCS(FGFDMExec* fdmex) : FGModel(fdmex) {
Name = "FGFCS";
for (int i=0; i < MAX_ENGINES; i++) {
ThrottleCmd[i] = 0.0;
@ -73,27 +73,26 @@ FGFCS::FGFCS(FGFDMExec* fdmex) : FGModel(fdmex)
/******************************************************************************/
FGFCS::~FGFCS(void)
{
}
FGFCS::~FGFCS(void) {}
/******************************************************************************/
bool FGFCS::Run(void)
{
bool FGFCS::Run(void) {
if (!FGModel::Run()) {
for (unsigned int i=0; i<Aircraft->GetNumEngines(); i++) ThrottlePos[i]=ThrottleCmd[i];
for (unsigned int i=0; i<Components.size(); i++) Components[i]->Run();
} else {
}
} else {}
return false;
}
/******************************************************************************/
void FGFCS::SetThrottleCmd(int engineNum, float setting)
{
void FGFCS::SetThrottleCmd(int engineNum, float setting) {
if (engineNum < 0) {
for (int ctr=0;ctr<Aircraft->GetNumEngines();ctr++) ThrottleCmd[ctr] = setting;
} else {
@ -103,10 +102,9 @@ void FGFCS::SetThrottleCmd(int engineNum, float setting)
/******************************************************************************/
void FGFCS::SetThrottlePos(int engineNum, float setting)
{
void FGFCS::SetThrottlePos(int engineNum, float setting) {
if (engineNum < 0) {
for (int ctr=0;ctr<Aircraft->GetNumEngines();ctr++) ThrottlePos[ctr] = ThrottleCmd[ctr];
for (int ctr=0;ctr<=Aircraft->GetNumEngines();ctr++) ThrottlePos[ctr] = ThrottleCmd[ctr];
} else {
ThrottlePos[engineNum] = setting;
}
@ -114,38 +112,39 @@ void FGFCS::SetThrottlePos(int engineNum, float setting)
/******************************************************************************/
#pragma warn -8030
bool FGFCS::LoadFCS(FGConfigFile* AC_cfg)
{
bool FGFCS::LoadFCS(FGConfigFile* AC_cfg) {
string token;
FCSName = AC_cfg->GetValue("NAME");
cout << " Control System Name: " << FCSName << endl;
AC_cfg->GetNextConfigLine();
while ((token = AC_cfg->GetValue()) != "/FLIGHT_CONTROL") {
if (token == "COMPONENT") {
if (((token = AC_cfg->GetValue("TYPE")) == "LAG_FILTER") ||
token = AC_cfg->GetValue("TYPE");
cout << " Loading Component \"" << AC_cfg->GetValue("NAME") << "\" of type: " << token << endl;
if ((token == "LAG_FILTER") ||
(token == "RECT_LAG_FILTER") ||
(token == "LEAD_LAG_FILTER") ||
(token == "SECOND_ORDER_FILTER") ||
(token == "WASHOUT_FILTER") ||
(token == "INTEGRATOR") )
{
Components.push_back(new FGFilter(this, AC_cfg));
(token == "INTEGRATOR") ) {
Components.push_back(new FGFilter(this, AC_cfg));
} else if ((token == "PURE_GAIN") ||
(token == "SCHEDULED_GAIN") ||
(token == "AEROSURFACE_SCALE") )
{
Components.push_back(new FGGain(this, AC_cfg));
(token == "SCHEDULED_GAIN") ||
(token == "AEROSURFACE_SCALE") ) {
Components.push_back(new FGGain(this, AC_cfg));
} else if (token == "SUMMER") {
Components.push_back(new FGSummer(this, AC_cfg));
Components.push_back(new FGSummer(this, AC_cfg));
} else if (token == "DEADBAND") {
Components.push_back(new FGDeadBand(this, AC_cfg));
Components.push_back(new FGDeadBand(this, AC_cfg));
} else if (token == "GRADIENT") {
Components.push_back(new FGGradient(this, AC_cfg));
Components.push_back(new FGGradient(this, AC_cfg));
} else if (token == "SWITCH") {
Components.push_back(new FGSwitch(this, AC_cfg));
Components.push_back(new FGSwitch(this, AC_cfg));
} else if (token == "FLAPS") {
Components.push_back(new FGFlaps(this, AC_cfg));
}
AC_cfg->GetNextConfigLine();
}
@ -153,20 +152,17 @@ bool FGFCS::LoadFCS(FGConfigFile* AC_cfg)
return true;
}
#pragma warn .8030
/******************************************************************************/
float FGFCS::GetComponentOutput(int idx)
{
float FGFCS::GetComponentOutput(int idx) {
return Components[idx]->GetOutput();
}
/******************************************************************************/
string FGFCS::GetComponentName(int idx)
{
string FGFCS::GetComponentName(int idx) {
return Components[idx]->GetName();
}
#pragma warn .8030

View file

@ -1,32 +1,32 @@
/*******************************************************************************
Header: FGGFCS.h
Author: Jon S. Berndt
Date started: 12/12/98
------------- Copyright (C) 1999 Jon S. Berndt (jsb@hal-pc.org) -------------
This program is free software; you can redistribute it and/or modify it under
the terms of the GNU General Public License as published by the Free Software
Foundation; either version 2 of the License, or (at your option) any later
version.
This program is distributed in the hope that it will be useful, but WITHOUT
ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
FOR A PARTICULAR PURPOSE. See the GNU General Public License for more
details.
You should have received a copy of the GNU General Public License along with
this program; if not, write to the Free Software Foundation, Inc., 59 Temple
Place - Suite 330, Boston, MA 02111-1307, USA.
Further information about the GNU General Public License can also be found on
the world wide web at http://www.gnu.org.
HISTORY
--------------------------------------------------------------------------------
12/12/98 JSB Created
********************************************************************************
SENTRY
*******************************************************************************/
@ -40,8 +40,6 @@ INCLUDES
#ifdef FGFS
# include <simgear/compiler.h>
# include STL_STRING
FG_USING_STD(string);
# ifdef FG_HAVE_STD_INCLUDES
# include <vector>
# else
@ -52,6 +50,7 @@ INCLUDES
# include <string>
#endif
#include <string>
#include "filtersjb/FGFCSComponent.h"
#include "FGModel.h"
#include "FGConfigFile.h"
@ -61,59 +60,62 @@ INCLUDES
CLASS DECLARATION
*******************************************************************************/
using namespace std;
class FGFCS : public FGModel
{
class FGFCS : public FGModel {
private:
float DaCmd, DeCmd, DrCmd, DfCmd, DsbCmd, DspCmd;
float DaPos, DePos, DrPos, DfPos, DsbPos, DspPos;
float PTrimCmd;
float ThrottleCmd[MAX_ENGINES];
float ThrottlePos[MAX_ENGINES];
vector <FGFCSComponent*> Components;
public:
FGFCS(FGFDMExec*);
~FGFCS(void);
FGFCS(FGFDMExec*);
~FGFCS(void);
bool Run(void);
bool Run(void);
inline float GetDaCmd(void) {return DaCmd;}
inline float GetDeCmd(void) {return DeCmd;}
inline float GetDrCmd(void) {return DrCmd;}
inline float GetDfCmd(void) {return DfCmd;}
inline float GetDsbCmd(void) {return DsbCmd;}
inline float GetDspCmd(void) {return DspCmd;}
inline float GetThrottleCmd(int ii) {return ThrottleCmd[ii];}
inline float GetDaCmd(void) { return DaCmd; }
inline float GetDeCmd(void) { return DeCmd; }
inline float GetDrCmd(void) { return DrCmd; }
inline float GetDfCmd(void) { return DfCmd; }
inline float GetDsbCmd(void) { return DsbCmd; }
inline float GetDspCmd(void) { return DspCmd; }
inline float GetThrottleCmd(int ii) { return ThrottleCmd[ii]; }
inline float GetPitchTrimCmd(void) { return PTrimCmd; }
inline float GetDaPos(void) {return DaPos;}
inline float GetDePos(void) {return DePos;}
inline float GetDrPos(void) {return DrPos;}
inline float GetDfPos(void) {return DfPos;}
inline float GetDsbPos(void) {return DsbPos;}
inline float GetDspPos(void) {return DspPos;}
inline float GetThrottlePos(int ii) {return ThrottlePos[ii];}
inline float GetDaPos(void) { return DaPos; }
inline float GetDePos(void) { return DePos; }
inline float GetDrPos(void) { return DrPos; }
inline float GetDfPos(void) { return DfPos; }
inline float GetDsbPos(void) { return DsbPos; }
inline float GetDspPos(void) { return DspPos; }
inline FGState* GetState(void) {return State;}
inline float GetThrottlePos(int ii) { return ThrottlePos[ii]; }
inline FGState* GetState(void) { return State; }
float GetComponentOutput(int idx);
string GetComponentName(int idx);
inline void SetDaCmd(float tt) {DaCmd = tt;}
inline void SetDeCmd(float tt) {DeCmd = tt;}
inline void SetDrCmd(float tt) {DrCmd = tt;}
inline void SetDfCmd(float tt) {DfCmd = tt;}
inline void SetDsbCmd(float tt) {DsbCmd = tt;}
inline void SetDspCmd(float tt) {DspCmd = tt;}
void SetThrottleCmd(int ii, float tt);
inline void SetDaCmd(float tt) { DaCmd = tt; }
inline void SetDeCmd(float tt) { DeCmd = tt; }
inline void SetDrCmd(float tt) { DrCmd = tt; }
inline void SetDfCmd(float tt) { DfCmd = tt; }
inline void SetDsbCmd(float tt) { DsbCmd = tt; }
inline void SetDspCmd(float tt) { DspCmd = tt; }
inline void SetPitchTrimCmd(float tt) { PTrimCmd = tt; }
inline void SetDaPos(float tt) {DaPos = tt;}
inline void SetDePos(float tt) {DePos = tt;}
inline void SetDrPos(float tt) {DrPos = tt;}
inline void SetDfPos(float tt) {DfPos = tt;}
inline void SetDsbPos(float tt) {DsbPos = tt;}
inline void SetDspPos(float tt) {DspPos = tt;}
void SetThrottlePos(int ii, float tt);
void SetThrottleCmd(int ii, float tt);
inline void SetDaPos(float tt) { DaPos = tt; }
inline void SetDePos(float tt) { DePos = tt; }
inline void SetDrPos(float tt) { DrPos = tt; }
inline void SetDfPos(float tt) { DfPos = tt; }
inline void SetDsbPos(float tt) { DsbPos = tt; }
inline void SetDspPos(float tt) { DspPos = tt; }
void SetThrottlePos(int ii, float tt);
bool LoadFCS(FGConfigFile* AC_cfg);
string FCSName;

View file

@ -44,8 +44,6 @@ INCLUDES
#include "FGModel.h"
#include "FGInitialCondition.h"
using namespace std;
/*******************************************************************************
CLASS DECLARATION
*******************************************************************************/

View file

@ -1,49 +1,49 @@
/*******************************************************************************
Header: FGInitialCondition.cpp
Author: Tony Peden
Date started: 7/1/99
------------- Copyright (C) 1999 Anthony K. Peden (apeden@earthlink.net) -------------
This program is free software; you can redistribute it and/or modify it under
the terms of the GNU General Public License as published by the Free Software
Foundation; either version 2 of the License, or (at your option) any later
version.
This program is distributed in the hope that it will be useful, but WITHOUT
ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
FOR A PARTICULAR PURPOSE. See the GNU General Public License for more
details.
You should have received a copy of the GNU General Public License along with
this program; if not, write to the Free Software Foundation, Inc., 59 Temple
Place - Suite 330, Boston, MA 02111-1307, USA.
Further information about the GNU General Public License can also be found on
the world wide web at http://www.gnu.org.
HISTORY
--------------------------------------------------------------------------------
7/1/99 TP Created
FUNCTIONAL DESCRIPTION
--------------------------------------------------------------------------------
The purpose of this class is to take a set of initial conditions and provide
a kinematically consistent set of body axis velocity components, euler
angles, and altitude. This class does not attempt to trim the model i.e.
the sim will most likely start in a very dynamic state (unless, of course,
you have chosen your IC's wisely) even after setting it up with this class.
CAVEAT: This class makes use of alpha=theta-gamma. This means that setting
any of the three with this class is only valid for steady state
(all accels zero) and zero pitch rate. One example where this
would produce invalid results is setting up for a trim in a pull-up
or pushover (both have nonzero pitch rate). Maybe someday...
********************************************************************************
INCLUDES
*******************************************************************************/
@ -61,246 +61,196 @@ INCLUDES
#include "FGOutput.h"
#include "FGDefs.h"
FGInitialCondition::FGInitialCondition(FGFDMExec *FDMExec)
{
vt=vc=0;
mach=0;
alpha=beta=gamma=0;
theta=phi=psi=0;
altitude=hdot=0;
latitude=longitude=0;
FGInitialCondition::FGInitialCondition(FGFDMExec *FDMExec) {
vt=vc=ve=0;
mach=0;
alpha=beta=gamma=0;
theta=phi=psi=0;
altitude=hdot=0;
latitude=longitude=0;
u=v=w=0;
lastSpeedSet=setvt;
if(fdmex != NULL ) {
fdmex=FDMExec;
fdmex->GetPosition()->Seth(altitude);
fdmex->GetAtmosphere()->Run();
} else {
cout << "FGInitialCondition: This class requires a pointer to an initialized FGFDMExec object" << endl;
}
}
FGInitialCondition::~FGInitialCondition(void) {};
FGInitialCondition::~FGInitialCondition(void) {}
;
void FGInitialCondition::SetVcalibratedKtsIC(float tt)
{
void FGInitialCondition::SetVcalibratedKtsIC(float tt) {
if(getMachFromVcas(&mach,tt*KTSTOFPS)) {
//cout << "Mach: " << mach << endl;
lastSpeedSet=setvc;
vc=tt*KTSTOFPS;
if(getMachFromVcas(&mach,vc)) {
vt=mach*fdmex->GetAtmosphere()->GetSoundSpeed();
}
}
void FGInitialCondition::SetVtrueKtsIC(float tt)
{
vt=tt*KTSTOFPS;
mach=vt/fdmex->GetAtmosphere()->GetSoundSpeed();
vc=calcVcas(mach);
}
void FGInitialCondition::SetMachIC(float tt)
{
mach=tt;
vt=mach*fdmex->GetAtmosphere()->GetSoundSpeed();
vc=calcVcas(mach);
ve=vt*sqrt(fdmex->GetAtmosphere()->GetDensityRatio());
//cout << "Vt: " << vt*FPSTOKTS << " Vc: " << vc*FPSTOKTS << endl;
}
else {
cout << "Failed to get Mach number for given Vc and altitude, Vc unchanged." << endl;
cout << "Please mail the set of initial conditions used to apeden@earthlink.net" << endl;
}
}
void FGInitialCondition::SetVequivalentKtsIC(float tt) {
ve=tt*KTSTOFPS;
lastSpeedSet=setve;
vt=ve*1/sqrt(fdmex->GetAtmosphere()->GetDensityRatio());
mach=vt/fdmex->GetAtmosphere()->GetSoundSpeed();
vc=calcVcas(mach);
}
void FGInitialCondition::SetVtrueKtsIC(float tt) {
vt=tt*KTSTOFPS;
lastSpeedSet=setvt;
mach=vt/fdmex->GetAtmosphere()->GetSoundSpeed();
vc=calcVcas(mach);
ve=vt*sqrt(fdmex->GetAtmosphere()->GetDensityRatio());
}
void FGInitialCondition::SetMachIC(float tt) {
mach=tt;
lastSpeedSet=setmach;
vt=mach*fdmex->GetAtmosphere()->GetSoundSpeed();
vc=calcVcas(mach);
ve=vt*sqrt(fdmex->GetAtmosphere()->GetDensityRatio());
//cout << "Vt: " << vt*FPSTOKTS << " Vc: " << vc*FPSTOKTS << endl;
}
void FGInitialCondition::SetAltitudeFtIC(float tt)
{
altitude=tt;
fdmex->GetPosition()->Seth(altitude);
fdmex->GetAtmosphere()->Run();
mach=vt/fdmex->GetAtmosphere()->GetSoundSpeed();
vc=calcVcas(mach);
void FGInitialCondition::SetClimbRateFpmIC(float tt) {
if(vt != 0) {
hdot=tt/60;
gamma=asin(hdot/vt);
}
}
void FGInitialCondition::SetUBodyFpsIC(float tt) {
u=tt;
vt=sqrt(u*u+v*v+w*w);
lastSpeedSet=setvt;
}
void FGInitialCondition::SetVBodyFpsIC(float tt) {
v=tt;
vt=sqrt(u*u+v*v+w*w);
lastSpeedSet=setvt;
}
void FGInitialCondition::SetWBodyFpsIC(float tt) {
w=tt;
vt=sqrt(u*u+v*v+w*w);
lastSpeedSet=setvt;
}
void FGInitialCondition::SetFlightPathAngleDegIC(float tt)
{
gamma=tt*DEGTORAD;
theta=alpha+gamma;
}
void FGInitialCondition::SetAlphaDegIC(float tt)
{
alpha=tt*DEGTORAD;
theta=alpha+gamma;
}
void FGInitialCondition::SetBetaDegIC(float tt)
{
beta=tt*DEGTORAD;
}
void FGInitialCondition::SetRollAngleDegIC(float tt)
{
phi=tt*DEGTORAD;
}
void FGInitialCondition::SetPitchAngleDegIC(float tt)
{
theta=tt*DEGTORAD;
alpha=theta-gamma;
}
void FGInitialCondition::SetHeadingDegIC(float tt)
{
psi=tt*DEGTORAD;
}
void FGInitialCondition::SetLatitudeDegIC(float tt)
{
latitude=tt*DEGTORAD;
}
void FGInitialCondition::SetLongitudeDegIC(float tt)
{
longitude=tt*DEGTORAD;
}
float FGInitialCondition::GetUBodyFpsIC(void)
{
return vt*cos(alpha)*cos(beta);
}
float FGInitialCondition::GetVBodyFpsIC(void)
{
return vt*sin(beta);
}
float FGInitialCondition::GetWBodyFpsIC(void)
{
return vt*sin(alpha)*cos(beta);
}
float FGInitialCondition::GetThetaRadIC(void)
{
return theta;
}
float FGInitialCondition::GetPhiRadIC(void)
{
return phi;
}
float FGInitialCondition::GetPsiRadIC(void)
{
return psi;
}
float FGInitialCondition::GetLatitudeRadIC(void)
{
return latitude;
}
float FGInitialCondition::GetLongitudeRadIC(void)
{
return longitude;
}
float FGInitialCondition::GetAltitudeFtIC(void)
{
return altitude;
void FGInitialCondition::SetAltitudeFtIC(float tt) {
altitude=tt;
fdmex->GetPosition()->Seth(altitude);
fdmex->GetAtmosphere()->Run();
//lets try to make sure the user gets what they intended
switch(lastSpeedSet) {
setvt:
SetVtrueKtsIC(vt);
break;
setvc:
SetVcalibratedKtsIC(vc);
break;
setve:
SetVequivalentKtsIC(ve);
break;
setmach:
SetMachIC(mach);
break;
}
}
float FGInitialCondition::calcVcas(float Mach) {
float p=fdmex->GetAtmosphere()->GetPressure();
float psl=fdmex->GetAtmosphere()->GetPressureSL();
float rhosl=fdmex->GetAtmosphere()->GetDensitySL();
float pt,A,B,D,vcas;
float p=fdmex->GetAtmosphere()->GetPressure();
float psl=fdmex->GetAtmosphere()->GetPressureSL();
float rhosl=fdmex->GetAtmosphere()->GetDensitySL();
float pt,A,B,D,vcas;
if(Mach < 1) //calculate total pressure assuming isentropic flow
pt=p*pow((1 + 0.2*Mach*Mach),3.5);
else
{
// shock in front of pitot tube, we'll assume its normal and use
// the Rayleigh Pitot Tube Formula, i.e. the ratio of total
// pressure behind the shock to the static pressure in front
if(Mach < 1) //calculate total pressure assuming isentropic flow
pt=p*pow((1 + 0.2*Mach*Mach),3.5);
else {
// shock in front of pitot tube, we'll assume its normal and use
// the Rayleigh Pitot Tube Formula, i.e. the ratio of total
// pressure behind the shock to the static pressure in front
//the normal shock assumption should not be a bad one -- most supersonic
//aircraft place the pitot probe out front so that it is the forward
//most point on the aircraft. The real shock would, of course, take
//on something like the shape of a rounded-off cone but, here again,
//the assumption should be good since the opening of the pitot probe
//is very small and, therefore, the effects of the shock curvature
//should be small as well. AFAIK, this approach is fairly well accepted
//within the aerospace community
//the normal shock assumption should not be a bad one -- most supersonic
//aircraft place the pitot probe out front so that it is the forward
//most point on the aircraft. The real shock would, of course, take
//on something like the shape of a rounded-off cone but, here again,
//the assumption should be good since the opening of the pitot probe
//is very small and, therefore, the effects of the shock curvature
//should be small as well. AFAIK, this approach is fairly well accepted
//within the aerospace community
B = 5.76*Mach*Mach/(5.6*Mach*Mach - 0.8);
B = 5.76*Mach*Mach/(5.6*Mach*Mach - 0.8);
// The denominator above is zero for Mach ~ 0.38, for which
// we'll never be here, so we're safe
// The denominator above is zero for Mach ~ 0.38, for which
// we'll never be here, so we're safe
D = (2.8*Mach*Mach-0.4)*0.4167;
pt = p*pow(B,3.5)*D;
}
D = (2.8*Mach*Mach-0.4)*0.4167;
pt = p*pow(B,3.5)*D;
}
A = pow(((pt-p)/psl+1),0.28571);
vcas = sqrt(7*psl/rhosl*(A-1));
//cout << "calcVcas: vcas= " << vcas*FPSTOKTS << " mach= " << Mach << " pressure: " << p << endl;
return vcas;
A = pow(((pt-p)/psl+1),0.28571);
vcas = sqrt(7*psl/rhosl*(A-1));
//cout << "calcVcas: vcas= " << vcas*FPSTOKTS << " mach= " << Mach << " pressure: " << p << endl;
return vcas;
}
bool FGInitialCondition::findMachInterval(float *mlo, float *mhi, float vcas) {
//void find_interval(inter_params &ip,eqfunc f,float y,float constant, int &flag){
//void find_interval(inter_params &ip,eqfunc f,float y,float constant, int &flag){
int i=0;
bool found=false;
float flo,fhi,fguess;
float lo,hi,guess,step;
step=0.1;
guess=1.5;
fguess=calcVcas(guess)-vcas;
lo=hi=guess;
do{
step=2*step;
lo-=step;
if(lo < 0)
lo=0;
hi+=step;
i++;
flo=calcVcas(lo)-vcas;
fhi=calcVcas(hi)-vcas;
if(flo*fhi <=0){ //found interval with root
found=true;
if(flo*fguess <= 0){ //narrow interval down a bit
hi=lo+step; //to pass solver interval that is as
//small as possible
}
else if(fhi*fguess <= 0){
lo=hi-step;
}
}
//cout << "findMachInterval: i=" << i << " Lo= " << lo << " Hi= " << hi << endl;
int i=0;
bool found=false;
float flo,fhi,fguess;
float lo,hi,guess,step;
step=0.1;
guess=1.5;
fguess=calcVcas(guess)-vcas;
lo=hi=guess;
do {
step=2*step;
lo-=step;
if(lo < 0)
lo=0;
hi+=step;
i++;
flo=calcVcas(lo)-vcas;
fhi=calcVcas(hi)-vcas;
if(flo*fhi <=0) { //found interval with root
found=true;
if(flo*fguess <= 0) { //narrow interval down a bit
hi=lo+step; //to pass solver interval that is as
//small as possible
}
else if(fhi*fguess <= 0) {
lo=hi-step;
}
}
while((found == 0) && (i <= 100));
*mlo=lo;
*mhi=hi;
return found;
//cout << "findMachInterval: i=" << i << " Lo= " << lo << " Hi= " << hi << endl;
}
while((found == 0) && (i <= 100));
*mlo=lo;
*mhi=hi;
return found;
}
@ -308,44 +258,46 @@ bool FGInitialCondition::findMachInterval(float *mlo, float *mhi, float vcas) {
bool FGInitialCondition::getMachFromVcas(float *Mach,float vcas) {
float x1,x2,x3,f1,f2,f3,d,d0;
float eps=1E-3;
float const relax =0.9;
int i;
bool success=false;
//initializations
if(findMachInterval(&x1,&x3,vcas)) {
float x1,x2,x3,f1,f2,f3,d,d0;
float eps=1E-3;
float const relax =0.9;
int i;
bool success=false;
f1=calcVcas(x1)-vcas;
f3=calcVcas(x3)-vcas;
d0=fabs(x3-x1);
//initializations
d=1;
if(findMachInterval(&x1,&x3,vcas)) {
//iterations
i=0;
while ((fabs(d) > eps) && (i < 100)){
d=(x3-x1)/d0;
x2=x1-d*d0*f1/(f3-f1);
f2=calcVcas(x2)-vcas;
if(f1*f2 <= 0.0){
x3=x2;
f3=f2;
f1=relax*f1;
}
else if(f2*f3 <= 0){
x1=x2;
f1=f2;
f3=relax*f3;
}
//cout << i << endl;
i++;
}//end while
if(i < 100) {
success=true;
*Mach=x2;
}
f1=calcVcas(x1)-vcas;
f3=calcVcas(x3)-vcas;
d0=fabs(x3-x1);
//iterations
i=0;
while ((fabs(d) > eps) && (i < 100)) {
//cout << "getMachFromVcas x1,x2,x3: " << x1 << "," << x2 << "," << x3 << endl;
d=(x3-x1)/d0;
x2=x1-d*d0*f1/(f3-f1);
f2=calcVcas(x2)-vcas;
if(f1*f2 <= 0.0) {
x3=x2;
f3=f2;
f1=relax*f1;
} else if(f2*f3 <= 0) {
x1=x2;
f1=f2;
f3=relax*f3;
}
//cout << i << endl;
i++;
}//end while
if(i < 100) {
success=true;
*Mach=x2;
}
//cout << "Success= " << success << " Vcas: " << vcas*FPSTOKTS << " Mach: " << *Mach << endl;
return success;
}
//cout << "Success= " << success << " Vcas: " << vcas*FPSTOKTS << " Mach: " << x2 << endl;
return success;
}

View file

@ -1,49 +1,49 @@
/*******************************************************************************
Header: FGInitialCondition.h
Author: Tony Peden
Date started: 7/1/99
------------- Copyright (C) 1999 Anthony K. Peden (apeden@earthlink.net) -------------
This program is free software; you can redistribute it and/or modify it under
the terms of the GNU General Public License as published by the Free Software
Foundation; either version 2 of the License, or (at your option) any later
version.
This program is distributed in the hope that it will be useful, but WITHOUT
ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
FOR A PARTICULAR PURPOSE. See the GNU General Public License for more
details.
You should have received a copy of the GNU General Public License along with
this program; if not, write to the Free Software Foundation, Inc., 59 Temple
Place - Suite 330, Boston, MA 02111-1307, USA.
Further information about the GNU General Public License can also be found on
the world wide web at http://www.gnu.org.
HISTORY
--------------------------------------------------------------------------------
7/1/99 TP Created
FUNCTIONAL DESCRIPTION
--------------------------------------------------------------------------------
The purpose of this class is to take a set of initial conditions and provide
a kinematically consistent set of body axis velocity components, euler
angles, and altitude. This class does not attempt to trim the model i.e.
the sim will most likely start in a very dynamic state (unless, of course,
you have chosen your IC's wisely) even after setting it up with this class.
CAVEAT: This class makes use of alpha=theta-gamma. This means that setting
any of the three with this class is only valid for steady state
(all accels zero) and zero pitch rate. One example where this
would produce invalid results is setting up for a trim in a pull-up
or pushover (both have nonzero pitch rate). Maybe someday...
********************************************************************************
SENTRY
*******************************************************************************/
@ -57,59 +57,162 @@ INCLUDES
#include "FGFDMExec.h"
#include "FGAtmosphere.h"
#include "FGMatrix.h"
/*******************************************************************************
CLASS DECLARATION
*******************************************************************************/
class FGInitialCondition
{
public:
typedef enum { none,setvt, setvc, setve, setmach } speedset;
FGInitialCondition(FGFDMExec *fdmex);
~FGInitialCondition(void);
/* USAGE NOTES
With a valid object of FGFDMExec and an aircraft model loaded
FGInitialCondition fgic=new FGInitialCondition(FDMExec);
fgic->SetVcalibratedKtsIC()
fgic->SetAltitudeFtIC();
.
.
.
//to directly into Run
FDMExec->GetState()->Initialize(fgic)
delete fgic;
FDMExec->Run()
//or to loop the sim w/o integrating
FDMExec->RunIC(fgic)
Speed:
Since vc, ve, vt, and mach all represent speed, the remaining
three are recalculated each time one of them is set (using the
current altitude). The most recent speed set is remembered so
that if and when altitude is reset, the last set speed is used
to recalculate the remaining three. Setting any of the body
components forces a recalculation of vt and vt then becomes the
most recent speed set.
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
set theta : recalculate alpha using gamma as currently set
set gamma : recalculate theta using alpha as currently set
The idea being that gamma is most interesting to pilots (since it
is indicative of climb rate).
Setting climb rate is, for the purpose of this discussion,
considered equivalent to setting gamma.
*/
class FGInitialCondition {
public:
void SetVcalibratedKtsIC(float tt);
void SetVtrueKtsIC(float tt);
void SetMachIC(float tt);
FGInitialCondition(FGFDMExec *fdmex);
~FGInitialCondition(void);
void SetAltitudeFtIC(float tt);
void SetFlightPathAngleDegIC(float tt); //"vertical" flight path, solve for alpha using speed
//void SetClimbRateFpmIC(float tt); //overwrite gamma
void SetAlphaDegIC(float tt); //use currently stored gamma
void SetBetaDegIC(float tt);
void SetRollAngleDegIC(float tt);
void SetPitchAngleDegIC(float tt); //use currently stored gamma
void SetHeadingDegIC(float tt);
void SetLatitudeDegIC(float tt);
void SetLongitudeDegIC(float tt);
void SetVcalibratedKtsIC(float tt);
void SetVequivalentKtsIC(float tt);
void SetVtrueKtsIC(float tt);
void SetMachIC(float tt);
float GetUBodyFpsIC(void);
float GetVBodyFpsIC(void);
float GetWBodyFpsIC(void);
void SetUBodyFpsIC(float tt);
void SetVBodyFpsIC(float tt);
void SetWBodyFpsIC(float tt);
float GetThetaRadIC(void);
float GetPhiRadIC(void);
float GetPsiRadIC(void);
void SetAltitudeFtIC(float tt);
float GetLatitudeRadIC(void);
float GetLongitudeRadIC(void);
//"vertical" flight path, recalculate theta
inline void SetFlightPathAngleDegIC(float tt) { gamma=tt*DEGTORAD; theta=alpha+gamma; }
inline void SetFlightPathAngleRadIC(float tt) { gamma=tt; theta=alpha+gamma; }
//set speed first
void SetClimbRateFpmIC(float tt);
//use currently stored gamma, recalcualte theta
inline void SetAlphaDegIC(float tt) { alpha=tt*DEGTORAD; theta=alpha+gamma; }
inline void SetAlphaRadIC(float tt) { alpha=tt; theta=alpha+gamma; }
//use currently stored gamma, recalcualte alpha
inline void SetPitchAngleDegIC(float tt) { theta=tt*DEGTORAD; alpha=theta-gamma; }
inline void SetPitchAngleRadIC(float tt) { theta=tt; alpha=theta-gamma; }
float GetAltitudeFtIC(void);
inline void SetBetaDegIC(float tt) { beta=tt*DEGTORAD; }
private:
float vt,vc;
float alpha,beta,gamma,theta,phi,psi;
float mach;
float altitude,hdot;
float u,v,w;
float latitude,longitude;
inline void SetRollAngleDegIC(float tt) { phi=tt*DEGTORAD; }
inline void SetRollAngleRadIC(float tt) { phi=tt; }
FGFDMExec *fdmex;
float calcVcas(float Mach);
bool findMachInterval(float *mlo, float *mhi,float vcas);
bool getMachFromVcas(float *Mach,float vcas);
inline void SetHeadingDegIC(float tt) { psi=tt*DEGTORAD; }
inline void SetHeadingRadIC(float tt) { psi=tt; }
inline void SetLatitudeDegIC(float tt) { latitude=tt*DEGTORAD; }
inline void SetLatitudeRadIC(float tt) { latitude=tt; }
inline void SetLongitudeDegIC(float tt) { longitude=tt*DEGTORAD; }
inline void SetLongitudeRadIC(float tt) { longitude=tt; }
inline float GetVcalibratedKtsIC(void) { return vc*FPSTOKTS; }
inline float GetVequivalentKtsIC(void) { return ve*FPSTOKTS; }
inline float GetVtrueKtsIC(void) { return vt*FPSTOKTS; }
inline float GetMachIC(void) { return mach; }
inline float GetAltitudeFtIC(void) { return altitude; }
inline float GetFlightPathAngleDegIC(void) { return gamma*RADTODEG; }
inline float GetFlightPathAngleRadIC(void) { return gamma; }
inline float GetClimbRateFpmIC(void) { return hdot*60; }
inline float GetClimbRateFpsIC(void) { return hdot; }
inline float GetAlphaDegIC(void) { return alpha*RADTODEG; }
inline float GetAlphaRadIC(void) { return alpha; }
inline float GetPitchAngleDegIC(void) { return theta*RADTODEG; }
inline float GetPitchAngleRadIC(void) { return theta; }
inline float GetBetaDegIC(void) { return beta*RADTODEG; }
inline float GetBetaRadIC(void) { return beta*RADTODEG; }
inline float GetRollAngleDegIC(void) { return phi*RADTODEG; }
inline float GetRollAngleRadIC(void) { return phi; }
inline float GetHeadingDegIC(void) { return psi*RADTODEG; }
inline float GetHeadingRadIC(void) { return psi; }
inline float GetLatitudeDegIC(void) { return latitude*RADTODEG; }
inline float GetLatitudeRadIC(void) { return latitude; }
inline float GetLongitudeDegIC(void) { return longitude*RADTODEG; }
inline float GetLongitudeRadIC(void) { return longitude; }
inline float GetUBodyFpsIC(void) { return vt*cos(alpha)*cos(beta); }
inline float GetVBodyFpsIC(void) { return vt*sin(beta); }
inline float GetWBodyFpsIC(void) { return vt*sin(alpha)*cos(beta); }
inline float GetThetaRadIC(void) { return theta; }
inline float GetPhiRadIC(void) { return phi; }
inline float GetPsiRadIC(void) { return psi; }
private:
float vt,vc,ve;
float alpha,beta,gamma,theta,phi,psi;
float mach;
float altitude,hdot;
float latitude,longitude;
float u,v,w;
speedset lastSpeedSet;
FGFDMExec *fdmex;
float calcVcas(float Mach);
bool findMachInterval(float *mlo, float *mhi,float vcas);
bool getMachFromVcas(float *Mach,float vcas);
};
#endif

View file

@ -37,27 +37,41 @@ INCLUDES
*******************************************************************************/
#include "FGLGear.h"
#include "FGState.h"
/*******************************************************************************
************************************ CODE **************************************
*******************************************************************************/
FGLGear::FGLGear(FGConfigFile* AC_cfg)
FGLGear::FGLGear(FGConfigFile* AC_cfg, FGFDMExec* fdmex) : vXYZ(3), Exec(fdmex)
{
string tmp;
*AC_cfg >> tmp >> name >> X >> Y >> Z >> kSpring >> bDamp >> statFCoeff >> brakeCoeff;
*AC_cfg >> tmp >> name >> vXYZ(1) >> vXYZ(2) >> vXYZ(3) >> kSpring >> bDamp
>> statFCoeff >> brakeCoeff;
State = Exec->GetState();
Aircraft = Exec->GetAircraft();
Position = Exec->GetPosition();
}
/******************************************************************************/
FGLGear::~FGLGear(void)
{
}
float FGLGear::Force(void)
/******************************************************************************/
FGColumnVector FGLGear::Force(void)
{
return 0.0;
static FGColumnVector vForce(3);
static FGColumnVector vLocalGear(3);
vLocalGear = State->GetTb2l() * (vXYZ - Aircraft->GetXYZcg());
vLocalGear(3) = -vLocalGear(3);
return vForce;
}
/******************************************************************************/

View file

@ -56,39 +56,48 @@ INCLUDES
#ifdef FGFS
# include <simgear/compiler.h>
# include STL_STRING
FG_USING_STD(string);
#else
# include <string>
#endif
#include <string>
#include "FGConfigFile.h"
#include "FGMatrix.h"
#include "FGFDMExec.h"
#include "FGState.h"
/*******************************************************************************
DEFINITIONS
*******************************************************************************/
using namespace std;
/*******************************************************************************
CLASS DECLARATION
*******************************************************************************/
class FGAircraft;
class FGPosition;
class FGLGear
{
public:
FGLGear(FGConfigFile*);
FGLGear(FGConfigFile*, FGFDMExec*);
~FGLGear(void);
float Force(void);
FGColumnVector Force(void);
private:
float X, Y, Z;
FGColumnVector vXYZ;
float kSpring, bDamp, compressLength;
float statFCoeff, rollFCoeff, skidFCoeff;
float frictionForce, compForce;
float brakePct, brakeForce, brakeCoeff;
string name;
FGState* State;
FGAircraft* Aircraft;
FGPosition* Position;
FGFDMExec* Exec;
};
#include "FGAircraft.h"
#include "FGPosition.h"
/******************************************************************************/
#endif

View file

@ -197,7 +197,7 @@ FGMatrix FGMatrix::operator-(const FGMatrix& M)
for (unsigned int i=1; i<=Rows(); i++) {
for (unsigned int j=1; j<=Cols(); j++) {
Diff(i,j) = (*this)(i,j) - M(i,j);
Diff(i,j) = data[i][j] - M(i,j);
}
}
return Diff;
@ -215,7 +215,7 @@ void FGMatrix::operator-=(const FGMatrix &M)
for (unsigned int i=1; i<=Rows(); i++) {
for (unsigned int j=1; j<=Cols(); j++) {
(*this)(i,j) -= M(i,j);
data[i][j] -= M(i,j);
}
}
}
@ -234,7 +234,7 @@ FGMatrix FGMatrix::operator+(const FGMatrix& M)
for (unsigned int i=1; i<=Rows(); i++) {
for (unsigned int j=1; j<=Cols(); j++) {
Sum(i,j) = (*this)(i,j) + M(i,j);
Sum(i,j) = data[i][j] + M(i,j);
}
}
return Sum;
@ -252,7 +252,7 @@ void FGMatrix::operator+=(const FGMatrix &M)
for (unsigned int i=1; i<=Rows(); i++) {
for (unsigned int j=1; j<=Cols(); j++) {
(*this)(i,j)+=M(i,j);
data[i][j]+=M(i,j);
}
}
}
@ -277,7 +277,7 @@ void FGMatrix::operator*=(const double scalar)
{
for (unsigned int i=1; i<=Rows(); i++) {
for (unsigned int j=1; j<=Cols(); j++) {
(*this)(i,j) *= scalar;
data[i][j] *= scalar;
}
}
}
@ -298,7 +298,7 @@ FGMatrix FGMatrix::operator*(const FGMatrix& M)
for (unsigned int j=1; j<=M.Cols(); j++) {
Product(i,j) = 0;
for (unsigned int k=1; k<=Cols(); k++) {
Product(i,j) += (*this)(i,k) * M(k,j);
Product(i,j) += data[i][k] * M(k,j);
}
}
}
@ -322,7 +322,7 @@ void FGMatrix::operator*=(const FGMatrix& M)
for (unsigned int j=1; j<=M.Cols(); j++) {
prod[i][j] = 0;
for (unsigned int k=1; k<=Cols(); k++) {
prod[i][j] += (*this)(i,k) * M(k,j);
prod[i][j] += data[i][k] * M(k,j);
}
}
}
@ -339,7 +339,7 @@ FGMatrix FGMatrix::operator/(const double scalar)
for (unsigned int i=1; i<=Rows(); i++) {
for (unsigned int j=1; j<=Cols(); j++) {
Quot(i,j) = (*this)(i,j)/scalar;
Quot(i,j) = data[i][j]/scalar;
}
}
return Quot;
@ -351,7 +351,7 @@ void FGMatrix::operator/=(const double scalar)
{
for (unsigned int i=1; i<=Rows(); i++) {
for (unsigned int j=1; j<=Cols(); j++) {
(*this)(i,j)/=scalar;
data[i][j]/=scalar;
}
}
}
@ -490,6 +490,25 @@ FGColumnVector FGColumnVector::operator*(const double scalar)
/******************************************************************************/
FGColumnVector FGColumnVector::operator-(const FGColumnVector& V)
{
if ((Rows() != V.Rows()) || (Cols() != V.Cols())) {
MatrixException mE;
mE.Message = "Invalid row/column match in Column Vector operator -";
throw mE;
}
FGColumnVector Diff(Rows());
for (unsigned int i=1; i<=Rows(); i++) {
Diff(i) = data[i][1] - V(i);
}
return Diff;
}
/******************************************************************************/
FGColumnVector FGColumnVector::operator/(const double scalar)
{
FGColumnVector Quotient(Rows());

View file

@ -23,18 +23,17 @@ INCLUDES
#include <stdlib.h>
#ifdef FGFS
# include <simgear/compiler.h>
# include STL_STRING
# ifdef FG_HAVE_STD_INCLUDES
# include <fstream>
# else
# include <fstream.h>
# endif
FG_USING_STD(string);
#else
# include <string>
# include <fstream>
#endif
#include <string>
/*******************************************************************************
FORWARD DECLARATIONS
*******************************************************************************/
@ -45,7 +44,9 @@ class FGColumnVector;
DECLARATION: MatrixException
*******************************************************************************/
using namespace std;
using std::string;
using std::ostream;
using std::istream;
class MatrixException /* : public exception */
{
@ -122,10 +123,12 @@ public:
FGColumnVector operator*(const double scalar);
FGColumnVector operator/(const double scalar);
FGColumnVector operator+(const FGColumnVector& B);
float Magnitude(void);
FGColumnVector operator-(const FGColumnVector& B);
float Magnitude(void);
FGColumnVector Normalize(void);
friend FGColumnVector operator*(const double scalar, const FGColumnVector& A);
friend FGColumnVector operator*(const FGMatrix& M, const FGColumnVector& V);
double& operator()(int m) const;
};

View file

@ -42,18 +42,17 @@ INCLUDES
#ifdef FGFS
# include <simgear/compiler.h>
# include STL_STRING
# ifdef FG_HAVE_STD_INCLUDES
# include <iostream>
# else
# include <iostream.h>
# endif
FG_USING_STD(string);
#else
# include <string>
# include <iostream>
#endif
#include <string>
/*******************************************************************************
DEFINES
*******************************************************************************/

View file

@ -178,7 +178,9 @@ void FGOutput::DelimitedOutput(void)
cout << "Phi, Tht, Psi, ";
cout << "Alpha, ";
cout << "Latitude, ";
cout << "Longitude";
cout << "Longitude, ";
cout << "Distance AGL, ";
cout << "Runway Radius";
}
if (SubSystems & FGAircraft::ssCoefficients) {
cout << ", ";
@ -241,7 +243,9 @@ void FGOutput::DelimitedOutput(void)
cout << Rotation->GetEuler() << ", ";
cout << Translation->Getalpha() << ", ";
cout << Position->GetLatitude() << ", ";
cout << Position->GetLongitude();
cout << Position->GetLongitude() << ", ";
cout << Position->GetDistanceAGL() << ", ";
cout << Position->GetRunwayRadius();
}
if (SubSystems & FGAircraft::ssCoefficients) {
cout << ", ";
@ -309,7 +313,9 @@ void FGOutput::DelimitedOutput(string fname)
datafile << "Phi, Tht, Psi, ";
datafile << "Alpha, ";
datafile << "Latitude, ";
datafile << "Longitude";
datafile << "Longitude, ";
datafile << "Distance AGL, ";
datafile << "Runway Radius";
}
if (SubSystems & FGAircraft::ssCoefficients) {
datafile << ", ";
@ -371,7 +377,9 @@ void FGOutput::DelimitedOutput(string fname)
datafile << Rotation->GetEuler() << ", ";
datafile << Translation->Getalpha() << ", ";
datafile << Position->GetLatitude() << ", ";
datafile << Position->GetLongitude();
datafile << Position->GetLongitude() << ", ";
datafile << Position->GetDistanceAGL() << ", ";
datafile << Position->GetRunwayRadius();
}
if (SubSystems & FGAircraft::ssCoefficients) {
datafile << ", ";

View file

@ -1,39 +1,39 @@
/*******************************************************************************
Module: FGPosition.cpp
Author: Jon S. Berndt
Date started: 01/05/99
Purpose: Integrate the EOM to determine instantaneous position
Called by: FGFDMExec
------------- Copyright (C) 1999 Jon S. Berndt (jsb@hal-pc.org) -------------
This program is free software; you can redistribute it and/or modify it under
the terms of the GNU General Public License as published by the Free Software
Foundation; either version 2 of the License, or (at your option) any later
version.
This program is distributed in the hope that it will be useful, but WITHOUT
ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
FOR A PARTICULAR PURPOSE. See the GNU General Public License for more
details.
You should have received a copy of the GNU General Public License along with
this program; if not, write to the Free Software Foundation, Inc., 59 Temple
Place - Suite 330, Boston, MA 02111-1307, USA.
Further information about the GNU General Public License can also be found on
the world wide web at http://www.gnu.org.
FUNCTIONAL DESCRIPTION
--------------------------------------------------------------------------------
This class encapsulates the integration of rates and accelerations to get the
current position of the aircraft.
HISTORY
--------------------------------------------------------------------------------
01/05/99 JSB Created
********************************************************************************
COMMENTS, REFERENCES, and NOTES
********************************************************************************
@ -48,7 +48,7 @@ COMMENTS, REFERENCES, and NOTES
Wiley & Sons, 1979 ISBN 0-471-03032-5
[5] Bernard Etkin, "Dynamics of Flight, Stability and Control", Wiley & Sons,
1982 ISBN 0-471-08936-2
********************************************************************************
INCLUDES
*******************************************************************************/
@ -79,29 +79,33 @@ INCLUDES
************************************ CODE **************************************
*******************************************************************************/
extern float globalTriNormal[3];
extern double globalSceneryAltitude;
extern double globalSeaLevelRadius;
FGPosition::FGPosition(FGFDMExec* fdmex) : FGModel(fdmex),
vUVW(3),
vVel(3)
vUVW(3),
vVel(3)
{
Name = "FGPosition";
LongitudeDot = LatitudeDot = RadiusDot = 0.0;
lastLongitudeDot = lastLatitudeDot = lastRadiusDot = 0.0;
Longitude = Latitude = 0.0;
h = 0.0;
Radius = EARTHRAD + h;
gamma=Vt=0.0;
RunwayRadius = EARTHRAD;
}
/******************************************************************************/
FGPosition::~FGPosition(void)
{
}
FGPosition::~FGPosition(void) {}
/******************************************************************************/
bool FGPosition:: Run(void)
{
float cosLat;
bool FGPosition:: Run(void) {
double cosLat;
double hdot_Vt;
if (!FGModel::Run()) {
GetState();
@ -118,8 +122,21 @@ bool FGPosition:: Run(void)
Latitude += 0.5*dt*rate*(LatitudeDot + lastLatitudeDot);
Radius += 0.5*dt*rate*(RadiusDot + lastRadiusDot);
h = Radius - EARTHRAD;
h = Radius - EARTHRAD; // Geocentric
DistanceAGL = Radius - RunwayRadius; // Geocentric
cout << "h: " << h << " DistanceAGL: " << DistanceAGL << endl;
hoverb = h/b;
if(Vt > 0) {
hdot_Vt=RadiusDot/Vt;
//make sure that -Vt <= hdot <= Vt, which, of course, should always be the case
if(fabs(hdot_Vt) <= 1) gamma= asin(hdot_Vt);
} else
gamma=0.0;
lastLatitudeDot = LatitudeDot;
lastLongitudeDot = LongitudeDot;
lastRadiusDot = RadiusDot;
@ -133,14 +150,14 @@ bool FGPosition:: Run(void)
/******************************************************************************/
void FGPosition::GetState(void)
{
void FGPosition::GetState(void) {
dt = State->Getdt();
vUVW = Translation->GetUVW();
Vt = Translation->GetVt();
invMass = 1.0 / Aircraft->GetMass();
invRadius = 1.0 / (h + EARTHRAD);
Radius = h + EARTHRAD;
b = Aircraft->GetWingSpan();
}

View file

@ -1,36 +1,36 @@
/*******************************************************************************
Header: FGPosition.h
Author: Jon S. Berndt
Date started: 1/5/99
------------- Copyright (C) 1999 Jon S. Berndt (jsb@hal-pc.org) -------------
This program is free software; you can redistribute it and/or modify it under
the terms of the GNU General Public License as published by the Free Software
Foundation; either version 2 of the License, or (at your option) any later
version.
This program is distributed in the hope that it will be useful, but WITHOUT
ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
FOR A PARTICULAR PURPOSE. See the GNU General Public License for more
details.
You should have received a copy of the GNU General Public License along with
this program; if not, write to the Free Software Foundation, Inc., 59 Temple
Place - Suite 330, Boston, MA 02111-1307, USA.
Further information about the GNU General Public License can also be found on
the world wide web at http://www.gnu.org.
HISTORY
--------------------------------------------------------------------------------
01/05/99 JSB Created
********************************************************************************
COMMENTS, REFERENCES, and NOTES
********************************************************************************
********************************************************************************
SENTRY
*******************************************************************************/
@ -45,23 +45,25 @@ INCLUDES
#include "FGModel.h"
#include "FGMatrix.h"
using namespace std;
/*******************************************************************************
CLASS DECLARATION
*******************************************************************************/
class FGPosition : public FGModel
{
class FGPosition : public FGModel {
FGColumnVector vUVW;
FGColumnVector vVel;
float Vee, invMass, invRadius;
double Vee, invMass, invRadius;
double Radius, h;
float LatitudeDot, LongitudeDot, RadiusDot;
float lastLatitudeDot, lastLongitudeDot, lastRadiusDot;
float Longitude, Latitude;
double LatitudeDot, LongitudeDot, RadiusDot;
double lastLatitudeDot, lastLongitudeDot, lastRadiusDot;
double Longitude, Latitude;
float dt;
double RunwayRadius;
double DistanceAGL;
double gamma;
double Vt;
double hoverb,b;
void GetState(void);
@ -69,18 +71,25 @@ public:
FGPosition(FGFDMExec*);
~FGPosition(void);
inline FGColumnVector GetVel(void) {return vVel;}
inline FGColumnVector GetUVW(void) {return vUVW;}
inline float GetVn(void) {return vVel(1);}
inline float GetVe(void) {return vVel(2);}
inline float GetVd(void) {return vVel(3);}
inline float Geth(void) {return h;}
inline float GetLatitude(void) {return Latitude;}
inline float GetLongitude(void) {return Longitude;}
void SetvVel(const FGColumnVector& v) {vVel = v;}
void SetLatitude(float tt) {Latitude = tt;}
void SetLongitude(float tt) {Longitude = tt;}
void Seth(float tt) {h = tt;}
inline FGColumnVector GetVel(void) { return vVel; }
inline FGColumnVector GetUVW(void) { return vUVW; }
inline double GetVn(void) { return vVel(1); }
inline double GetVe(void) { return vVel(2); }
inline double GetVd(void) { return vVel(3); }
inline double Geth(void) { return h; }
inline double Gethdot(void) { return RadiusDot; }
inline double GetLatitude(void) { return Latitude; }
inline double GetLongitude(void) { return Longitude; }
inline double GetRunwayRadius(void) { return RunwayRadius; }
inline double GetDistanceAGL(void) { return DistanceAGL; }
inline double GetGamma(void) { return gamma; }
inline double GetHOverB(void) { return hoverb; }
void SetvVel(const FGColumnVector& v) { vVel = v; }
void SetLatitude(float tt) { Latitude = tt; }
void SetLongitude(double tt) { Longitude = tt; }
void Seth(double tt) { h = tt; }
void SetRunwayRadius(double tt) { RunwayRadius = tt; }
void SetDistanceAGL(double tt) { DistanceAGL = tt; }
bool Run(void);
};

View file

@ -70,8 +70,6 @@ INCLUDES
#include "FGModel.h"
#include "FGMatrix.h"
using namespace std;
/*******************************************************************************
CLASS DECLARATION
*******************************************************************************/

View file

@ -4,34 +4,34 @@
Author: Jon Berndt
Date started: 11/17/98
Called by: FGFDMExec and accessed by all models.
------------- Copyright (C) 1999 Jon S. Berndt (jsb@hal-pc.org) -------------
This program is free software; you can redistribute it and/or modify it under
the terms of the GNU General Public License as published by the Free Software
Foundation; either version 2 of the License, or (at your option) any later
version.
This program is distributed in the hope that it will be useful, but WITHOUT
ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
FOR A PARTICULAR PURPOSE. See the GNU General Public License for more
details.
You should have received a copy of the GNU General Public License along with
this program; if not, write to the Free Software Foundation, Inc., 59 Temple
Place - Suite 330, Boston, MA 02111-1307, USA.
Further information about the GNU General Public License can also be found on
the world wide web at http://www.gnu.org.
FUNCTIONAL DESCRIPTION
--------------------------------------------------------------------------------
See header file.
HISTORY
--------------------------------------------------------------------------------
11/17/98 JSB Created
********************************************************************************
INCLUDES
*******************************************************************************/
@ -64,10 +64,9 @@ INCLUDES
FGState::FGState(FGFDMExec* fdex) : mTb2l(3,3),
mTl2b(3,3),
mTs2b(3,3),
vQtrn(4)
{
mTl2b(3,3),
mTs2b(3,3),
vQtrn(4) {
FDMExec = fdex;
adot = bdot = 0.0;
@ -102,25 +101,24 @@ FGState::FGState(FGFDMExec* fdex) : mTb2l(3,3),
coeffdef["FG_SPDBRAKE_CMD"] = 16777216L ;
coeffdef["FG_SPOILERS_CMD"] = 33554432L ;
coeffdef["FG_FLAPS_CMD"] = 67108864L ;
coeffdef["FG_SPARE3"] = 134217728L ;
coeffdef["FG_SPARE4"] = 268435456L ;
coeffdef["FG_SPARE5"] = 536870912L ;
coeffdef["FG_SPARE6"] = 1073741824L ;
coeffdef["FG_THROTTLE_CMD"] = 134217728L ;
coeffdef["FG_THROTTLE_POS"] = 268435456L ;
coeffdef["FG_HOVERB"] = 536870912L ;
coeffdef["FG_PITCH_TRIM_CMD"] = 1073741824L ;
}
/******************************************************************************/
FGState::~FGState(void)
{
}
FGState::~FGState(void) {}
//***************************************************************************
//
// Reset: Assume all angles READ FROM FILE IN DEGREES !!
//
bool FGState::Reset(string path, string acname, string fname)
{
bool FGState::Reset(string path, string acname, string fname) {
string resetDef;
float U, V, W;
float phi, tht, psi;
@ -163,12 +161,11 @@ bool FGState::Reset(string path, string acname, string fname)
void FGState::Initialize(float U, float V, float W,
float phi, float tht, float psi,
float Latitude, float Longitude, float H)
{
float Latitude, float Longitude, float H) {
FGColumnVector vUVW(3);
FGColumnVector vLocalVelNED(3);
FGColumnVector vEuler(3);
float alpha, beta, gamma;
float alpha, beta;
float qbar, Vt;
FDMExec->GetPosition()->SetLatitude(Latitude);
@ -177,7 +174,6 @@ void FGState::Initialize(float U, float V, float W,
FDMExec->GetAtmosphere()->Run();
gamma = 0.0;
if (W != 0.0)
alpha = U*U > 0.0 ? atan2(W, U) : 0.0;
else
@ -193,7 +189,7 @@ void FGState::Initialize(float U, float V, float W,
vEuler << phi << tht << psi;
FDMExec->GetRotation()->SetEuler(vEuler);
FDMExec->GetTranslation()->SetABG(alpha, beta, gamma);
FDMExec->GetTranslation()->SetAB(alpha, beta);
Vt = sqrt(U*U + V*V + W*W);
FDMExec->GetTranslation()->SetVt(Vt);
@ -209,8 +205,7 @@ void FGState::Initialize(float U, float V, float W,
/******************************************************************************/
void FGState::Initialize(FGInitialCondition *FGIC)
{
void FGState::Initialize(FGInitialCondition *FGIC) {
float tht,psi,phi;
float U, V, W, h;
@ -231,8 +226,7 @@ void FGState::Initialize(FGInitialCondition *FGIC)
/******************************************************************************/
bool FGState::StoreData(string fname)
{
bool FGState::StoreData(string fname) {
ofstream datafile(fname.c_str());
if (datafile) {
@ -255,15 +249,13 @@ bool FGState::StoreData(string fname)
/******************************************************************************/
float FGState::GetParameter(string val_string)
{
float FGState::GetParameter(string val_string) {
return GetParameter(coeffdef[val_string]);
}
/******************************************************************************/
int FGState::GetParameterIndex(string val_string)
{
int FGState::GetParameterIndex(string val_string) {
return coeffdef[val_string];
}
@ -271,8 +263,7 @@ int FGState::GetParameterIndex(string val_string)
//
// NEED WORK BELOW TO ADD NEW PARAMETERS !!!
//
float FGState::GetParameter(int val_idx)
{
float FGState::GetParameter(int val_idx) {
switch(val_idx) {
case FG_QBAR:
return FDMExec->GetTranslation()->Getqbar();
@ -328,14 +319,21 @@ float FGState::GetParameter(int val_idx)
return FDMExec->GetAircraft()->GetWingSpan()/(2.0 * FDMExec->GetTranslation()->GetVt());
case FG_CI2VEL:
return FDMExec->GetAircraft()->Getcbar()/(2.0 * FDMExec->GetTranslation()->GetVt());
case FG_THROTTLE_CMD:
return FDMExec->GetFCS()->GetThrottleCmd(0);
case FG_THROTTLE_POS:
return FDMExec->GetFCS()->GetThrottlePos(0);
case FG_HOVERB:
return FDMExec->GetPosition()->GetHOverB();
case FG_PITCH_TRIM_CMD:
return FDMExec->GetFCS()->GetPitchTrimCmd();
}
return 0;
}
/******************************************************************************/
void FGState::SetParameter(int val_idx, float val)
{
void FGState::SetParameter(int val_idx, float val) {
switch(val_idx) {
case FG_ELEVATOR_POS:
FDMExec->GetFCS()->SetDePos(val);
@ -347,21 +345,22 @@ void FGState::SetParameter(int val_idx, float val)
FDMExec->GetFCS()->SetDrPos(val);
break;
case FG_SPDBRAKE_POS:
FDMExec->GetFCS()->SetDrPos(val);
FDMExec->GetFCS()->SetDsbPos(val);
break;
case FG_SPOILERS_POS:
FDMExec->GetFCS()->SetDrPos(val);
FDMExec->GetFCS()->SetDspPos(val);
break;
case FG_FLAPS_POS:
FDMExec->GetFCS()->SetDrPos(val);
FDMExec->GetFCS()->SetDfPos(val);
break;
case FG_THROTTLE_POS:
FDMExec->GetFCS()->SetThrottlePos(-1,val);
}
}
/******************************************************************************/
void FGState::InitMatrices(float phi, float tht, float psi)
{
void FGState::InitMatrices(float phi, float tht, float psi) {
float thtd2, psid2, phid2;
float Sthtd2, Spsid2, Sphid2;
float Cthtd2, Cpsid2, Cphid2;
@ -397,8 +396,7 @@ void FGState::InitMatrices(float phi, float tht, float psi)
/******************************************************************************/
void FGState::CalcMatrices(void)
{
void FGState::CalcMatrices(void) {
float Q0Q0, Q1Q1, Q2Q2, Q3Q3;
float Q0Q1, Q0Q2, Q0Q3, Q1Q2;
float Q1Q3, Q2Q3;
@ -430,8 +428,7 @@ void FGState::CalcMatrices(void)
/******************************************************************************/
void FGState::IntegrateQuat(FGColumnVector vPQR, int rate)
{
void FGState::IntegrateQuat(FGColumnVector vPQR, int rate) {
static FGColumnVector vlastQdot(4);
static FGColumnVector vQdot(4);
@ -449,8 +446,7 @@ void FGState::IntegrateQuat(FGColumnVector vPQR, int rate)
/******************************************************************************/
FGColumnVector FGState::CalcEuler(void)
{
FGColumnVector FGState::CalcEuler(void) {
static FGColumnVector vEuler(3);
if (mTb2l(3,3) == 0) vEuler(ePhi) = 0.0;
@ -468,8 +464,7 @@ FGColumnVector FGState::CalcEuler(void)
/******************************************************************************/
FGMatrix FGState::GetTs2b(float alpha, float beta)
{
FGMatrix FGState::GetTs2b(float alpha, float beta) {
float ca, cb, sa, sb;
ca = cos(alpha);

View file

@ -1,38 +1,38 @@
/*******************************************************************************
Header: FGState.h
Author: Jon S. Berndt
Date started: 11/17/98
------------- Copyright (C) 1999 Jon S. Berndt (jsb@hal-pc.org) -------------
This program is free software; you can redistribute it and/or modify it under
the terms of the GNU General Public License as published by the Free Software
Foundation; either version 2 of the License, or (at your option) any later
version.
This program is distributed in the hope that it will be useful, but WITHOUT
ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
FOR A PARTICULAR PURPOSE. See the GNU General Public License for more
details.
You should have received a copy of the GNU General Public License along with
this program; if not, write to the Free Software Foundation, Inc., 59 Temple
Place - Suite 330, Boston, MA 02111-1307, USA.
Further information about the GNU General Public License can also be found on
the world wide web at http://www.gnu.org.
FUNCTIONAL DESCRIPTION
--------------------------------------------------------------------------------
Based on Flightgear code, which is based on LaRCSim. This class wraps all
global state variables (such as velocity, position, orientation, etc.).
HISTORY
--------------------------------------------------------------------------------
11/17/98 JSB Created
********************************************************************************
SENTRY
*******************************************************************************/
@ -46,18 +46,16 @@ INCLUDES
#ifdef FGFS
# include <simgear/compiler.h>
# include STL_STRING
# ifdef FG_HAVE_STD_INCLUDES
# include <fstream>
# else
# include <fstream.h>
# endif
FG_USING_STD(string);
#else
# include <string>
# include <fstream>
#endif
#include <string>
#include <map>
#include "FGDefs.h"
#include "FGInitialCondition.h"
@ -67,18 +65,15 @@ INCLUDES
DEFINES
*******************************************************************************/
using namespace std;
/*******************************************************************************
CLASS DECLARATION
*******************************************************************************/
class FGFDMExec;
class FGState
{
class FGState {
public:
FGState(FGFDMExec*);
FGState(FGFDMExec*);
~FGState(void);
bool Reset(string, string, string);
@ -86,38 +81,44 @@ public:
void Initialize(FGInitialCondition *FGIC);
bool StoreData(string);
inline float Getadot(void) {return adot;}
inline float Getbdot(void) {return bdot;}
inline float Getadot(void) { return adot; }
inline float Getbdot(void) { return bdot; }
inline float GetLocalAltitudeOverRunway(void) {return LocalAltitudeOverRunway;}
inline float Geta(void) {return a;}
inline float GetLocalAltitudeOverRunway(void) { return LocalAltitudeOverRunway; }
inline float Geta(void) { return a; }
inline float Getsim_time(void) {return sim_time;}
inline float Getdt(void) {return dt;}
inline float Getsim_time(void) { return sim_time; }
inline float Getdt(void) { return dt; }
float GetParameter(int val_idx);
float GetParameter(string val_string);
int GetParameterIndex(string val_string);
inline void Setadot(float tt) {adot = tt;}
inline void Setbdot(float tt) {bdot = tt;}
inline void Setadot(float tt) { adot = tt; }
inline void Setbdot(float tt) { bdot = tt; }
inline void SetLocalAltitudeOverRunway(float tt) {LocalAltitudeOverRunway = tt;}
inline void Seta(float tt) {a = tt;}
inline void SetLocalAltitudeOverRunway(float tt) { LocalAltitudeOverRunway = tt; }
inline void Seta(float tt) { a = tt; }
inline float Setsim_time(float tt) {sim_time = tt; return sim_time;}
inline void Setdt(float tt) {dt = tt;}
inline float Setsim_time(float tt) {
sim_time = tt;
return sim_time;
}
inline void Setdt(float tt) { dt = tt; }
void SetParameter(int, float);
inline float IncrTime(void) {sim_time+=dt;return sim_time;}
inline float IncrTime(void) {
sim_time+=dt;
return sim_time;
}
void InitMatrices(float phi, float tht, float psi);
void CalcMatrices(void);
void IntegrateQuat(FGColumnVector vPQR, int rate);
FGColumnVector CalcEuler(void);
FGMatrix GetTs2b(float alpha, float beta);
FGMatrix GetTl2b(void) {return mTl2b;}
FGMatrix GetTb2l(void) {return mTb2l;}
FGMatrix GetTl2b(void) { return mTl2b; }
FGMatrix GetTb2l(void) { return mTb2l; }
private:

View file

@ -46,20 +46,15 @@ INCLUDES
#ifdef FGFS
# include <simgear/compiler.h>
# include STL_STRING
FG_USING_STD(string);
#else
# include <string>
#endif
#include <string>
#include "FGConfigFile.h"
/*******************************************************************************
DEFINES
*******************************************************************************/
using namespace std;
/*******************************************************************************
CLASS DECLARATION
*******************************************************************************/

View file

@ -1,40 +1,40 @@
/*******************************************************************************
Module: FGTranslation.cpp
Author: Jon Berndt
Date started: 12/02/98
Purpose: Integrates the translational EOM
Called by: FDMExec
------------- Copyright (C) 1999 Jon S. Berndt (jsb@hal-pc.org) -------------
This program is free software; you can redistribute it and/or modify it under
the terms of the GNU General Public License as published by the Free Software
Foundation; either version 2 of the License, or (at your option) any later
version.
This program is distributed in the hope that it will be useful, but WITHOUT
ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
FOR A PARTICULAR PURPOSE. See the GNU General Public License for more
details.
You should have received a copy of the GNU General Public License along with
this program; if not, write to the Free Software Foundation, Inc., 59 Temple
Place - Suite 330, Boston, MA 02111-1307, USA.
Further information about the GNU General Public License can also be found on
the world wide web at http://www.gnu.org.
FUNCTIONAL DESCRIPTION
--------------------------------------------------------------------------------
This class integrates the translational EOM.
HISTORY
--------------------------------------------------------------------------------
12/02/98 JSB Created
7/23/99 TP Added data member and modified Run and PutState to calcuate
Mach number
********************************************************************************
COMMENTS, REFERENCES, and NOTES
********************************************************************************
@ -49,10 +49,10 @@ COMMENTS, REFERENCES, and NOTES
Wiley & Sons, 1979 ISBN 0-471-03032-5
[5] Bernard Etkin, "Dynamics of Flight, Stability and Control", Wiley & Sons,
1982 ISBN 0-471-08936-2
The order of rotations used in this class corresponds to a 3-2-1 sequence,
or Y-P-R, or Z-Y-X, if you prefer.
********************************************************************************
INCLUDES
*******************************************************************************/
@ -74,74 +74,75 @@ INCLUDES
FGTranslation::FGTranslation(FGFDMExec* fdmex) : FGModel(fdmex),
vUVW(3),
vWindUVW(3),
vUVWdot(3),
vPQR(3),
vForces(3),
vEuler(3)
vUVW(3),
vWindUVW(3),
vUVWdot(3),
vNcg(3),
vPQR(3),
vForces(3),
vEuler(3)
{
Name = "FGTranslation";
qbar = 0;
Vt = 0.0;
Mach = 0.0;
alpha = beta = gamma = 0.0;
rho = 0.002378;
Name = "FGTranslation";
qbar = 0;
Vt = 0.0;
Mach = 0.0;
alpha = beta = 0.0;
rho = 0.002378;
}
/******************************************************************************/
FGTranslation::~FGTranslation(void)
{
FGTranslation::~FGTranslation(void) {}
/******************************************************************************/
bool FGTranslation::Run(void) {
static FGColumnVector vlastUVWdot(3);
static FGMatrix mVel(3,3);
if (!FGModel::Run()) {
GetState();
mVel(1,1) = 0.0;
mVel(1,2) = -vUVW(eW);
mVel(1,3) = vUVW(eV);
mVel(2,1) = vUVW(eW);
mVel(2,2) = 0.0;
mVel(2,3) = -vUVW(eU);
mVel(3,1) = -vUVW(eV);
mVel(3,2) = vUVW(eU);
mVel(3,3) = 0.0;
vUVWdot = mVel*vPQR + vForces/Mass;
vNcg=vUVWdot*INVGRAVITY;
vUVW += 0.5*dt*rate*(vlastUVWdot + vUVWdot) + vWindUVW;
Vt = vUVW.Magnitude();
if (vUVW(eW) != 0.0)
alpha = vUVW(eU)*vUVW(eU) > 0.0 ? atan2(vUVW(eW), vUVW(eU)) : 0.0;
if (vUVW(eV) != 0.0)
beta = vUVW(eU)*vUVW(eU)+vUVW(eW)*vUVW(eW) > 0.0 ? atan2(vUVW(eV),
(fabs(vUVW(eU))/vUVW(eU))*sqrt(vUVW(eU)*vUVW(eU) + vUVW(eW)*vUVW(eW))) : 0.0;
qbar = 0.5*rho*Vt*Vt;
Mach = Vt / State->Geta();
vlastUVWdot = vUVWdot;
} else {}
return false;
}
/******************************************************************************/
bool FGTranslation::Run(void)
{
static FGColumnVector vlastUVWdot(3);
static FGMatrix mVel(3,3);
if (!FGModel::Run()) {
GetState();
mVel(1,1) = 0.0;
mVel(1,2) = -vUVW(eW);
mVel(1,3) = vUVW(eV);
mVel(2,1) = vUVW(eW);
mVel(2,2) = 0.0;
mVel(2,3) = -vUVW(eU);
mVel(3,1) = -vUVW(eV);
mVel(3,2) = vUVW(eU);
mVel(3,3) = 0.0;
vUVWdot = mVel*vPQR + vForces/Mass;
vUVW += 0.5*dt*rate*(vlastUVWdot + vUVWdot) + vWindUVW;
Vt = vUVW.Magnitude();
if (vUVW(eW) != 0.0)
alpha = vUVW(eU)*vUVW(eU) > 0.0 ? atan2(vUVW(eW), vUVW(eU)) : 0.0;
if (vUVW(eV) != 0.0)
beta = vUVW(eU)*vUVW(eU)+vUVW(eW)*vUVW(eW) > 0.0 ? atan2(vUVW(eV), (fabs(vUVW(eU))/vUVW(eU))*sqrt(vUVW(eU)*vUVW(eU) + vUVW(eW)*vUVW(eW))) : 0.0;
qbar = 0.5*rho*Vt*Vt;
Mach = Vt / State->Geta();
vlastUVWdot = vUVWdot;
} else {
}
return false;
}
/******************************************************************************/
void FGTranslation::GetState(void)
{
void FGTranslation::GetState(void) {
dt = State->Getdt();
vPQR = Rotation->GetPQR();
@ -150,8 +151,10 @@ void FGTranslation::GetState(void)
Mass = Aircraft->GetMass();
rho = Atmosphere->GetDensity();
vEuler = Rotation->GetEuler();
// vWindUVW = Atmosphere->GetWindUVW();
vWindUVW = Atmosphere->GetWindUVW();
}

View file

@ -1,32 +1,32 @@
/*******************************************************************************
Header: FGTranslation.h
Author: Jon Berndt
Date started: 12/02/98
------------- Copyright (C) 1999 Jon S. Berndt (jsb@hal-pc.org) -------------
This program is free software; you can redistribute it and/or modify it under
the terms of the GNU General Public License as published by the Free Software
Foundation; either version 2 of the License, or (at your option) any later
version.
This program is distributed in the hope that it will be useful, but WITHOUT
ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
FOR A PARTICULAR PURPOSE. See the GNU General Public License for more
details.
You should have received a copy of the GNU General Public License along with
this program; if not, write to the Free Software Foundation, Inc., 59 Temple
Place - Suite 330, Boston, MA 02111-1307, USA.
Further information about the GNU General Public License can also be found on
the world wide web at http://www.gnu.org.
HISTORY
--------------------------------------------------------------------------------
12/02/98 JSB Created
********************************************************************************
COMMENTS, REFERENCES, and NOTES
********************************************************************************
@ -41,10 +41,10 @@ COMMENTS, REFERENCES, and NOTES
Wiley & Sons, 1979 ISBN 0-471-03032-5
[5] Bernard Etkin, "Dynamics of Flight, Stability and Control", Wiley & Sons,
1982 ISBN 0-471-08936-2
The order of rotations used in this class corresponds to a 3-2-1 sequence,
or Y-P-R, or Z-Y-X, if you prefer.
********************************************************************************
SENTRY
*******************************************************************************/
@ -70,53 +70,52 @@ INCLUDES
#include "FGModel.h"
#include "FGMatrix.h"
using namespace std;
/*******************************************************************************
CLASS DECLARATION
*******************************************************************************/
#pragma warn -8026
class FGTranslation : public FGModel
{
class FGTranslation : public FGModel {
public:
FGTranslation(FGFDMExec*);
~FGTranslation(void);
FGTranslation(FGFDMExec*);
~FGTranslation(void);
inline FGColumnVector GetUVW(void) {return vUVW;}
inline FGColumnVector GetUVWdot(void) { return vUVWdot; }
inline FGColumnVector GetUVW(void) { return vUVW; }
inline FGColumnVector GetUVWdot(void) { return vUVWdot; }
inline FGColumnVector GetNcg(void) { return vNcg; }
inline float Getalpha(void) {return alpha;}
inline float Getbeta (void) {return beta; }
inline float Getgamma(void) {return gamma;}
inline float Getqbar (void) {return qbar;}
inline float GetVt (void) {return Vt;}
inline float GetMach (void) {return Mach;}
inline float Getalpha(void) { return alpha; }
inline float Getbeta (void) { return beta; }
inline float Getqbar (void) { return qbar; }
inline float GetVt (void) { return Vt; }
inline float GetMach (void) { return Mach; }
void SetUVW(FGColumnVector tt) {vUVW = tt;}
inline void Setalpha(float tt) {alpha = tt;}
inline void Setbeta (float tt) {beta = tt;}
inline void Setgamma(float tt) {gamma = tt;}
inline void Setqbar (float tt) {qbar = tt;}
inline void SetVt (float tt) {Vt = tt;}
void SetUVW(FGColumnVector tt) { vUVW = tt; }
inline void SetABG(float t1, float t2, float t3) {alpha=t1; beta=t2; gamma=t3;}
bool Run(void);
inline void Setalpha(float tt) { alpha = tt; }
inline void Setbeta (float tt) { beta = tt; }
inline void Setqbar (float tt) { qbar = tt; }
inline void SetVt (float tt) { Vt = tt; }
inline void SetAB(float t1, float t2) { alpha=t1; beta=t2; }
bool Run(void);
protected:
private:
FGColumnVector vUVW,vWindUVW;
FGColumnVector vUVWdot;
FGColumnVector vNcg;
FGColumnVector vPQR;
FGColumnVector vForces;
FGColumnVector vEuler;
float Vt, qbar, Mach;
float Mass, dt;
float alpha, beta, gamma;
float alpha, beta;
float rho;
void GetState(void);

View file

@ -0,0 +1,425 @@
/*******************************************************************************
Header: FGTrimLong.cpp
Author: Tony Peden
Date started: 9/8/99
------------- Copyright (C) 1999 Anthony K. Peden (apeden@earthlink.net) -------------
This program is free software; you can redistribute it and/or modify it under
the terms of the GNU General Public License as published by the Free Software
Foundation; either version 2 of the License, or (at your option) any later
version.
This program is distributed in the hope that it will be useful, but WITHOUT
ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
FOR A PARTICULAR PURPOSE. See the GNU General Public License for more
details.
You should have received a copy of the GNU General Public License along with
this program; if not, write to the Free Software Foundation, Inc., 59 Temple
Place - Suite 330, Boston, MA 02111-1307, USA.
Further information about the GNU General Public License can also be found on
the world wide web at http://www.gnu.org.
HISTORY
--------------------------------------------------------------------------------
9/8/99 TP Created
FUNCTIONAL DESCRIPTION
--------------------------------------------------------------------------------
This class takes the given set of IC's and finds the angle of attack, elevator,
and throttle setting required to fly steady level. This is currently for in-air
conditions only. It is implemented using an iterative, one-axis-at-a-time
scheme. */
// !!!!!!! BEWARE ALL YE WHO ENTER HERE !!!!!!!
/*******************************************************************************
INCLUDES
*******************************************************************************/
#include "FGFDMExec.h"
#include "FGAtmosphere.h"
#include "FGInitialCondition.h"
#include "FGTrimLong.h"
#include "FGAircraft.h"
/*******************************************************************************
CLASS DECLARATION
*******************************************************************************/
FGTrimLong::FGTrimLong(FGFDMExec *FDMExec,FGInitialCondition *FGIC ) {
Ncycles=40;
Naxis=10;
Tolerance=1E-3;
A_Tolerance = Tolerance / 10;
Debug=0;
fdmex=FDMExec;
fgic=FGIC;
alphaMin=fdmex->GetAircraft()->GetAlphaCLMin()*RADTODEG;
alphaMax=fdmex->GetAircraft()->GetAlphaCLMax()*RADTODEG;
if(alphaMax <= alphaMin) {
alphaMax=20;
alphaMin=-5;
}
udotf=&FGTrimLong::udot_func;
wdotf=&FGTrimLong::wdot_func;
qdotf=&FGTrimLong::qdot_func;
total_its=0;
udot_subits=wdot_subits=qdot_subits=0;
trimudot=true;
axis_count=0;
}
FGTrimLong::~FGTrimLong(void) {}
void FGTrimLong::TrimStats() {
cout << endl << " Trim Statistics: " << endl;
cout << " Total Iterations: " << total_its << endl;
if(total_its > 0) {
cout << " Sub-iterations:" << endl;
cout << " wdot: " << wdot_subits << " average: " << wdot_subits/total_its << endl;
cout << " udot: " << udot_subits << " average: " << udot_subits/total_its << endl;
cout << " qdot: " << qdot_subits << " average: " << qdot_subits/total_its << endl;
}
}
void FGTrimLong::Report(void) {
cout << endl << " Trim Results" << endl;
cout << " Alpha: " << fdmex->GetTranslation()->Getalpha()*RADTODEG
<< " wdot: " << fdmex->GetTranslation()->GetUVWdot()(3)
<< " Tolerance " << Tolerance << endl;
cout << " Throttle: " << fdmex->GetFCS()->GetThrottlePos(0)
<< " udot: " << fdmex->GetTranslation()->GetUVWdot()(1)
<< " Tolerance " << Tolerance << endl;
cout << " Elevator: " << fdmex->GetFCS()->GetDePos()*RADTODEG
<< " qdot: " << fdmex->GetRotation()->GetPQRdot()(2)
<< " Tolerance " << A_Tolerance << endl;
}
void FGTrimLong::ReportState(void) {
cout << endl << " JSBSim Trim Report" << endl;
cout << " Weight: " << fdmex->GetAircraft()->GetWeight()
<< " lbs. CG x,y,z: " << fdmex->GetAircraft()->GetXYZcg()
<< " inches " << endl;
cout << " Flaps: ";
float flaps=fdmex->GetFCS()->GetDfPos();
if(flaps <= 0.01)
cout << "Up";
else
cout << flaps;
cout << " Gear: ";
if(fdmex->GetAircraft()->GetGearUp() == true)
cout << "Up" << endl;
else
cout << "Down" << endl;
cout << " Speed: " << fdmex->GetAuxiliary()->GetVcalibratedKTS()
<< " KCAS Mach: " << fdmex->GetState()->GetParameter(FG_MACH)
<< endl;
cout << " Altitude: " << fdmex->GetPosition()->Geth() << " ft" << endl;
cout << " Pitch Angle: " << fdmex->GetRotation()->Gettht()*RADTODEG
<< " deg Angle of Attack: " << fdmex->GetState()->GetParameter(FG_ALPHA)*RADTODEG
<< " deg" << endl;
cout << " Flight Path Angle: "
<< fdmex->GetPosition()->GetGamma()*RADTODEG
<< " deg" << endl;
cout << " Normal Load Factor: " << fdmex->GetAircraft()->GetNlf() << endl;
cout << " Pitch Rate: " << fdmex->GetState()->GetParameter(FG_PITCHRATE)*RADTODEG
<< " deg/s" << endl;
cout << " Roll Angle: " << fdmex->GetRotation()->Getphi()*RADTODEG
<< " deg Roll Rate: " << fdmex->GetState()->GetParameter(FG_ROLLRATE)
<< " deg/s"
<< endl ;
cout << " Sideslip: " << fdmex->GetState()->GetParameter(FG_BETA) *RADTODEG
<< " deg Yaw Rate: " << fdmex->GetState()->GetParameter(FG_YAWRATE)*RADTODEG
<< " deg/s " << endl;
cout << " Elevator: " << fdmex->GetState()->GetParameter(FG_ELEVATOR_POS)*RADTODEG
<< " deg Left Aileron: " << fdmex->GetState()->GetParameter(FG_AILERON_POS)*RADTODEG
<< " deg Rudder: " << fdmex->GetState()->GetParameter(FG_RUDDER_POS)*RADTODEG
<< " deg" << endl;
cout << " Throttle: " << fdmex->GetFCS()->GetThrottlePos(0)/100 << endl;
}
void FGTrimLong::setThrottlesPct(float tt) {
float tMin,tMax;
for(int i=0;i<fdmex->GetAircraft()->GetNumEngines();i++) {
tMin=fdmex->GetAircraft()->GetEngine(i)->GetThrottleMin();
tMax=fdmex->GetAircraft()->GetEngine(i)->GetThrottleMax();
dth=tt;
//cout << "setThrottlespct: " << i << ", " << tMin << ", " << tMax << ", " << dth << endl;
fdmex -> GetFCS() -> SetThrottleCmd(i,tMin+dth*(tMax-tMin));
}
}
int FGTrimLong::checkLimits(trimfp fp, float current, float min, float max) {
float lo,hi;
int result=0;
//cout << "Min: " << min << " Max: " << max << endl;
lo=(this->*fp)(min);
hi=(this->*fp)(max);
if(lo*hi >= 0) {
//cout << "Lo: " << lo << " Hi: " << hi << endl;
result=0;
} else {
lo=(this->*fp)(0);
if(lo*hi >= 0)
result=-1;
else
result=1;
}
return result;
}
bool FGTrimLong::solve(trimfp fp,float guess,float desired, float *result, float eps, float min, float max, int max_iterations, int *actual_its) {
float x1,x2,x3,f1,f2,f3,d,d0;
float const relax =0.9;
x1=x3=0;
int i;
d=1;
bool success=false;
//initializations
int side=checkLimits(fp,guess,min,max);
if(side != 0) {
if (side < 0)
x3=min;
else
x1=max;
f1=(this->*fp)(x1)-desired;
f3=(this->*fp)(x3)-desired;
d0=fabs(x3-x1);
//iterations
i=0;
while ((fabs(d) > eps) && (i < max_iterations)) {
if(Debug > 1)
cout << "FGTrimLong::solve i,x1,x2,x3: " << i << ", " << x1 << ", " << x2 << ", " << x3 << endl;
d=(x3-x1)/d0;
x2=x1-d*d0*f1/(f3-f1);
// if(x2 < min)
// x2=min;
// else if(x2 > max)
// x2=max;
f2=(this->*fp)(x2)-desired;
if(f1*f2 <= 0.0) {
x3=x2;
f3=f2;
f1=relax*f1;
} else if(f2*f3 <= 0) {
x1=x2;
f1=f2;
f3=relax*f3;
}
//cout << i << endl;
i++;
}//end while
if(i < max_iterations) {
success=true;
*result=x2;
}
*actual_its=i;
} else {
*actual_its=0;
}
return success;
}
bool FGTrimLong::findInterval(trimfp fp, float *lo, float *hi,float guess,float desired,int max_iterations) {
int i=0;
bool found=false;
float flo,fhi,fguess;
float xlo,xhi,step;
step=0.1*guess;
fguess=(this->*fp)(guess)-desired;
xlo=xhi=guess;
do {
step=2*step;
xlo-=step;
xhi+=step;
i++;
flo=(this->*fp)(xlo)-desired;
fhi=(this->*fp)(xhi)-desired;
if(flo*fhi <=0) { //found interval with root
found=true;
if(flo*fguess <= 0) { //narrow interval down a bit
xhi=xlo+step; //to pass solver interval that is as
//small as possible
}
else if(fhi*fguess <= 0) {
xlo=xhi-step;
}
}
if(Debug > 1)
cout << "FGTrimLong::findInterval: i=" << i << " Lo= " << xlo << " Hi= " << xhi << " flo*fhi: " << flo*fhi << endl;
} while((found == 0) && (i <= max_iterations));
*lo=xlo;
*hi=xhi;
return found;
}
float FGTrimLong::udot_func(float x) {
setThrottlesPct(x);
fdmex->RunIC(fgic);
return fdmex->GetTranslation()->GetUVWdot()(1);
}
float FGTrimLong::wdot_func(float x) {
fgic->SetAlphaDegIC(x);
fdmex->RunIC(fgic);
return fdmex->GetTranslation()->GetUVWdot()(3);
}
float FGTrimLong::qdot_func(float x) {
fdmex->GetFCS()->SetPitchTrimCmd(x);
fdmex->RunIC(fgic);
return fdmex->GetRotation()->GetPQRdot()(2);
}
bool FGTrimLong::DoTrim(void) {
int k=0,j=0,sum=0,trim_failed=0,jmax=Naxis;
int its;
float step,temp,min,max;
trimfp fp;
fgic -> SetAlphaDegIC((alphaMin+alphaMax)/2);
fdmex -> GetFCS() -> SetDeCmd(0);
fdmex -> GetFCS() -> SetPitchTrimCmd(0);
setThrottlesPct(0.5);
fdmex -> RunIC(fgic);
if(trimudot == false)
udot=0;
do {
axis_count=0;
solve(wdotf,fgic->GetAlphaDegIC(),0,&wdot,Tolerance,alphaMin, alphaMax,Naxis,&its);
wdot_subits+=its;
if(Debug > 0) {
cout << "Alpha: " << fdmex->GetTranslation()->Getalpha()*RADTODEG
<< " wdot: " << fdmex->GetTranslation()->GetUVWdot()(3)
<< endl;
}
solve(udotf,dth,0,&udot,Tolerance,0,1,Naxis,&its);
udot_subits+=its;
if(Debug > 0) {
cout << "Throttle: " << fdmex->GetFCS()->GetThrottlePos(0)
<< " udot: " << fdmex->GetTranslation()->GetUVWdot()(1)
<< endl;
}
solve(qdotf,fdmex->GetFCS()->GetPitchTrimCmd(),0,&qdot,A_Tolerance,-1,1,Naxis,&its);
qdot_subits+=its;
if(Debug > 0) {
cout << "Elevator: " << fdmex->GetFCS()->GetDePos()*RADTODEG
<< " qdot: " << fdmex->GetRotation()->GetPQRdot()(2)
<< endl;
}
wdot=fabs(fdmex->GetTranslation()->GetUVWdot()(3));
qdot=fabs(fdmex->GetRotation()->GetPQRdot()(2));
udot=fabs(fdmex->GetTranslation()->GetUVWdot()(1));
//these checks need to be done after all the axes have run
if(udot < Tolerance)
axis_count++;
if(wdot < Tolerance)
axis_count++;
if(qdot < A_Tolerance)
axis_count++;
if(axis_count == 2) {
//At this point we can check the input limits of the failed axis
//and declare the trim failed if there is no sign change. If there
//is, keep going until success or max iteration count
//Oh, well: two out of three ain't bad
if(wdot > Tolerance) {
if(checkLimits(wdotf,fgic->GetAlphaDegIC(),alphaMin,alphaMax) == false) {
cout << " Sorry, wdot doesn't appear to be trimmable" << endl;
total_its=k;
k=Ncycles; //force the trim to fail
}
}
if( udot > Tolerance ) {
if(checkLimits(udotf,dth,0,1) == false) {
cout << " Sorry, udot doesn't appear to be trimmable" << endl;
cout << " Resetting throttles to zero" << endl;
fdmex->GetFCS()->SetThrottleCmd(-1,0);
total_its=k;
k=Ncycles; //force the trim to fail
}
}
if(qdot > A_Tolerance) {
if(checkLimits(qdotf,fdmex->GetFCS()->GetPitchTrimCmd(),-1,1) == false) {
cout << " Sorry, qdot doesn't appear to be trimmable" << endl;
total_its=k;
k=Ncycles; //force the trim to fail
}
}
}
k++;
} while((axis_count < 3) && (k < Ncycles));
if(axis_count >= 3) {
total_its=k;
cout << endl << " Trim successful" << endl;
return true;
} else {
total_its=k;
cout << endl << " Trim failed" << endl;
return false;
}
}
//YOU WERE WARNED, BUT YOU DID IT ANYWAY.

140
src/FDM/JSBSim/FGTrimLong.h Normal file
View file

@ -0,0 +1,140 @@
/*******************************************************************************
Header: FGTrimLong.h
Author: Tony Peden
Date started: 7/1/99
------------- Copyright (C) 1999 Anthony K. Peden (apeden@earthlink.net) -------------
This program is free software; you can redistribute it and/or modify it under
the terms of the GNU General Public License as published by the Free Software
Foundation; either version 2 of the License, or (at your option) any later
version.
This program is distributed in the hope that it will be useful, but WITHOUT
ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
FOR A PARTICULAR PURPOSE. See the GNU General Public License for more
details.
You should have received a copy of the GNU General Public License along with
this program; if not, write to the Free Software Foundation, Inc., 59 Temple
Place - Suite 330, Boston, MA 02111-1307, USA.
Further information about the GNU General Public License can also be found on
the world wide web at http://www.gnu.org.
HISTORY
--------------------------------------------------------------------------------
9/8/99 TP Created
FUNCTIONAL DESCRIPTION
--------------------------------------------------------------------------------
This class takes the given set of IC's and finds the angle of attack, elevator,
and throttle setting required to fly steady level. This is currently for in-air
conditions only. It is implemented using an iterative, one-axis-at-a-time
scheme.
********************************************************************************
SENTRY
*******************************************************************************/
#ifndef FGTRIMLONG_H
#define FGTRIMLONG_H
/*******************************************************************************
INCLUDES
*******************************************************************************/
#include "FGFDMExec.h"
#include "FGRotation.h"
#include "FGAtmosphere.h"
#include "FGState.h"
#include "FGFCS.h"
#include "FGAircraft.h"
#include "FGTranslation.h"
#include "FGPosition.h"
#include "FGAuxiliary.h"
#include "FGOutput.h"
#include "FGTrimLong.h"
#define ELEV_MIN -1
#define ELEV_MAX 1
#define THROTTLE_MIN 0
#define THROTTLE_MAX 1
/*******************************************************************************
CLASS DECLARATION
*******************************************************************************/
class FGTrimLong {
private:
typedef float (FGTrimLong::*trimfp)(float);
int Ncycles,Naxis,Debug;
float Tolerance, A_Tolerance;
float alphaMin, alphaMax;
float wdot,udot,qdot;
float dth;
float udot_subits, wdot_subits, qdot_subits;
int total_its;
bool trimudot;
int axis_count;
trimfp udotf,wdotf,qdotf;
FGFDMExec* fdmex;
FGInitialCondition* fgic;
void setThrottlesPct(float tt);
int checkLimits(trimfp fp,float current,float min, float max);
// returns false if no sign change in fp(min)*fp(max) => no solution
bool solve(trimfp fp,float guess,float desired,float *result,float eps,float min, float max,int max_iterations,int *actual_its );
bool findInterval(trimfp fp, float *lo, float *hi,float guess,float desired,int max_iterations);
float udot_func(float x);
float wdot_func(float x);
float qdot_func(float x);
public:
FGTrimLong(FGFDMExec *FDMExec, FGInitialCondition *FGIC);
~FGTrimLong(void);
bool DoTrim(void);
void Report(void);
void ReportState(void);
void TrimStats();
inline void SetUdotTrim(bool bb) { trimudot=bb; }
inline bool GetUdotTrim(void) { return trimudot; }
inline void SetMaxCycles(int ii) { Ncycles = ii; }
inline void SetMaxCyclesPerAxis(int ii) { Naxis = ii; }
inline void SetTolerance(float tt) {
Tolerance = tt;
A_Tolerance = tt / 10;
}
//Debug level 1 shows results of each top-level iteration
//Debug level 2 shows level 1 & results of each per-axis iteration
inline void SetDebug(int level) { Debug = level; }
inline void ClearDebug(void) { Debug = 0; }
};
#endif

View file

@ -42,10 +42,6 @@ INCLUDES
DEFINES
*******************************************************************************/
#ifndef FGFS
using namespace std;
#endif
/*******************************************************************************
CLASS DECLARATION
*******************************************************************************/

View file

@ -42,28 +42,25 @@ COMMENTS, REFERENCES, and NOTES
INCLUDES
*******************************************************************************/
#include <stdlib.h>
#include <stdio.h>
#ifdef FGFS
# pragma message("FGFS defined")
# include <simgear/compiler.h>
# include STL_STRING
# ifdef FG_HAVE_STD_INCLUDES
# include <fstream>
# include <iostream>
# include <fstream>
# else
# include <fstream.h>
# include <iostream.h>
# include <fstream.h>
# endif
FG_USING_STD(string);
#else
# pragma message("FGFS not defined")
# include <string>
# include <fstream>
# include <iostream>
# include <fstream>
#endif
#include <string>
#include <sys/types.h>
#if defined(__BORLANDC__) || defined(_MSC_VER)
@ -79,12 +76,14 @@ INCLUDES
DEFINITIONS
*******************************************************************************/
using std::cout;
using std::endl;
/*******************************************************************************
CLASS DECLARATION
*******************************************************************************/
using namespace std;
using std::string;
class FGfdmSocket {
public:

View file

@ -71,6 +71,8 @@ USEUNIT("filtersjb\FGGain.cpp");
USEUNIT("filtersjb\FGGradient.cpp");
USEUNIT("filtersjb\FGSummer.cpp");
USEUNIT("filtersjb\FGDeadBand.cpp");
USEUNIT("FGTrimLong.cpp");
USEUNIT("filtersjb\FGFlaps.cpp");
//---------------------------------------------------------------------------
#pragma argsused
#endif

View file

@ -22,6 +22,7 @@ libJSBsim_a_SOURCES = FGAircraft.cpp FGAircraft.h \
FGRotation.cpp FGRotation.h \
FGState.cpp FGState.h \
FGTranslation.cpp FGTranslation.h \
FGTrimLong.cpp FGTrimLong.h \
FGUtility.cpp FGUtility.h \
FGEngine.cpp FGEngine.h \
FGTank.cpp FGTank.h \

View file

@ -1,104 +1,91 @@
CC = g++
INCLUDES = -I.
LINKDIR= -Lfiltersjb
LINKDIR= -Lfiltersjb/
JSBSim_objects = FGAircraft.o FGAtmosphere.o FGCoefficient.o FGFCS.o FGFDMExec.o\
FGModel.o FGOutput.o FGPosition.o FGRotation.o FGState.o FGTranslation.o\
FGUtility.o FGEngine.o FGTank.o FGAuxiliary.o FGfdmSocket.o\
FGConfigFile.o FGInitialCondition.o FGLGear.o FGMatrix.o
JSBSim : $(JSBSim_objects) JSBSim.o
echo "Making JSBSim"
cd filtersjb && make -fMakefile.solo && cd ..
g++ $(INCLUDES) $(CCOPTS) $(LINKDIR) $(JSBSim_objects) JSBSim.o -oJSBSim -lm -lFCSComponents
JSBSim : $(JSBSim_objects) JSBSim.o libFCSComponents.a
$(CC) $(INCLUDES) $(CCOPTS) $(LINKDIR) $(JSBSim_objects) JSBSim.o -oJSBSim -lm -lFCSComponents
libFCSComponents.a :
cd filtersjb; make -fMakefile.solo; cd ..
FGAircraft.o : FGAircraft.cpp
g++ $(INCLUDES) $(CCOPTS) -c FGAircraft.cpp
$(CC) $(INCLUDES) $(CCOPTS) -c FGAircraft.cpp
FGAtmosphere.o : FGAtmosphere.cpp
g++ $(INCLUDES) $(CCOPTS) -c FGAtmosphere.cpp
$(CC) $(INCLUDES) $(CCOPTS) -c FGAtmosphere.cpp
FGAuxiliary.o : FGAuxiliary.cpp
g++ $(INCLUDES) $(CCOPTS) -c FGAuxiliary.cpp
$(CC) $(INCLUDES) $(CCOPTS) -c FGAuxiliary.cpp
FGCoefficient.o : FGCoefficient.cpp
g++ $(INCLUDES) $(CCOPTS) -c FGCoefficient.cpp
$(CC) $(INCLUDES) $(CCOPTS) -c FGCoefficient.cpp
FGFCS.o : FGFCS.cpp
g++ $(INCLUDES) $(CCOPTS) -c FGFCS.cpp
$(CC) $(INCLUDES) $(CCOPTS) -c FGFCS.cpp
FGFDMExec.o : FGFDMExec.cpp
g++ $(INCLUDES) $(CCOPTS) -c FGFDMExec.cpp
$(CC) $(INCLUDES) $(CCOPTS) -c FGFDMExec.cpp
FGModel.o : FGModel.cpp
g++ $(INCLUDES) $(CCOPTS) -c FGModel.cpp
$(CC) $(INCLUDES) $(CCOPTS) -c FGModel.cpp
FGOutput.o : FGOutput.cpp
g++ $(INCLUDES) $(CCOPTS) -c FGOutput.cpp
$(CC) $(INCLUDES) $(CCOPTS) -c FGOutput.cpp
FGPosition.o : FGPosition.cpp
g++ $(INCLUDES) $(CCOPTS) -c FGPosition.cpp
$(CC) $(INCLUDES) $(CCOPTS) -c FGPosition.cpp
FGRotation.o : FGRotation.cpp
g++ $(INCLUDES) $(CCOPTS) -c FGRotation.cpp
$(CC) $(INCLUDES) $(CCOPTS) -c FGRotation.cpp
FGState.o : FGState.cpp
g++ $(INCLUDES) $(CCOPTS) -c FGState.cpp
$(CC) $(INCLUDES) $(CCOPTS) -c FGState.cpp
FGTranslation.o : FGTranslation.cpp
g++ $(INCLUDES) $(CCOPTS) -c FGTranslation.cpp
$(CC) $(INCLUDES) $(CCOPTS) -c FGTranslation.cpp
FGUtility.o : FGUtility.cpp
g++ $(INCLUDES) $(CCOPTS) -c FGUtility.cpp
$(CC) $(INCLUDES) $(CCOPTS) -c FGUtility.cpp
FGEngine.o : FGEngine.cpp
g++ $(INCLUDES) $(CCOPTS) -c FGEngine.cpp
$(CC) $(INCLUDES) $(CCOPTS) -c FGEngine.cpp
FGTank.o : FGTank.cpp
g++ $(INCLUDES) $(CCOPTS) -c FGTank.cpp
$(CC) $(INCLUDES) $(CCOPTS) -c FGTank.cpp
FGInitialCondition.o : FGInitialCondition.cpp
g++ $(INCLUDES) $(CCOPTS) -c FGInitialCondition.cpp
$(CC) $(INCLUDES) $(CCOPTS) -c FGInitialCondition.cpp
FGfdmSocket.o : FGfdmSocket.cpp
g++ $(INCLUDES) $(CCOPTS) -c FGfdmSocket.cpp
$(CC) $(INCLUDES) $(CCOPTS) -c FGfdmSocket.cpp
FGConfigFile.o : FGConfigFile.cpp
g++ $(INCLUDES) $(CCOPTS) -c FGConfigFile.cpp
$(CC) $(INCLUDES) $(CCOPTS) -c FGConfigFile.cpp
FGLGear.o : FGLGear.cpp
g++ $(INCLUDES) $(CCOPTS) -c FGLGear.cpp
$(CC) $(INCLUDES) $(CCOPTS) -c FGLGear.cpp
FGMatrix.o : FGMatrix.cpp
g++ $(INCLUDES) $(CCOPTS) -c FGMatrix.cpp
$(CC) $(INCLUDES) $(CCOPTS) -c FGMatrix.cpp
JSBSim.o : JSBSim.cpp
g++ $(INCLUDES) $(CCOPTS) -c JSBSim.cpp
gpswitch.o: gptest.cpp
g++ -DSWITCH $(INCLUDES) $(CCOPTS) -c gptest.cpp -o gpswitch.o
gpaop.o: gptest.cpp
g++ -DAOP $(INCLUDES) $(CCOPTS) -c gptest.cpp -o gpaop.o
gpmap.o: gptest.cpp
g++ -DMAP $(INCLUDES) $(CCOPTS) -c gptest.cpp -o gpmap.o
gpswitch: $(JSBSim_objects) gpswitch.o
g++ -DSWITCH $(LINKDIR) -o gpswitch gpswitch.o $(JSBSim_objects) -lm -lFCSComponents
gpaop: $(JSBSim_objects) gpaop.o
g++ -Daop $(LINKDIR) -o gpaop gpaop.o $(JSBSim_objects) -lm -lFCSComponents
gpmap: $(JSBSim_objects) gpmap.o
g++ -Dmap $(LINKDIR) -o gpmap gpmap.o $(JSBSim_objects) -lm -lFCSComponents
$(CC) $(INCLUDES) $(CCOPTS) -c JSBSim.cpp
clean:
mv *.*~ backup
rm *.o
-mv *.*~ backup
-rm *.o
all:
touch *.cpp
make JSBSim
cd filtersjb; make all CCOPTS=-g -fMakefile.solo; cd ..
make JSBSim -fMakefile.solo
debug:
env CCOPTS=-g -WALL
make all
touch *.cpp
touch filtersjb/*.cpp
cd filtersjb; make debug CCOPTS=-g -fMakefile.solo; cd ..
make JSBSim CCOPTS=-g -fMakefile.solo

View file

@ -0,0 +1,170 @@
/*******************************************************************************
Module: FGFlap.cpp
Author: Tony Peden, for flight control system authored by Jon S. Berndt
Date started: 5/11/00
------------- Copyright (C) 2000 Anthony K. Peden -------------
This program is free software; you can redistribute it and/or modify it under
the terms of the GNU General Public License as published by the Free Software
Foundation; either version 2 of the License, or (at your option) any later
version.
This program is distributed in the hope that it will be useful, but WITHOUT
ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
FOR A PARTICULAR PURPOSE. See the GNU General Public License for more
details.
You should have received a copy of the GNU General Public License along with
this program; if not, write to the Free Software Foundation, Inc., 59 Temple
Place - Suite 330, Boston, MA 02111-1307, USA.
Further information about the GNU General Public License can also be found on
the world wide web at http://www.gnu.org.
FUNCTIONAL DESCRIPTION
--------------------------------------------------------------------------------
HISTORY
--------------------------------------------------------------------------------
********************************************************************************
COMMENTS, REFERENCES, and NOTES
********************************************************************************
********************************************************************************
INCLUDES
*******************************************************************************/
#include "FGFlaps.h"
/*******************************************************************************
************************************ CODE **************************************
*******************************************************************************/
// *****************************************************************************
// Function: Constructor
// Purpose:
// Parameters: void
// Comments:
FGFlaps::FGFlaps(FGFCS* fcs, FGConfigFile* AC_cfg) : FGFCSComponent(fcs),
AC_cfg(AC_cfg) {
string token;
float tmpDetent;
float tmpTime;
Detents.clear();
TransitionTimes.clear();
Type = AC_cfg->GetValue("TYPE");
Name = AC_cfg->GetValue("NAME");
AC_cfg->GetNextConfigLine();
while ((token = AC_cfg->GetValue()) != "/COMPONENT") {
*AC_cfg >> token;
if (token == "ID") {
*AC_cfg >> ID;
cout << " ID: " << ID << endl;
} else if (token == "INPUT") {
token = AC_cfg->GetValue("INPUT");
cout << " INPUT: " << token << endl;
if (token.find("FG_") != token.npos) {
*AC_cfg >> token;
InputIdx = fcs->GetState()->GetParameterIndex(token);
InputType = itPilotAC;
}
} else if ( token == "DETENTS" ) {
*AC_cfg >> NumDetents;
cout << " DETENTS: " << NumDetents << endl;
for(int i=0;i<NumDetents;i++) {
*AC_cfg >> tmpDetent;
*AC_cfg >> tmpTime;
Detents.push_back(tmpDetent);
TransitionTimes.push_back(tmpTime);
cout << " " << Detents[i] << " " << TransitionTimes[i] << endl;
}
} else if (token == "OUTPUT") {
IsOutput = true;
*AC_cfg >> sOutputIdx;
cout << " OUTPUT: " <<sOutputIdx << endl;
OutputIdx = fcs->GetState()->GetParameterIndex(sOutputIdx);
}
}
}
// *****************************************************************************
// Function: Run
// Purpose:
// Parameters: void
// Comments:
bool FGFlaps::Run(void ) {
float dt=fcs->GetState()->Getdt();
float flap_transit_rate=0;
FGFCSComponent::Run(); // call the base class for initialization of Input
Flap_Handle=Input*Detents[NumDetents-1];
Flap_Position=fcs->GetState()->GetParameter(OutputIdx);
if(Flap_Handle < Detents[0]) {
fi=0;
Flap_Handle=Detents[0];
lastFlapHandle=Flap_Handle;
Flap_Position=Detents[0];
Output=Flap_Position;
} else if(Flap_Handle > Detents[NumDetents-1]) {
fi=NumDetents-1;
Flap_Handle=Detents[fi];
lastFlapHandle=Flap_Handle;
Flap_Position=Detents[fi];
Output=Flap_Position;
} else {
//cout << "FGFlaps::Run Handle: " << Flap_Handle << " Position: " << Flap_Position << endl;
if(dt <= 0)
Flap_Position=Flap_Handle;
else {
if(Flap_Handle != lastFlapHandle) {
Flaps_In_Transit=1;
}
if(Flaps_In_Transit) {
//fprintf(stderr,"Flap_Handle: %g, Flap_Position: %g\n",Flap_Handle,Flap_Position);
fi=0;
while(Detents[fi] < Flap_Handle) {
fi++;
}
if(Flap_Position < Flap_Handle) {
if(TransitionTimes[fi] > 0)
flap_transit_rate=(Detents[fi] - Detents[fi-1])/TransitionTimes[fi];
else
flap_transit_rate=(Detents[fi] - Detents[fi-1])/5;
} else {
if(TransitionTimes[fi+1] > 0)
flap_transit_rate=(Detents[fi] - Detents[fi+1])/TransitionTimes[fi+1];
else
flap_transit_rate=(Detents[fi] - Detents[fi+1])/5;
}
if(fabs(Flap_Position - Flap_Handle) > dt*flap_transit_rate)
Flap_Position+=flap_transit_rate*dt;
else {
Flaps_In_Transit=0;
Flap_Position=Flap_Handle;
}
}
}
lastFlapHandle=Flap_Handle;
Output=Flap_Position;
}
//cout << "FGFlaps::Run Handle: " << Flap_Handle << " Position: " << Flap_Position << " Output: " << Output << endl;
if (IsOutput) {
//cout << "Calling SetOutput()" << endl;
SetOutput();
}
//cout << "Out FGFlap::Run" << endl;
return true;
}

View file

@ -0,0 +1,87 @@
/*******************************************************************************
Header: FGFlap.h
Author: Tony Peden, for flight control system authored by Jon S. Berndt
Date started: 5/11/00
------------- Copyright (C) Anthony K. Peden -------------
This program is free software; you can redistribute it and/or modify it under
the terms of the GNU General Public License as published by the Free Software
Foundation; either version 2 of the License, or (at your option) any later
version.
This program is distributed in the hope that it will be useful, but WITHOUT
ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
FOR A PARTICULAR PURPOSE. See the GNU General Public License for more
details.
You should have received a copy of the GNU General Public License along with
this program; if not, write to the Free Software Foundation, Inc., 59 Temple
Place - Suite 330, Boston, MA 02111-1307, USA.
Further information about the GNU General Public License can also be found on
the world wide web at http://www.gnu.org.
HISTORY
--------------------------------------------------------------------------------
********************************************************************************
COMMENTS, REFERENCES, and NOTES
********************************************************************************
********************************************************************************
SENTRY
*******************************************************************************/
#ifndef FGFlap_H
#define FGFlap_H
/*******************************************************************************
INCLUDES
*******************************************************************************/
#ifdef FGFS
# include <simgear/compiler.h>
# ifdef FG_HAVE_STD_INCLUDES
# include <vector>
# else
# include <vector.h>
# endif
#else
# include <vector>
#endif
#include <string>
#include "FGFCSComponent.h"
#include "../FGConfigFile.h"
/*******************************************************************************
DEFINES
*******************************************************************************/
/*******************************************************************************
CLASS DECLARATION
*******************************************************************************/
class FGFlaps : public FGFCSComponent {
FGConfigFile* AC_cfg;
vector<float> Detents;
vector<float> TransitionTimes;
int NumDetents,fi;
float lastFlapHandle;
float Flap_Handle;
float Flap_Position;
bool Flaps_In_Transit;
public:
FGFlaps(FGFCS* fcs, FGConfigFile* AC_cfg);
~FGFlaps ( ) { } //Destructor
bool Run (void );
};
#endif

View file

@ -68,8 +68,10 @@ FGGain::FGGain(FGFCS* fcs, FGConfigFile* AC_cfg) : FGFCSComponent(fcs),
*AC_cfg >> token;
if (token == "ID") {
*AC_cfg >> ID;
cout << " ID: " << ID << endl;
} else if (token == "INPUT") {
token = AC_cfg->GetValue("INPUT");
cout << " INPUT: " << token << endl;
if (token.find("FG_") != token.npos) {
*AC_cfg >> token;
InputIdx = fcs->GetState()->GetParameterIndex(token);
@ -80,16 +82,20 @@ FGGain::FGGain(FGFCS* fcs, FGConfigFile* AC_cfg) : FGFCSComponent(fcs),
}
} else if (token == "GAIN") {
*AC_cfg >> Gain;
cout << " GAIN: " << Gain << endl;
} else if (token == "MIN") {
*AC_cfg >> Min;
cout << " MIN: " << Min << endl;
} else if (token == "MAX") {
*AC_cfg >> Max;
cout << " MAX: " << Max << endl;
} else if (token == "SCHEDULED_BY") {
*AC_cfg >> ScheduledBy;
} else if (token == "OUTPUT") {
IsOutput = true;
*AC_cfg >> sOutputIdx;
OutputIdx = fcs->GetState()->GetParameterIndex(sOutputIdx);
cout << " OUTPUT: " << sOutputIdx << endl;
} else {
AC_cfg->ResetLineIndexToZero();
lookup = new float[2];

View file

@ -44,8 +44,6 @@ INCLUDES
#ifdef FGFS
# include <simgear/compiler.h>
# include STL_STRING
FG_USING_STD(string);
# ifdef FG_HAVE_STD_INCLUDES
# include <vector>
# else
@ -53,9 +51,9 @@ INCLUDES
# endif
#else
# include <vector>
# include <string>
#endif
#include <string>
#include "FGFCSComponent.h"
#include "../FGConfigFile.h"

View file

@ -56,6 +56,7 @@ FGSummer::FGSummer(FGFCS* fcs, FGConfigFile* AC_cfg) : FGFCSComponent(fcs),
string token;
int tmpInputIndex;
clip = false;
InputIndices.clear();
InputTypes.clear();
@ -67,8 +68,10 @@ FGSummer::FGSummer(FGFCS* fcs, FGConfigFile* AC_cfg) : FGFCSComponent(fcs),
*AC_cfg >> token;
if (token == "ID") {
*AC_cfg >> ID;
cout << " ID: " << ID << endl;
} else if (token == "INPUT") {
token = AC_cfg->GetValue("INPUT");
cout << " INPUT: " << token << endl;
if (token.find("FG_") != token.npos) {
*AC_cfg >> token;
tmpInputIndex = fcs->GetState()->GetParameterIndex(token);
@ -79,9 +82,17 @@ FGSummer::FGSummer(FGFCS* fcs, FGConfigFile* AC_cfg) : FGFCSComponent(fcs),
InputIndices.push_back(tmpInputIndex);
InputTypes.push_back(itFCS);
}
} else if (token == "CLIPTO") {
*AC_cfg >> clipmin >> clipmax;
if(clipmax > clipmin) {
clip=true;
cout << " CLIPTO: " << clipmin << ", " << clipmax << endl;
}
} else if (token == "OUTPUT") {
IsOutput = true;
*AC_cfg >> sOutputIdx;
cout << " OUTPUT: " <<sOutputIdx << endl;
OutputIdx = fcs->GetState()->GetParameterIndex(sOutputIdx);
}
}
@ -108,12 +119,18 @@ bool FGSummer::Run(void )
break;
case itFCS:
Output += fcs->GetComponentOutput(InputIndices[idx]);
break;
}
}
if (IsOutput) SetOutput();
if(clip) {
if(Output > clipmax)
Output=clipmax;
else if(Output < clipmin)
Output=clipmin;
}
if (IsOutput) { SetOutput(); }
//cout << "Out FGSummer::Run" << endl;
return true;
}

View file

@ -44,8 +44,6 @@ INCLUDES
#ifdef FGFS
# include <simgear/compiler.h>
# include STL_STRING
FG_USING_STD(string);
# ifdef FG_HAVE_STD_INCLUDES
# include <vector>
# else
@ -53,9 +51,9 @@ INCLUDES
# endif
#else
# include <vector>
# include <string>
#endif
#include <string>
#include "FGFCSComponent.h"
#include "../FGConfigFile.h"
@ -72,6 +70,9 @@ class FGSummer : public FGFCSComponent
FGConfigFile* AC_cfg;
vector<int> InputIndices;
vector<int> InputTypes;
bool clip;
float clipmin,clipmax;
public:
FGSummer(FGFCS* fcs, FGConfigFile* AC_cfg);

View file

@ -6,6 +6,7 @@ libfiltersjb_a_SOURCES = \
FGDeadBand.cpp FGDeadBand.h \
FGFCSComponent.cpp FGFCSComponent.h \
FGFilter.cpp FGFilter.h \
FGFlaps.cpp FGFlaps.h \
FGGain.cpp FGGain.h \
FGGradient.cpp FGGradient.h \
FGSummer.cpp FGSummer.h \

View file

@ -1,34 +1,38 @@
libFCSComponents_OBJECTS = FGDeadBand.o FGFilter.o FGGradient.o FGSwitch.o \
FGFCSComponent.o FGGain.o FGSummer.o
CC = g++
libFCSComponents_OBJECTS = FGDeadBand.o FGFilter.o FGGradient.o FGSwitch.o \
FGFCSComponent.o FGGain.o FGSummer.o FGFlaps.o
INCLUDES = -I../
libFCSComponents.a : $(libFCSComponents_OBJECTS)
echo "Making filters..."
-rm -f libFCSComponents.a
ar cru libFCSComponents.a $(libFCSComponents_OBJECTS)
ranlib libFCSComponents.a
FGDeadBand.o : FGDeadBand.cpp FGDeadBand.h
g++ $(INCLUDES) $(CCOPTS) -c FGDeadBand.cpp
FGFilter.o : FGFilter.cpp FGFilter.h
g++ $(INCLUDES) $(CCOPTS) -c FGFilter.cpp
FGGradient.o : FGGradient.cpp FGGradient.h
g++ $(INCLUDES) $(CCOPTS) -c FGGradient.cpp
FGSwitch.o : FGSwitch.cpp FGSwitch.h
g++ $(INCLUDES) $(CCOPTS) -c FGSwitch.cpp
FGFCSComponent.o : FGFCSComponent.cpp FGFCSComponent.h
g++ $(INCLUDES) $(CCOPTS) -c FGFCSComponent.cpp
FGGain.o : FGGain.cpp FGGain.h
g++ $(INCLUDES) $(CCOPTS) -c FGGain.cpp
FGSummer.o : FGSummer.cpp FGSummer.h
g++ $(INCLUDES) $(CCOPTS) -c FGSummer.cpp
FGDeadBand.o: FGDeadBand.cpp FGDeadBand.h
$(CC) $(INCLUDES) $(CCOPTS) -c FGDeadBand.cpp
FGFilter.o: FGFilter.cpp FGFilter.h
$(CC) $(INCLUDES) $(CCOPTS) -c FGFilter.cpp
FGGradient.o: FGGradient.cpp FGGradient.h
$(CC) $(INCLUDES) $(CCOPTS) -c FGGradient.cpp
FGSwitch.o: FGSwitch.cpp FGSwitch.h
$(CC) $(INCLUDES) $(CCOPTS) -c FGSwitch.cpp
FGFCSComponent.o: FGFCSComponent.cpp FGFCSComponent.h
$(CC) $(INCLUDES) $(CCOPTS) -c FGFCSComponent.cpp
FGGain.o: FGGain.cpp FGGain.h
$(CC) $(INCLUDES) $(CCOPTS) -c FGGain.cpp
FGSummer.o: FGSummer.cpp FGSummer.h
$(CC) $(INCLUDES) $(CCOPTS) -c FGSummer.cpp
FGFlaps.o: FGFlaps.cpp FGFlaps.h
$(CC) $(INCLUDES) $(CCOPTS) -c FGFlaps.cpp
clean:
rm -f *.o
rm -f *.a
-rm -f *.o
-rm -f *.a
all:
touch *.cpp
make libFCSComponents.a -fMakefile.solo
debug:
make all CCOPTS=-g -fMakefile.solo

View file

@ -544,6 +544,13 @@ bool fgInitSubsystems( void ) {
// Autopilot init
current_autopilot = new FGAutopilot;
current_autopilot->init();
if ( current_options.get_trim_mode() == true ) {
current_autopilot->set_AutoThrottleEnabled(
!current_autopilot->get_AutoThrottleEnabled() );
current_autopilot->AutoThrottleAdjust(
controls.get_trimmed_throttle(0) );
}
// initialize the gui parts of the autopilot
NewTgtAirportInit();

View file

@ -85,7 +85,7 @@
// #defines in uiuc_aircraft.h
#include "bfi.hxx"
// #include <FDM/UIUCModel/uiuc_aircraft.h>
q#include <FDM/UIUCModel/uiuc_aircraft.h>
#include <FDM/UIUCModel/uiuc_aircraftdir.h>
#include <GUI/gui.h>
#include <Joystick/joystick.hxx>

View file

@ -147,7 +147,7 @@ fgOPTIONS::fgOPTIONS() :
pitch(0.424), // pitch angle in degrees (Theta)
// Initialize current options velocities to 0.0
uBody(0.0), vBody(0.0), wBody(0.0),
uBody(0.0), vBody(0.0), wBody(0.0), vkcas(0.0), mach(0.0),
// Miscellaneous
game_mode(0),
@ -169,6 +169,7 @@ fgOPTIONS::fgOPTIONS() :
aircraft( "c172" ),
model_hz( NEW_DEFAULT_MODEL_HZ ),
speed_up( 1 ),
trim(true),
// Rendering options
fog(FG_FOG_NICEST), // nicest
@ -643,23 +644,33 @@ int fgOPTIONS::parse_option( const string& arg ) {
altitude = atof( arg.substr(11) );
}
} else if ( arg.find( "--uBody=" ) != string::npos ) {
vkcas=mach=-1;
if ( units == FG_UNITS_FEET ) {
uBody = atof( arg.substr(8) );
} else {
uBody = atof( arg.substr(8) ) * FEET_TO_METER;
}
} else if ( arg.find( "--vBody=" ) != string::npos ) {
vkcas=mach=-1;
if ( units == FG_UNITS_FEET ) {
vBody = atof( arg.substr(8) );
} else {
vBody = atof( arg.substr(8) ) * FEET_TO_METER;
}
} else if ( arg.find( "--wBody=" ) != string::npos ) {
vkcas=mach=-1;
if ( units == FG_UNITS_FEET ) {
wBody = atof( arg.substr(8) );
} else {
wBody = atof( arg.substr(8) ) * FEET_TO_METER;
}
} else if ( arg.find( "--vc=" ) != string::npos) {
mach=-1;
vkcas=atof( arg.substr(5) );
cout << "Got vc: " << vkcas << endl;
} else if ( arg.find( "--mach=" ) != string::npos) {
vkcas=-1;
mach=atof( arg.substr(7) );
} else if ( arg.find( "--heading=" ) != string::npos ) {
heading = atof( arg.substr(10) );
} else if ( arg.find( "--roll=" ) != string::npos ) {
@ -678,6 +689,8 @@ int fgOPTIONS::parse_option( const string& arg ) {
model_hz = atoi( arg.substr(11) );
} else if ( arg.find( "--speed=" ) != string::npos ) {
speed_up = atoi( arg.substr(8) );
} else if ( arg.find( "--notrim") != string::npos) {
trim=false;
} else if ( arg == "--fog-disable" ) {
fog = FG_FOG_DISABLED;
} else if ( arg == "--fog-fastest" ) {
@ -914,6 +927,7 @@ void fgOPTIONS::usage ( void ) {
cout << "\t--model-hz=n: run the FDM this rate (iterations per second)"
<< endl;
cout << "\t--speed=n: run the FDM this much faster than real time" << endl;
cout << "\t--notrim: Do NOT attempt to trim the model when initializing JSBsim" << endl;
cout << endl;
//(UIUC)
cout <<"Aircraft model directory" << endl;
@ -940,6 +954,8 @@ void fgOPTIONS::usage ( void ) {
cout << "\t--wBody=feet per second: velocity along the body Z axis"
<< endl;
cout << "\t\t(unless --units-meters specified" << endl;
cout << "\t--vc= initial airspeed in knots (--fdm=jsb only)" << endl;
cout << "\t--mach= initial mach number (--fdm=jsb only)" << endl;
cout << endl;
cout << "Rendering Options:" << endl;

View file

@ -139,6 +139,8 @@ private:
double uBody; // Body axis X velocity (U)
double vBody; // Body axis Y velocity (V)
double wBody; // Body axis Z velocity (W)
double vkcas; // Calibrated airspeed, knots
double mach; // Mach number
// Miscellaneous
bool game_mode; // Game mode enabled/disabled
@ -160,6 +162,7 @@ private:
string aircraft; // Aircraft to model
int model_hz; // number of FDM iterations per second
int speed_up; // Sim mechanics run this much faster than normal speed
bool trim; // use the FDM trimming routine during init
// Rendering options
fgFogKind fog; // Fog nicest/fastest/disabled
@ -228,6 +231,9 @@ public:
inline double get_uBody() const {return uBody;}
inline double get_vBody() const {return vBody;}
inline double get_wBody() const {return wBody;}
inline double get_vc() const {return vkcas;}
inline double get_mach() const {return mach;}
inline bool get_game_mode() const { return game_mode; }
inline bool get_splash_screen() const { return splash_screen; }
inline bool get_intro_music() const { return intro_music; }
@ -250,6 +256,8 @@ public:
inline int get_model_hz() const { return model_hz; }
inline int get_speed_up() const { return speed_up; }
inline void set_speed_up( int speed ) { speed_up = speed; }
inline bool get_trim_mode(void) { return trim; }
inline bool fog_enabled() const { return fog != FG_FOG_DISABLED; }
inline fgFogKind get_fog() const { return fog; }
inline bool get_clouds() const { return clouds; }
@ -292,6 +300,8 @@ public:
inline void set_uBody (double value) { uBody = value; }
inline void set_vBody (double value) { vBody = value; }
inline void set_wBody (double value) { wBody = value; }
inline void set_vc (double value) { vkcas = value; }
inline void set_mach(double value) { mach = value; }
inline void set_game_mode (bool value) { game_mode = value; }
inline void set_splash_screen (bool value) { splash_screen = value; }
inline void set_intro_music (bool value) { intro_music = value; }
@ -303,6 +313,7 @@ public:
inline void set_flight_model (int value) { flight_model = value; }
inline void set_aircraft (const string &ac) { aircraft = ac; }
inline void set_model_hz (int value) { model_hz = value; }
inline void set_trim_mode(bool bb) { trim=bb; }
inline void set_fog (fgFogKind value) { fog = value; }
inline void set_clouds( bool value ) { clouds = value; }
inline void set_clouds_asl( double value ) { clouds_asl = value; }