]> git.mxchange.org Git - flightgear.git/blob - src/FDM/JSBSim.cxx
6abc5e2a0c01b091737bb5dbb1cd43e7763693f4
[flightgear.git] / src / FDM / JSBSim.cxx
1 // JSBsim.cxx -- interface to the JSBsim flight model
2 //
3 // Written by Curtis Olson, started February 1999.
4 //
5 // Copyright (C) 1999  Curtis L. Olson  - curt@flightgear.org
6 //
7 // This program is free software; you can redistribute it and/or
8 // modify it under the terms of the GNU General Public License as
9 // published by the Free Software Foundation; either version 2 of the
10 // License, or (at your option) any later version.
11 //
12 // This program is distributed in the hope that it will be useful, but
13 // WITHOUT ANY WARRANTY; without even the implied warranty of
14 // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
15 // General Public License for more details.
16 //
17 // You should have received a copy of the GNU General Public License
18 // along with this program; if not, write to the Free Software
19 // Foundation, Inc., 675 Mass Ave, Cambridge, MA 02139, USA.
20 //
21 // $Id$
22
23
24 #include <simgear/compiler.h>
25
26 #ifdef FG_MATH_EXCEPTION_CLASH
27 #  include <math.h>
28 #endif
29
30 #include STL_STRING
31
32 #include <simgear/constants.h>
33 #include <simgear/debug/logstream.hxx>
34 #include <simgear/math/sg_geodesy.hxx>
35 #include <simgear/misc/fgpath.hxx>
36
37 #include <Scenery/scenery.hxx>
38
39 #include <Aircraft/aircraft.hxx>
40 #include <Controls/controls.hxx>
41 #include <Main/options.hxx>
42
43 #include <FDM/JSBSim/FGFDMExec.h>
44 #include <FDM/JSBSim/FGAircraft.h>
45 #include <FDM/JSBSim/FGFCS.h>
46 #include <FDM/JSBSim/FGPosition.h>
47 #include <FDM/JSBSim/FGRotation.h>
48 #include <FDM/JSBSim/FGState.h>
49 #include <FDM/JSBSim/FGTranslation.h>
50 #include <FDM/JSBSim/FGAuxiliary.h>
51 #include <FDM/JSBSim/FGDefs.h>
52 #include <FDM/JSBSim/FGInitialCondition.h>
53 #include <FDM/JSBSim/FGTrim.h>
54 #include <FDM/JSBSim/FGAtmosphere.h>
55
56 #include "JSBSim.hxx"
57
58 /******************************************************************************/
59
60 // Initialize the JSBsim flight model, dt is the time increment for
61 // each subsequent iteration through the EOM
62
63 int FGJSBsim::init( double dt ) {
64
65   bool result;
66
67   FG_LOG( FG_FLIGHT, FG_INFO, "Starting and initializing JSBsim" );
68   FG_LOG( FG_FLIGHT, FG_INFO, "  created FDMExec" );
69
70   FGPath aircraft_path( current_options.get_fg_root() );
71   aircraft_path.append( "Aircraft" );
72
73   FGPath engine_path( current_options.get_fg_root() );
74   engine_path.append( "Engine" );
75
76   //FDMExec.GetState()->Setdt( dt );
77
78   result = FDMExec.LoadModel( aircraft_path.str(),
79                                        engine_path.str(),
80                                        current_options.get_aircraft() );
81   FDMExec.GetState()->Setdt( dt );
82   
83   if (result) {
84     FG_LOG( FG_FLIGHT, FG_INFO, "  loaded aircraft " << current_options.get_aircraft() );
85   } else {
86     FG_LOG( FG_FLIGHT, FG_INFO, "  aircraft" << current_options.get_aircraft()
87                                 << " does not exist");
88     return 0;
89   }
90
91   FDMExec.GetAtmosphere()->SetExTemperature(get_Static_temperature());
92   FDMExec.GetAtmosphere()->SetExPressure(get_Static_pressure());
93   FDMExec.GetAtmosphere()->SetExDensity(get_Density());
94   FDMExec.GetAtmosphere()->SetWindNED(get_V_north_airmass(),
95                                       get_V_east_airmass(),
96                                       get_V_down_airmass());
97  
98   FDMExec.GetAtmosphere()->UseInternal();
99   
100  
101   FDMExec.GetPosition()->SetRunwayRadius(scenery.cur_radius*METER_TO_FEET);
102   FDMExec.GetPosition()->SetSeaLevelRadius(get_Sea_level_radius());
103
104   FG_LOG( FG_FLIGHT, FG_INFO, "  Initializing JSBSim with:" );
105   
106   FGInitialCondition *fgic = new FGInitialCondition(&FDMExec);
107   fgic->SetAltitudeFtIC(get_Altitude());
108   if((current_options.get_mach() < 0) && (current_options.get_vc() < 0 )) {
109     fgic->SetUBodyFpsIC(current_options.get_uBody());
110     fgic->SetVBodyFpsIC(current_options.get_vBody());
111     fgic->SetWBodyFpsIC(current_options.get_wBody());
112     FG_LOG(FG_FLIGHT,FG_INFO, "  u,v,w= " << current_options.get_uBody()
113            << ", " << current_options.get_vBody()
114            << ", " << current_options.get_wBody());
115   } else if (current_options.get_vc() < 0) {
116     fgic->SetMachIC(current_options.get_mach());
117     FG_LOG(FG_FLIGHT,FG_INFO, "  mach: " << current_options.get_mach() );
118   } else {
119     fgic->SetVcalibratedKtsIC(current_options.get_vc());
120     FG_LOG(FG_FLIGHT,FG_INFO, "  vc: " << current_options.get_vc() );
121     //this should cover the case in which no speed switches are used
122     //current_options.get_vc() will return zero by default
123   }
124
125   //fgic->SetFlightPathAngleDegIC(current_options.get_Gamma());
126   fgic->SetRollAngleRadIC(get_Phi());
127   fgic->SetPitchAngleRadIC(get_Theta());
128   fgic->SetHeadingRadIC(get_Psi());
129   fgic->SetLatitudeRadIC(get_Lat_geocentric());
130   fgic->SetLongitudeRadIC(get_Longitude());
131
132   
133   
134   
135   //FG_LOG( FG_FLIGHT, FG_INFO, "  gamma: " <<  current_options.get_Gamma());
136   FG_LOG( FG_FLIGHT, FG_INFO, "  phi: " <<  get_Phi());
137   //FG_LOG( FG_FLIGHT, FG_INFO, "  theta: " <<  get_Theta() );
138   FG_LOG( FG_FLIGHT, FG_INFO, "  psi: " <<  get_Psi() );
139   FG_LOG( FG_FLIGHT, FG_INFO, "  lat: " <<  get_Latitude() );
140   FG_LOG( FG_FLIGHT, FG_INFO, "  lon: " <<  get_Longitude() );
141   
142   FG_LOG( FG_FLIGHT, FG_INFO, "  Pressure Altiude: " <<  get_Altitude() );
143   FG_LOG( FG_FLIGHT, FG_INFO, "  Terrain Altitude: " 
144           <<  scenery.cur_radius*METER_TO_FEET );
145   FG_LOG( FG_FLIGHT, FG_INFO, "      AGL Altitude: " 
146           <<  get_Altitude() + get_Sea_level_radius()
147                 - scenery.cur_radius*METER_TO_FEET );
148   
149   FG_LOG( FG_FLIGHT, FG_INFO, "      current_options.get_altitude(): " 
150           <<  current_options.get_altitude() );
151   //must check > 0, != 0 will give bad result if --notrim set
152   if(current_options.get_trim_mode() > 0) {
153     FDMExec.RunIC(fgic);
154     FG_LOG( FG_FLIGHT, FG_INFO, "  Starting trim..." );
155     FGTrim *fgtrim=new FGTrim(&FDMExec,fgic,tLongitudinal);
156     fgtrim->DoTrim();
157     fgtrim->Report();
158     fgtrim->TrimStats();
159     fgtrim->ReportState();
160
161
162     controls.set_elevator_trim(FDMExec.GetFCS()->GetPitchTrimCmd());
163     controls.set_throttle(FGControls::ALL_ENGINES,FDMExec.GetFCS()->GetThrottleCmd(0)/100);
164     trimmed=true;
165     trim_elev=FDMExec.GetFCS()->GetPitchTrimCmd();
166     trim_throttle=FDMExec.GetFCS()->GetThrottleCmd(0)/100;
167     //the trimming routine only knows how to get 1 value for throttle
168     
169     delete fgtrim;
170     FG_LOG( FG_FLIGHT, FG_INFO, "  Trim complete." );
171   } else {
172     FG_LOG( FG_FLIGHT, FG_INFO, "  Initializing without trim" );
173     FDMExec.GetState()->Initialize(fgic);
174
175   }
176
177   delete fgic;
178
179   FG_LOG( FG_FLIGHT, FG_INFO, "  loaded initial conditions" );
180
181   FG_LOG( FG_FLIGHT, FG_INFO, "  set dt" );
182
183   FG_LOG( FG_FLIGHT, FG_INFO, "Finished initializing JSBSim" );
184
185   copy_from_JSBsim();
186
187   return 1;
188 }
189
190 /******************************************************************************/
191
192 // Run an iteration of the EOM (equations of motion)
193
194 int FGJSBsim::update( int multiloop ) {
195   double save_alt = 0.0;
196   double time_step = (1.0 / current_options.get_model_hz()) * multiloop;
197   double start_elev = get_Altitude();
198  
199   
200   // lets try to avoid really screwing up the JSBsim model
201   if ( get_Altitude() < -9000 ) {
202     save_alt = get_Altitude();
203     set_Altitude( 0.0 );
204   }
205   
206   if(trimmed) {
207     
208     controls.set_elevator_trim(trim_elev);
209     controls.set_throttle(FGControls::ALL_ENGINES,trim_throttle);
210     
211     controls.set_elevator(0.0);
212     controls.set_aileron(0.0);
213     controls.set_rudder(0.0);
214     trimmed=false;
215     
216   } 
217   
218   copy_to_JSBsim();
219
220   for ( int i = 0; i < multiloop; i++ ) {
221     FDMExec.Run();
222   }
223
224   // printf("%d FG_Altitude = %.2f\n", i, FG_Altitude * 0.3048);
225   // printf("%d Altitude = %.2f\n", i, Altitude * 0.3048);
226
227   // translate JSBsim back to FG structure so that the
228   // autopilot (and the rest of the sim can use the updated values
229
230   copy_from_JSBsim();
231
232   // but lets restore our original bogus altitude when we are done
233
234   if ( save_alt < -9000.0 ) {
235     set_Altitude( save_alt );
236   }
237
238   double end_elev = get_Altitude();
239
240   return 1;
241 }
242
243 /******************************************************************************/
244
245 // Convert from the FGInterface struct to the JSBsim generic_ struct
246
247 int FGJSBsim::copy_to_JSBsim() {
248   // copy control positions into the JSBsim structure
249
250   FDMExec.GetFCS()->SetDaCmd( controls.get_aileron());
251   FDMExec.GetFCS()->SetDeCmd( controls.get_elevator());
252   FDMExec.GetFCS()->SetPitchTrimCmd(controls.get_elevator_trim());
253   FDMExec.GetFCS()->SetDrCmd( controls.get_rudder());
254   FDMExec.GetFCS()->SetDfCmd( controls.get_flaps() );
255   FDMExec.GetFCS()->SetDsbCmd( 0.0 ); //speedbrakes
256   FDMExec.GetFCS()->SetDspCmd( 0.0 ); //spoilers
257   FDMExec.GetFCS()->SetThrottleCmd( FGControls::ALL_ENGINES,
258                                     controls.get_throttle( 0 ) * 100.0 );
259
260   FDMExec.GetFCS()->SetLBrake( controls.get_brake( 0 ) );
261   FDMExec.GetFCS()->SetRBrake( controls.get_brake( 1 ) );
262   FDMExec.GetFCS()->SetCBrake( controls.get_brake( 2 ) );
263
264   // Inform JSBsim of the local terrain altitude; uncommented 5/3/00
265   //  FDMExec.GetPosition()->SetRunwayElevation(get_Runway_altitude()); // seems to work
266   FDMExec.GetPosition()->SetRunwayRadius(scenery.cur_radius*METER_TO_FEET);
267   FDMExec.GetPosition()->SetSeaLevelRadius(get_Sea_level_radius());
268
269   FDMExec.GetAtmosphere()->SetExTemperature(get_Static_temperature());
270   FDMExec.GetAtmosphere()->SetExPressure(get_Static_pressure());
271   FDMExec.GetAtmosphere()->SetExDensity(get_Density());
272   FDMExec.GetAtmosphere()->SetWindNED(get_V_north_airmass(),
273                                       get_V_east_airmass(),
274                                       get_V_down_airmass());
275
276   return 1;
277 }
278
279 /******************************************************************************/
280
281 // Convert from the JSBsim generic_ struct to the FGInterface struct
282
283 int FGJSBsim::copy_from_JSBsim() {
284
285   set_Inertias( FDMExec.GetAircraft()->GetMass(),
286                 FDMExec.GetAircraft()->GetIxx(),
287                 FDMExec.GetAircraft()->GetIyy(),
288                 FDMExec.GetAircraft()->GetIzz(),
289                 FDMExec.GetAircraft()->GetIxz() );
290   
291   set_CG_Position ( FDMExec.GetAircraft()->GetXYZcg()(1),
292                     FDMExec.GetAircraft()->GetXYZcg()(2),
293                     FDMExec.GetAircraft()->GetXYZcg()(3) );
294   
295   set_Accels_Body ( FDMExec.GetTranslation()->GetUVWdot()(1),
296                     FDMExec.GetTranslation()->GetUVWdot()(2),
297                     FDMExec.GetTranslation()->GetUVWdot()(3) );
298   
299   set_Accels_CG_Body ( FDMExec.GetTranslation()->GetUVWdot()(1),
300                        FDMExec.GetTranslation()->GetUVWdot()(2),
301                        FDMExec.GetTranslation()->GetUVWdot()(3) );
302   
303   //set_Accels_CG_Body_N ( FDMExec.GetTranslation()->GetNcg()(1),
304   //                       FDMExec.GetTranslation()->GetNcg()(2),
305   //                       FDMExec.GetTranslation()->GetNcg()(3) );
306   //
307   set_Accels_Pilot_Body( FDMExec.GetAuxiliary()->GetPilotAccel()(1),
308                          FDMExec.GetAuxiliary()->GetPilotAccel()(2),
309                          FDMExec.GetAuxiliary()->GetPilotAccel()(3) );
310   
311   //set_Accels_Pilot_Body_N( FDMExec.GetAuxiliary()->GetNpilot()(1),
312   //                         FDMExec.GetAuxiliary()->GetNpilot()(2),
313   //                         FDMExec.GetAuxiliary()->GetNpilot()(3) );
314   
315                            
316   
317   set_Nlf( FDMExec.GetAircraft()->GetNlf());                       
318   
319   
320    
321   // Velocities
322
323   set_Velocities_Local( FDMExec.GetPosition()->GetVn(),
324                         FDMExec.GetPosition()->GetVe(),
325                         FDMExec.GetPosition()->GetVd() );
326
327   set_Velocities_Wind_Body( FDMExec.GetTranslation()->GetUVW()(1),
328                             FDMExec.GetTranslation()->GetUVW()(2),
329                             FDMExec.GetTranslation()->GetUVW()(3)  );
330   
331   set_V_equiv_kts( FDMExec.GetAuxiliary()->GetVequivalentKTS() );
332
333   //set_V_calibrated( FDMExec.GetAuxiliary()->GetVcalibratedFPS() );
334
335   set_V_calibrated_kts( FDMExec.GetAuxiliary()->GetVcalibratedKTS() );
336   
337   set_V_ground_speed ( FDMExec.GetPosition()->GetVground() );
338
339   set_Omega_Body( FDMExec.GetState()->GetParameter(FG_ROLLRATE),
340                   FDMExec.GetState()->GetParameter(FG_PITCHRATE),
341                   FDMExec.GetState()->GetParameter(FG_YAWRATE) );
342
343   set_Euler_Rates( FDMExec.GetRotation()->GetEulerRates()(2),
344                    FDMExec.GetRotation()->GetEulerRates()(1),
345                    FDMExec.GetRotation()->GetEulerRates()(3));
346
347   // ***FIXME*** set_Geocentric_Rates( Latitude_dot, Longitude_dot, Radius_dot );
348
349   set_Mach_number( FDMExec.GetTranslation()->GetMach());
350
351   // Positions
352
353   double lat_geoc = FDMExec.GetPosition()->GetLatitude();
354   double lon = FDMExec.GetPosition()->GetLongitude();
355   double alt = FDMExec.GetPosition()->Geth();
356   double lat_geod, tmp_alt, sl_radius1, sl_radius2, tmp_lat_geoc;
357
358   sgGeocToGeod( lat_geoc, EQUATORIAL_RADIUS_M + alt * FEET_TO_METER,
359                 &lat_geod, &tmp_alt, &sl_radius1 );
360   sgGeodToGeoc( lat_geod, alt * FEET_TO_METER, &sl_radius2, &tmp_lat_geoc );
361
362   FG_LOG( FG_FLIGHT, FG_DEBUG, "lon = " << lon << " lat_geod = " << lat_geod
363           << " lat_geoc = " << lat_geoc
364           << " alt = " << alt << " tmp_alt = " << tmp_alt * METER_TO_FEET
365           << " sl_radius1 = " << sl_radius1 * METER_TO_FEET
366           << " sl_radius2 = " << sl_radius2 * METER_TO_FEET
367           << " Equator = " << EQUATORIAL_RADIUS_FT );
368
369   set_Geocentric_Position( lat_geoc, lon,
370                            sl_radius2 * METER_TO_FEET + alt );
371   set_Geodetic_Position( lat_geod, lon, alt );
372   set_Euler_Angles( FDMExec.GetRotation()->Getphi(),
373                     FDMExec.GetRotation()->Gettht(),
374                     FDMExec.GetRotation()->Getpsi() );
375
376   set_Alpha( FDMExec.GetTranslation()->Getalpha() );
377   set_Beta( FDMExec.GetTranslation()->Getbeta() );
378
379   set_Gamma_vert_rad( FDMExec.GetPosition()->GetGamma() );
380   // set_Gamma_horiz_rad( Gamma_horiz_rad );
381
382   /* **FIXME*** */ set_Sea_level_radius( sl_radius2 * METER_TO_FEET );
383   /* **FIXME*** */ set_Earth_position_angle( 0.0 );
384
385   // /* ***FIXME*** */ set_Runway_altitude( 0.0 );
386
387   set_sin_lat_geocentric( lat_geoc );
388   set_cos_lat_geocentric( lat_geoc );
389   set_sin_cos_longitude( lon );
390   set_sin_cos_latitude( lat_geod );
391   
392   set_Climb_Rate(FDMExec.GetPosition()->Gethdot());
393
394   return 1;
395 }