]> git.mxchange.org Git - flightgear.git/blob - src/FDM/JSBSim.cxx
376afdfc28198a2653572fd0814cd0ba868cf731
[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/fg_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/FGTrimLong.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.GetAircraft()->LoadAircraft( aircraft_path.str(),
79                                        engine_path.str(),
80                                        current_options.get_aircraft() );
81
82   if (result) {
83     FG_LOG( FG_FLIGHT, FG_INFO, "  loaded aircraft" << current_options.get_aircraft() );
84   } else {
85     FG_LOG( FG_FLIGHT, FG_INFO, "  aircraft" << current_options.get_aircraft()
86                                 << " does not exist");
87     return 0;
88   }
89
90   FDMExec.GetAtmosphere()->UseInternal();
91
92   FG_LOG( FG_FLIGHT, FG_INFO, "  Initializing JSBSim with:" );
93
94   FGInitialCondition *fgic = new FGInitialCondition(&FDMExec);
95   fgic->SetAltitudeFtIC(get_Altitude());
96   if((current_options.get_mach() < 0) && (current_options.get_vc() < 0 )) {
97     fgic->SetUBodyFpsIC(current_options.get_uBody());
98     fgic->SetVBodyFpsIC(current_options.get_vBody());
99     fgic->SetWBodyFpsIC(current_options.get_wBody());
100     FG_LOG(FG_FLIGHT,FG_INFO, "  u,v,w= " << current_options.get_uBody()
101            << ", " << current_options.get_vBody()
102            << ", " << current_options.get_wBody());
103   } else if (current_options.get_vc() < 0) {
104     fgic->SetMachIC(current_options.get_mach());
105     FG_LOG(FG_FLIGHT,FG_INFO, "  mach: " << current_options.get_mach() );
106   } else {
107     fgic->SetVcalibratedKtsIC(current_options.get_vc());
108     FG_LOG(FG_FLIGHT,FG_INFO, "  vc: " << current_options.get_vc() );
109     //this should cover the case in which no speed switches are used
110     //current_options.get_vc() will return zero by default
111   }
112
113
114   fgic->SetRollAngleRadIC(get_Phi());
115   fgic->SetPitchAngleRadIC(get_Theta());
116   fgic->SetHeadingRadIC(get_Psi());
117 //  fgic->SetLatitudeRadIC(get_Latitude());
118   fgic->SetLatitudeRadIC(get_Lat_geocentric());
119   fgic->SetLongitudeRadIC(get_Longitude());
120
121   FDMExec.GetPosition()->SetRunwayRadius(scenery.cur_radius*METER_TO_FEET);
122   FDMExec.GetPosition()->SetSeaLevelRadius(get_Sea_level_radius());
123
124   FG_LOG( FG_FLIGHT, FG_INFO, "  phi: " <<  get_Phi());
125   FG_LOG( FG_FLIGHT, FG_INFO, "  theta: " <<  get_Theta() );
126   FG_LOG( FG_FLIGHT, FG_INFO, "  psi: " <<  get_Psi() );
127   FG_LOG( FG_FLIGHT, FG_INFO, "  lat: " <<  get_Latitude() );
128   FG_LOG( FG_FLIGHT, FG_INFO, "  lon: " <<  get_Longitude() );
129   FG_LOG( FG_FLIGHT, FG_INFO, "  alt: " <<  get_Altitude() );
130
131   //must check > 0, != 0 will give bad result if --notrim set
132   if(current_options.get_trim_mode() > 0) {
133     FDMExec.RunIC(fgic);
134     FG_LOG( FG_FLIGHT, FG_INFO, "  Starting trim..." );
135     FGTrimLong *fgtrim=new FGTrimLong(&FDMExec,fgic);
136     fgtrim->DoTrim();
137     fgtrim->Report();
138     fgtrim->TrimStats();
139     fgtrim->ReportState();
140
141     controls.set_elevator_trim(FDMExec.GetFCS()->GetPitchTrimCmd());
142     controls.set_throttle(FGControls::ALL_ENGINES,FDMExec.GetFCS()->GetThrottleCmd(0)/100);
143     //the trimming routine only knows how to get 1 value for throttle
144
145     
146     delete fgtrim;
147     FG_LOG( FG_FLIGHT, FG_INFO, "  Trim complete." );
148   } else {
149     FG_LOG( FG_FLIGHT, FG_INFO, "  Initializing without trim" );
150     FDMExec.GetState()->Initialize(fgic);
151
152   }
153
154   delete fgic;
155
156   FG_LOG( FG_FLIGHT, FG_INFO, "  loaded initial conditions" );
157
158   FG_LOG( FG_FLIGHT, FG_INFO, "  set dt" );
159
160   FG_LOG( FG_FLIGHT, FG_INFO, "Finished initializing JSBSim" );
161
162   copy_from_JSBsim();
163   
164   
165   return 1;
166 }
167
168 /******************************************************************************/
169
170 // Run an iteration of the EOM (equations of motion)
171
172 int FGJSBsim::update( int multiloop ) {
173   double save_alt = 0.0;
174   double time_step = (1.0 / current_options.get_model_hz()) * multiloop;
175   double start_elev = get_Altitude();
176
177   // lets try to avoid really screwing up the JSBsim model
178   if ( get_Altitude() < -9000 ) {
179     save_alt = get_Altitude();
180     set_Altitude( 0.0 );
181   }
182
183   // copy control positions into the JSBsim structure
184
185   FDMExec.GetFCS()->SetDaCmd( controls.get_aileron());
186   FDMExec.GetFCS()->SetDeCmd( controls.get_elevator());
187   FDMExec.GetFCS()->SetPitchTrimCmd(controls.get_elevator_trim());
188   FDMExec.GetFCS()->SetDrCmd( controls.get_rudder());
189   FDMExec.GetFCS()->SetDfCmd( controls.get_flaps() );
190   FDMExec.GetFCS()->SetDsbCmd( 0.0 ); //speedbrakes
191   FDMExec.GetFCS()->SetDspCmd( 0.0 ); //spoilers
192   FDMExec.GetFCS()->SetThrottleCmd( FGControls::ALL_ENGINES,
193                                     controls.get_throttle( 0 ) * 100.0 );
194
195   // FCS->SetBrake( controls.get_brake( 0 ) );
196
197   // Inform JSBsim of the local terrain altitude; uncommented 5/3/00
198   //  FDMExec.GetPosition()->SetRunwayElevation(get_Runway_altitude()); // seems to work
199   FDMExec.GetPosition()->SetRunwayRadius(scenery.cur_radius*METER_TO_FEET);
200   FDMExec.GetPosition()->SetSeaLevelRadius(get_Sea_level_radius());
201
202   FDMExec.GetAtmosphere()->SetExTemperature(get_Static_temperature());
203   FDMExec.GetAtmosphere()->SetExPressure(get_Static_pressure());
204   FDMExec.GetAtmosphere()->SetExDensity(get_Density());
205   FDMExec.GetAtmosphere()->SetWindNED(get_V_north_airmass(),
206                                       get_V_east_airmass(),
207                                       get_V_down_airmass());
208
209   for ( int i = 0; i < multiloop; i++ ) {
210     FDMExec.Run();
211   }
212
213   // printf("%d FG_Altitude = %.2f\n", i, FG_Altitude * 0.3048);
214   // printf("%d Altitude = %.2f\n", i, Altitude * 0.3048);
215
216   // translate JSBsim back to FG structure so that the
217   // autopilot (and the rest of the sim can use the updated values
218
219   copy_from_JSBsim();
220
221   // but lets restore our original bogus altitude when we are done
222
223   if ( save_alt < -9000.0 ) {
224     set_Altitude( save_alt );
225   }
226
227   double end_elev = get_Altitude();
228   //if ( time_step > 0.0 ) {
229     // feet per second
230   //  set_Climb_Rate( (end_elev - start_elev) / time_step );
231   //}
232
233   return 1;
234 }
235
236 /******************************************************************************/
237
238 // Convert from the FGInterface struct to the JSBsim generic_ struct
239
240 int FGJSBsim::copy_to_JSBsim() {
241   return 1;
242 }
243
244 /******************************************************************************/
245
246 // Convert from the JSBsim generic_ struct to the FGInterface struct
247
248 int FGJSBsim::copy_from_JSBsim() {
249
250   set_Inertias( FDMExec.GetAircraft()->GetMass(),
251                 FDMExec.GetAircraft()->GetIxx(),
252                 FDMExec.GetAircraft()->GetIyy(),
253                 FDMExec.GetAircraft()->GetIzz(),
254                 FDMExec.GetAircraft()->GetIxz() );
255   
256   set_CG_Position ( FDMExec.GetAircraft()->GetXYZcg()(1),
257                     FDMExec.GetAircraft()->GetXYZcg()(2),
258                     FDMExec.GetAircraft()->GetXYZcg()(3) );
259   
260   
261   set_Accels_Local( FDMExec.GetPosition()->GetVelDot()(1),
262                     FDMExec.GetPosition()->GetVelDot()(2),
263                     FDMExec.GetPosition()->GetVelDot()(3) );
264                     
265   set_Accels_Body ( FDMExec.GetTranslation()->GetUVWdot()(1),
266                     FDMExec.GetTranslation()->GetUVWdot()(2),
267                     FDMExec.GetTranslation()->GetUVWdot()(3) );
268   
269   set_Accels_CG_Body ( FDMExec.GetTranslation()->GetUVWdot()(1),
270                        FDMExec.GetTranslation()->GetUVWdot()(2),
271                        FDMExec.GetTranslation()->GetUVWdot()(3) );
272   
273   //set_Accels_CG_Body_N ( FDMExec.GetTranslation()->GetNcg()(1),
274   //                       FDMExec.GetTranslation()->GetNcg()(2),
275   //                       FDMExec.GetTranslation()->GetNcg()(3) );
276   //
277   
278   set_Accels_Pilot_Body( FDMExec.GetAuxiliary()->GetPilotAccel()(1),
279                          FDMExec.GetAuxiliary()->GetPilotAccel()(2),
280                          FDMExec.GetAuxiliary()->GetPilotAccel()(3) );
281   
282   //set_Accels_Pilot_Body_N( FDMExec.GetAuxiliary()->GetNpilot()(1),
283   //                         FDMExec.GetAuxiliary()->GetNpilot()(2),
284   //                         FDMExec.GetAuxiliary()->GetNpilot()(3) );
285   
286                            
287   
288   set_Nlf( FDMExec.GetAircraft()->GetNlf());                       
289   
290   
291    
292   // Velocities
293
294   set_Velocities_Local( FDMExec.GetPosition()->GetVn(),
295                         FDMExec.GetPosition()->GetVe(),
296                         FDMExec.GetPosition()->GetVd() );
297
298   set_Velocities_Wind_Body( FDMExec.GetTranslation()->GetUVW()(1),
299                             FDMExec.GetTranslation()->GetUVW()(2),
300                             FDMExec.GetTranslation()->GetUVW()(3)  );
301   
302   set_V_equiv_kts( FDMExec.GetAuxiliary()->GetVequivalentKTS() );
303
304   //set_V_calibrated( FDMExec.GetAuxiliary()->GetVcalibratedFPS() );
305
306   set_V_calibrated_kts( FDMExec.GetAuxiliary()->GetVcalibratedKTS() );
307   
308   set_V_ground_speed ( FDMExec.GetPosition()->GetVground() );
309
310   set_Omega_Body( FDMExec.GetState()->GetParameter(FG_ROLLRATE),
311                   FDMExec.GetState()->GetParameter(FG_PITCHRATE),
312                   FDMExec.GetState()->GetParameter(FG_YAWRATE) );
313
314   set_Euler_Rates( FDMExec.GetRotation()->GetEulerRates()(1),
315                    FDMExec.GetRotation()->GetEulerRates()(2),
316                    FDMExec.GetRotation()->GetEulerRates()(3) );
317
318   set_Geocentric_Rates( FDMExec.GetPosition()->GetLatitudeDot(),
319                         FDMExec.GetPosition()->GetLongitudeDot(),
320                         FDMExec.GetPosition()->Gethdot() );
321
322   set_Mach_number( FDMExec.GetTranslation()->GetMach());
323
324   // Positions
325
326   double lat_geoc = FDMExec.GetPosition()->GetLatitude();
327   double lon = FDMExec.GetPosition()->GetLongitude();
328   double alt = FDMExec.GetPosition()->Geth();
329   double lat_geod, tmp_alt, sl_radius1, sl_radius2, tmp_lat_geoc;
330
331   fgGeocToGeod( lat_geoc, EQUATORIAL_RADIUS_M + alt * FEET_TO_METER,
332                 &lat_geod, &tmp_alt, &sl_radius1 );
333   fgGeodToGeoc( lat_geod, alt * FEET_TO_METER, &sl_radius2, &tmp_lat_geoc );
334
335   FG_LOG( FG_FLIGHT, FG_DEBUG, "lon = " << lon << " lat_geod = " << lat_geod
336           << " lat_geoc = " << lat_geoc
337           << " alt = " << alt << " tmp_alt = " << tmp_alt * METER_TO_FEET
338           << " sl_radius1 = " << sl_radius1 * METER_TO_FEET
339           << " sl_radius2 = " << sl_radius2 * METER_TO_FEET
340           << " Equator = " << EQUATORIAL_RADIUS_FT );
341
342   set_Geocentric_Position( lat_geoc, lon,
343                            sl_radius2 * METER_TO_FEET + alt );
344   set_Geodetic_Position( lat_geod, lon, alt );
345   set_Euler_Angles( FDMExec.GetRotation()->Getphi(),
346                     FDMExec.GetRotation()->Gettht(),
347                     FDMExec.GetRotation()->Getpsi() );
348                     
349   for(int i=0; i<3; i++ ) {
350     for (int j=0; j<3; j++ ) {
351       set_T_Local_to_Body(i,j,FDMExec.GetState()->GetTl2b()(i,j));
352     }
353   }     
354
355   set_Alpha( FDMExec.GetTranslation()->Getalpha() );
356   set_Beta( FDMExec.GetTranslation()->Getbeta() );
357   
358   set_Cos_phi( FDMExec.GetRotation()->GetCosphi() );
359   //set_Sin_phi ( FDMExec.GetRotation()->GetSinpphi() );
360   
361   set_Cos_theta( FDMExec.GetRotation()->GetCostht() );
362   //set_Sin_theta ( FDMExec.GetRotation()->GetSintht() );
363   
364   //set_Cos_psi( FDMExec.GetRotation()->GetCospsi() );
365   //set_Sin_psi ( FDMExec.GetRotation()->GetSinpsi() );
366   
367   set_Gamma_vert_rad( FDMExec.GetPosition()->GetGamma() );
368   // set_Gamma_horiz_rad( Gamma_horiz_rad );
369
370
371   set_Density( FDMExec.GetAtmosphere()->GetDensity() );
372   set_Static_pressure( FDMExec.GetAtmosphere()->GetPressure() );
373   set_Static_temperature ( FDMExec.GetAtmosphere()->GetTemperature() );
374   
375   set_Earth_position_angle( FDMExec.GetAuxiliary()->GetEarthPositionAngle() );
376   
377   /* **FIXME*** */ set_Sea_level_radius( sl_radius2 * METER_TO_FEET );
378   /* **FIXME*** */ set_Earth_position_angle( 0.0 );
379
380   // /* ***FIXME*** */ set_Runway_altitude( 0.0 );
381
382   set_sin_lat_geocentric( lat_geoc );
383   set_cos_lat_geocentric( lat_geoc );
384   set_sin_cos_longitude( lon );
385   set_sin_cos_latitude( lat_geod );
386   
387   set_Climb_Rate(FDMExec.GetPosition()->Gethdot());
388
389   return 1;
390 }