Paparazzi UAS  v5.10_stable-5-g83a0da5-dirty
Paparazzi is a free software Unmanned Aircraft System.
 All Data Structures Namespaces Files Functions Variables Typedefs Enumerations Enumerator Macros Modules Pages
nps_fdm_jsbsim.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2009 Antoine Drouin <poinix@gmail.com>
3  *
4  * This file is part of paparazzi.
5  *
6  * paparazzi is free software; you can redistribute it and/or modify
7  * it under the terms of the GNU General Public License as published by
8  * the Free Software Foundation; either version 2, or (at your option)
9  * any later version.
10  *
11  * paparazzi is distributed in the hope that it will be useful,
12  * but WITHOUT ANY WARRANTY; without even the implied warranty of
13  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
14  * GNU General Public License for more details.
15  *
16  * You should have received a copy of the GNU General Public License
17  * along with paparazzi; see the file COPYING. If not, write to
18  * the Free Software Foundation, 59 Temple Place - Suite 330,
19  * Boston, MA 02111-1307, USA.
20  */
21 
29 #include <iostream>
30 #include <stdlib.h>
31 #include <stdio.h>
32 
33 // ignore stupid warnings in JSBSim
34 #pragma GCC diagnostic push
35 #pragma GCC diagnostic ignored "-Wunused-parameter"
36 
37 #include <FGFDMExec.h>
38 #include <FGJSBBase.h>
39 #include <initialization/FGInitialCondition.h>
40 #include <models/FGPropulsion.h>
41 #include <models/FGGroundReactions.h>
42 #include <models/FGAccelerations.h>
43 #include <models/FGAuxiliary.h>
44 #include <models/FGAtmosphere.h>
45 #include <models/FGFCS.h>
46 #include <models/atmosphere/FGWinds.h>
47 
48 // Thrusters
49 #include <models/propulsion/FGThruster.h>
50 #include <models/propulsion/FGPropeller.h>
51 
52 // end ignore unused param warnings in JSBSim
53 #pragma GCC diagnostic pop
54 
55 
56 #include "nps_fdm.h"
57 #include "math/pprz_geodetic.h"
60 #include "math/pprz_algebra.h"
62 
64 
65 #include "generated/airframe.h"
66 #include "generated/flight_plan.h"
67 
69 #define MetersOfFeet(_f) ((_f)/3.2808399)
70 #define FeetOfMeters(_m) ((_m)*3.2808399)
71 
72 #define PascalOfPsf(_p) ((_p) * 47.8802588889)
73 #define CelsiusOfRankine(_r) (((_r) - 491.67) / 1.8)
74 
78 #ifndef NPS_JSBSIM_MODEL
79 #define NPS_JSBSIM_MODEL AIRFRAME_NAME
80 #endif
81 
82 #ifdef NPS_INITIAL_CONDITITONS
83 #warning NPS_INITIAL_CONDITITONS was replaced by NPS_JSBSIM_INIT!
84 #warning Defaulting to flight plan location.
85 #endif
86 
90 #ifndef NPS_JSBSIM_PITCH_TRIM
91 #define NPS_JSBSIM_PITCH_TRIM 0.0
92 #endif
93 
94 #ifndef NPS_JSBSIM_ROLL_TRIM
95 #define NPS_JSBSIM_ROLL_TRIM 0.0
96 #endif
97 
98 #ifndef NPS_JSBSIM_YAW_TRIM
99 #define NPS_JSBSIM_YAW_TRIM 0.0
100 #endif
101 
105 #define DEG2RAD 0.017
106 
107 #ifndef NPS_JSBSIM_ELEVATOR_MAX_RAD
108 #define NPS_JSBSIM_ELEVATOR_MAX_RAD (20.0*DEG2RAD)
109 #endif
110 
111 #ifndef NPS_JSBSIM_AILERON_MAX_RAD
112 #define NPS_JSBSIM_AILERON_MAX_RAD (20.0*DEG2RAD)
113 #endif
114 
115 #ifndef NPS_JSBSIM_RUDDER_MAX_RAD
116 #define NPS_JSBSIM_RUDDER_MAX_RAD (20.0*DEG2RAD)
117 #endif
118 
119 #ifndef NPS_JSBSIM_FLAP_MAX_RAD
120 #define NPS_JSBSIM_FLAP_MAX_RAD (20.0*DEG2RAD)
121 #endif
122 
126 #define MIN_DT (1.0/10240.0)
127 
128 using namespace JSBSim;
129 using namespace std;
130 
131 static void feed_jsbsim(double *commands, int commands_nb);
132 static void feed_jsbsim(double throttle, double aileron, double elevator, double rudder);
133 static void fetch_state(void);
134 static int check_for_nan(void);
135 
136 static void jsbsimvec_to_vec(DoubleVect3 *fdm_vector, const FGColumnVector3 *jsb_vector);
137 static void jsbsimloc_to_loc(EcefCoor_d *fdm_location, const FGLocation *jsb_location);
138 static void jsbsimquat_to_quat(DoubleQuat *fdm_quat, const FGQuaternion *jsb_quat);
139 static void jsbsimvec_to_rate(DoubleRates *fdm_rate, const FGColumnVector3 *jsb_vector);
140 static void llh_from_jsbsim(LlaCoor_d *fdm_lla, FGPropagate *propagate);
141 static void lla_from_jsbsim_geodetic(LlaCoor_d *fdm_lla, FGPropagate *propagate);
142 static void lla_from_jsbsim_geocentric(LlaCoor_d *fdm_lla, FGPropagate *propagate);
143 
144 static void init_jsbsim(double dt);
145 static void init_ltp(void);
146 
148 struct NpsFdm fdm;
149 
151 static FGFDMExec *FDMExec;
152 
153 static struct LtpDef_d ltpdef;
154 
155 // Offset between ecef in geodetic and geocentric coordinates
156 static struct EcefCoor_d offset;
157 
160 
162 double min_dt;
163 
164 void nps_fdm_init(double dt)
165 {
166 
167  fdm.init_dt = dt;
168  fdm.curr_dt = dt;
169  //Sets up the high fidelity timestep as a multiple of the normal timestep
170  for (min_dt = (1.0 / dt); min_dt < (1 / MIN_DT); min_dt += (1 / dt)) {}
171  min_dt = (1 / min_dt);
172 
173  fdm.nan_count = 0;
174 
175  VECT3_ASSIGN(offset, 0., 0., 0.);
176 
177  init_jsbsim(dt);
178 
179  FDMExec->RunIC();
180 
181  init_ltp();
182 
183 #if DEBUG_NPS_JSBSIM
184  printf("fdm.time,fdm.body_ecef_accel.x,fdm.body_ecef_accel.y,fdm.body_ecef_accel.z,fdm.ltp_ecef_accel.x,fdm.ltp_ecef_accel.y,fdm.ltp_ecef_accel.z,fdm.ecef_ecef_accel.x,fdm.ecef_ecef_accel.y,fdm.ecef_ecef_accel.z,fdm.ltpprz_ecef_accel.z,fdm.ltpprz_ecef_accel.y,fdm.ltpprz_ecef_accel.z,fdm.agl\n");
185 #endif
186 
187  fetch_state();
188 
189 }
190 
191 void nps_fdm_run_step(bool launch __attribute__((unused)), double *commands, int commands_nb)
192 {
193 
194 #ifdef NPS_JSBSIM_LAUNCHSPEED
195  static bool already_launched = FALSE;
196 
197  if (launch && !already_launched) {
198  printf("Launching with speed of %.1f m/s!\n", (float)NPS_JSBSIM_LAUNCHSPEED);
199  FDMExec->GetIC()->SetUBodyFpsIC(FeetOfMeters(NPS_JSBSIM_LAUNCHSPEED));
200  FDMExec->RunIC();
201  already_launched = TRUE;
202  }
203 #endif
204 
205  feed_jsbsim(commands, commands_nb);
206 
207  /* To deal with ground interaction issues, we decrease the time
208  step as the vehicle is close to the ground. This is done predictively
209  to ensure no weird accelerations or oscillations. From tests with a bouncing
210  ball model in JSBSim, it seems that 10k steps per second is reasonable to capture
211  all the dynamics. Higher might be a bit more stable, but really starting to push
212  the simulation CPU requirements, especially for more complex models.
213  - at init: get the largest radius from CG to any contact point (landing gear)
214  - if descending...
215  - find current number of timesteps to impact
216  - if impact imminent, calculate a new timestep to use (with limit)
217  - if ascending...
218  - change timestep back to init value
219  - run sim for as many steps as needed to reach init_dt amount of time
220 
221  Of course, could probably be improved...
222  */
223  // If the vehicle has a downwards velocity
224  if (fdm.ltp_ecef_vel.z > 0) {
225  // Get the current number of timesteps until impact at current velocity
226  double numDT_to_impact = (fdm.agl - vehicle_radius_max) / (fdm.curr_dt * fdm.ltp_ecef_vel.z);
227  // If impact imminent within next timestep, use high sim rate
228  if (numDT_to_impact <= 1.0) {
229  fdm.curr_dt = min_dt;
230  }
231  }
232  // If the vehicle is moving upwards and out of the ground, reset timestep
233  else if ((fdm.ltp_ecef_vel.z <= 0) && ((fdm.agl + vehicle_radius_max) > 0)) {
235  }
236 
237  // Calculate the number of sim steps for correct amount of time elapsed
238  int num_steps = int(fdm.init_dt / fdm.curr_dt);
239 
240  // Set the timestep then run sim
241  FDMExec->Setdt(fdm.curr_dt);
242  int i;
243  for (i = 0; i < num_steps; i++) {
244  FDMExec->Run();
245  }
246 
247  fetch_state();
248 
249  /* Check the current state to make sure it is valid (no NaNs) */
250  if (check_for_nan()) {
251  printf("Error: FDM simulation encountered a total of %i NaN values at simulation time %f.\n", fdm.nan_count, fdm.time);
252  printf("It is likely the simulation diverged and gave non-physical results. If you did\n");
253  printf("not crash, check your model and/or initial conditions. Exiting with status 1.\n");
254  exit(1);
255  }
256 
257 }
258 
259 void nps_fdm_set_wind(double speed, double dir)
260 {
261  FGWinds *Winds = FDMExec->GetWinds();
262  Winds->SetWindspeed(FeetOfMeters(speed));
263  Winds->SetWindPsi(dir);
264 }
265 
266 void nps_fdm_set_wind_ned(double wind_north, double wind_east, double wind_down)
267 {
268  FGWinds *Winds = FDMExec->GetWinds();
269  Winds->SetWindNED(FeetOfMeters(wind_north), FeetOfMeters(wind_east),
270  FeetOfMeters(wind_down));
271 }
272 
273 void nps_fdm_set_turbulence(double wind_speed, int turbulence_severity)
274 {
275  FGWinds *Winds = FDMExec->GetWinds();
276  /* wind speed used for turbulence */
277  Winds->SetWindspeed20ft(FeetOfMeters(wind_speed) / 2);
278  Winds->SetProbabilityOfExceedence(turbulence_severity);
279 }
280 
281 void nps_fdm_set_temperature(double temp, double h)
282 {
283  FDMExec->GetAtmosphere()->SetTemperature(temp, h, FGAtmosphere::eCelsius);
284 }
285 
292 static void feed_jsbsim(double *commands, int commands_nb)
293 {
294 #ifdef NPS_ACTUATOR_NAMES
295  char buf[64];
296  const char *names[] = NPS_ACTUATOR_NAMES;
297  string property;
298 
299  int i;
300  for (i = 0; i < commands_nb; i++) {
301  sprintf(buf, "fcs/%s", names[i]);
302  property = string(buf);
303  FDMExec->GetPropertyManager()->GetNode(property)->SetDouble("", commands[i]);
304  }
305 #else
306  if (commands_nb != 4) {
307  cerr << "commands_nb must be 4!" << endl;
308  exit(-1);
309  }
310  /* call version that directly feeds throttle, aileron, elevator, rudder */
311  feed_jsbsim(commands[COMMAND_THROTTLE], commands[COMMAND_ROLL], commands[COMMAND_PITCH], commands[3]);
312 #endif
313 }
314 
315 static void feed_jsbsim(double throttle, double aileron, double elevator, double rudder)
316 {
317  FGFCS *FCS = FDMExec->GetFCS();
318  FGPropulsion *FProp = FDMExec->GetPropulsion();
319 
320  // Set trims
321  FCS->SetPitchTrimCmd(NPS_JSBSIM_PITCH_TRIM);
322  FCS->SetRollTrimCmd(NPS_JSBSIM_ROLL_TRIM);
323  FCS->SetYawTrimCmd(NPS_JSBSIM_YAW_TRIM);
324 
325  // Set commands
326  FCS->SetDaCmd(aileron);
327  FCS->SetDeCmd(elevator);
328  FCS->SetDrCmd(rudder);
329 
330  for (unsigned int i = 0; i < FDMExec->GetPropulsion()->GetNumEngines(); i++) {
331  FCS->SetThrottleCmd(i, throttle);
332 
333  if (throttle > 0.01) {
334  FProp->SetStarter(1);
335  } else {
336  FProp->SetStarter(0);
337  }
338  }
339 }
340 
341 
345 static void fetch_state(void)
346 {
347 
348  fdm.time = FDMExec->GetPropertyManager()->GetNode("simulation/sim-time-sec")->getDoubleValue();
349 
350 #if DEBUG_NPS_JSBSIM
351  printf("%f,", fdm.time);
352 #endif
353 
354  FGPropagate *propagate = FDMExec->GetPropagate();
355  FGAccelerations *accelerations = FDMExec->GetAccelerations();
356 
357  fdm.on_ground = FDMExec->GetGroundReactions()->GetWOW();
358 
359  /*
360  * position
361  */
362  jsbsimloc_to_loc(&fdm.ecef_pos, &propagate->GetLocation());
363  fdm.hmsl = propagate->GetAltitudeASLmeters();
364 
365  /*
366  * linear speed and accelerations
367  */
368 
369  /* in body frame */
370  jsbsimvec_to_vec(&fdm.body_ecef_vel, &propagate->GetUVW());
371  jsbsimvec_to_vec(&fdm.body_ecef_accel, &accelerations->GetUVWdot());
372  jsbsimvec_to_vec(&fdm.body_inertial_accel, &accelerations->GetUVWidot());
373  jsbsimvec_to_vec(&fdm.body_accel, &accelerations->GetBodyAccel());
374 
375 #if DEBUG_NPS_JSBSIM
376  printf("%f,%f,%f,", fdm.body_ecef_accel.x, fdm.body_ecef_accel.y, fdm.body_ecef_accel.z);
377 #endif
378 
379  /* in LTP frame */
380  jsbsimvec_to_vec((DoubleVect3 *)&fdm.ltp_ecef_vel, &propagate->GetVel());
381  const FGColumnVector3 &fg_ltp_ecef_accel = propagate->GetTb2l() * accelerations->GetUVWdot();
382  jsbsimvec_to_vec((DoubleVect3 *)&fdm.ltp_ecef_accel, &fg_ltp_ecef_accel);
383 
384 #if DEBUG_NPS_JSBSIM
385  printf("%f,%f,%f,", fdm.ltp_ecef_accel.x, fdm.ltp_ecef_accel.y, fdm.ltp_ecef_accel.z);
386 #endif
387 
388  /* in ECEF frame */
389  const FGColumnVector3 &fg_ecef_ecef_vel = propagate->GetECEFVelocity();
390  jsbsimvec_to_vec((DoubleVect3 *)&fdm.ecef_ecef_vel, &fg_ecef_ecef_vel);
391 
392  const FGColumnVector3 &fg_ecef_ecef_accel = propagate->GetTb2ec() * accelerations->GetUVWdot();
393  jsbsimvec_to_vec((DoubleVect3 *)&fdm.ecef_ecef_accel, &fg_ecef_ecef_accel);
394 
395 #if DEBUG_NPS_JSBSIM
396  printf("%f,%f,%f,", fdm.ecef_ecef_accel.x, fdm.ecef_ecef_accel.y, fdm.ecef_ecef_accel.z);
397 #endif
398 
399  /* in LTP pprz */
403 
404 #if DEBUG_NPS_JSBSIM
406 #endif
407 
408  /* llh */
409  llh_from_jsbsim(&fdm.lla_pos, propagate);
410 
411  //for debug
415  fdm.agl = MetersOfFeet(propagate->GetDistanceAGL());
416 
417 #if DEBUG_NPS_JSBSIM
418  printf("%f\n", fdm.agl);
419 #endif
420 
421  /*
422  * attitude
423  */
424  const FGQuaternion jsb_quat = propagate->GetQuaternion();
426  /* convert to eulers */
428  /* the "false" pprz lpt */
429  /* FIXME: use jsbsim ltp for now */
432 
433  /*
434  * rotational speed and accelerations
435  */
436  jsbsimvec_to_rate(&fdm.body_ecef_rotvel, &propagate->GetPQR());
437  jsbsimvec_to_rate(&fdm.body_ecef_rotaccel, &accelerations->GetPQRdot());
438 
439  jsbsimvec_to_rate(&fdm.body_inertial_rotvel, &propagate->GetPQRi());
440  jsbsimvec_to_rate(&fdm.body_inertial_rotaccel, &accelerations->GetPQRidot());
441 
442 
443  /*
444  * wind
445  */
446  const FGColumnVector3 &fg_wind_ned = FDMExec->GetWinds()->GetTotalWindNED();
447  jsbsimvec_to_vec(&fdm.wind, &fg_wind_ned);
448 
449  /*
450  * Equivalent Airspeed, atmospheric pressure and temperature.
451  */
452  fdm.airspeed = MetersOfFeet(FDMExec->GetAuxiliary()->GetVequivalentFPS());
453  fdm.pressure = PascalOfPsf(FDMExec->GetAtmosphere()->GetPressure());
454  fdm.pressure_sl = PascalOfPsf(FDMExec->GetAtmosphere()->GetPressureSL());
455  fdm.total_pressure = PascalOfPsf(FDMExec->GetAuxiliary()->GetTotalPressure());
456  fdm.dynamic_pressure = PascalOfPsf(FDMExec->GetAuxiliary()->Getqbar());
457  fdm.temperature = CelsiusOfRankine(FDMExec->GetAtmosphere()->GetTemperature());
458 
459  /*
460  * Control surface positions
461  *
462  */
463  fdm.rudder = (FDMExec->GetPropertyManager()->GetNode("fcs/rudder-pos-rad")->getDoubleValue()) /
465  fdm.left_aileron = (-1 * FDMExec->GetPropertyManager()->GetNode("fcs/left-aileron-pos-rad")->getDoubleValue()) /
467  fdm.right_aileron = (FDMExec->GetPropertyManager()->GetNode("fcs/right-aileron-pos-rad")->getDoubleValue()) /
469  fdm.elevator = (FDMExec->GetPropertyManager()->GetNode("fcs/elevator-pos-rad")->getDoubleValue()) /
471  fdm.flap = (FDMExec->GetPropertyManager()->GetNode("fcs/flap-pos-rad")->getDoubleValue()) / NPS_JSBSIM_FLAP_MAX_RAD;
472 
473  /*
474  * Propulsion
475  */
476  FGPropulsion *FGProp = FDMExec->GetPropulsion();
477  fdm.num_engines = FGProp->GetNumEngines();
478 
479  /*
480  * Note that JSBSim for some reason has very high momentum for the propeller
481  * (even when the moment of inertia of the propeller has the right value)
482  * As a result after switching the motor off
483  */
484  for (uint32_t k = 0; k < fdm.num_engines; k++) {
485  FGEngine *FGEng = FGProp->GetEngine(k);
486  FGThruster *FGThrst = FGEng->GetThruster();
487  fdm.eng_state[k] = FGEng->GetStarter();
488  fdm.rpm[k] = (float) FGThrst->GetRPM();
489  //printf("RPM: %f\n", fdm.rpm[k]);
490  //printf("STATE: %u\n", fdm.eng_state[k]);
491  }
492 }
493 
504 static void init_jsbsim(double dt)
505 {
506 
507  char buf[1024];
508  string rootdir;
509  string jsbsim_home = "/conf/simulator/jsbsim/";
510  string jsbsim_ic_name;
511 
512  char* pprz_home = getenv("PAPARAZZI_HOME");
513 
514  int cnt = -1;
515  if (strlen(pprz_home) < sizeof(buf)) {
516  cnt = snprintf(buf, strlen(pprz_home) + 1, "%s", pprz_home);
517  rootdir = string(buf) + jsbsim_home;
518  }
519 
520  // check the results
521  if (cnt < 0){
522  // Either pprz_home path too long for the buffer
523  // or writing the string was not successful.
524  cout << "PPRZ_HOME not set correctly, exiting..." << endl;
525  exit(-1);
526  }
527 
528  /* if jsbsim initial conditions are defined, use them
529  * otherwise use flightplan location
530  */
531 #ifdef NPS_JSBSIM_INIT
532  jsbsim_ic_name = NPS_JSBSIM_INIT;
533 #endif
534 
535  FDMExec = new FGFDMExec();
536 
537  FDMExec->Setsim_time(0.);
538  FDMExec->Setdt(dt);
539 
540  FDMExec->DisableOutput();
541  FDMExec->SetDebugLevel(0); // No DEBUG messages
542 
543  if (! FDMExec->LoadModel(rootdir + "aircraft",
544  rootdir + "engine",
545  rootdir + "systems",
547  false)) {
548 #ifdef DEBUG
549  cerr << " JSBSim could not be started" << endl << endl;
550 #endif
551  delete FDMExec;
552  exit(-1);
553  }
554 
555 #ifdef DEBUG
556  cerr << "NumEngines: " << FDMExec->GetPropulsion()->GetNumEngines() << endl;
557  cerr << "NumGearUnits: " << FDMExec->GetGroundReactions()->GetNumGearUnits() << endl;
558 #endif
559 
560  // LLA initial coordinates (geodetic lat, geoid alt)
561  struct LlaCoor_d lla0;
562 
563  FGInitialCondition *IC = FDMExec->GetIC();
564  if (!jsbsim_ic_name.empty()) {
565  if (! IC->Load(jsbsim_ic_name)) {
566 #ifdef DEBUG
567  cerr << "Initialization unsuccessful" << endl;
568 #endif
569  delete FDMExec;
570  exit(-1);
571  }
572 
573  llh_from_jsbsim(&lla0, FDMExec->GetPropagate());
574  cout << "JSBSim initial conditions loaded from " << jsbsim_ic_name << endl;
575  } else {
576  // FGInitialCondition::SetAltitudeASLFtIC
577  // requires this function to be called
578  // before itself
579  IC->SetVgroundFpsIC(0.);
580 
581  // Use flight plan initial conditions
582  // convert geodetic lat from flight plan to geocentric
583  double gd_lat = RadOfDeg(NAV_LAT0 / 1e7);
584  double gc_lat = gc_of_gd_lat_d(gd_lat, GROUND_ALT);
585  IC->SetLatitudeDegIC(DegOfRad(gc_lat));
586  IC->SetLongitudeDegIC(NAV_LON0 / 1e7);
587 
588  IC->SetWindNEDFpsIC(0.0, 0.0, 0.0);
589  IC->SetAltitudeASLFtIC(FeetOfMeters(GROUND_ALT + 2.0));
590  IC->SetTerrainElevationFtIC(FeetOfMeters(GROUND_ALT));
591  IC->SetPsiDegIC(QFU);
592  IC->SetVgroundFpsIC(0.);
593 
594  lla0.lon = RadOfDeg(NAV_LON0 / 1e7);
595  lla0.lat = gd_lat;
596  lla0.alt = (double)(NAV_ALT0 + NAV_MSL0) / 1000.0;
597  }
598 
599  // initial commands to zero
600  feed_jsbsim(0.0, 0.0, 0.0, 0.0);
601 
602  //loop JSBSim once w/o integrating
603  if (!FDMExec->RunIC()) {
604  cerr << "Initialization unsuccessful" << endl;
605  exit(-1);
606  }
607 
608  //initRunning for all engines
609  FDMExec->GetPropulsion()->InitRunning(-1);
610 
611 
612  // compute offset between geocentric and geodetic ecef
613  ecef_of_lla_d(&offset, &lla0);
614  struct EcefCoor_d ecef0 = {
615  MetersOfFeet(FDMExec->GetPropagate()->GetLocation().Entry(1)),
616  MetersOfFeet(FDMExec->GetPropagate()->GetLocation().Entry(2)),
617  MetersOfFeet(FDMExec->GetPropagate()->GetLocation().Entry(3))
618  };
619  VECT3_DIFF(offset, offset, ecef0);
620 
621  // calculate vehicle max radius in m
622  vehicle_radius_max = 0.01; // specify not 0.0 in case no gear
623  int num_gear = FDMExec->GetGroundReactions()->GetNumGearUnits();
624  int i;
625  for (i = 0; i < num_gear; i++) {
626  FGColumnVector3 gear_location = FDMExec->GetGroundReactions()->GetGearUnit(i)->GetBodyLocation();
627  double radius = MetersOfFeet(gear_location.Magnitude());
628  if (radius > vehicle_radius_max) { vehicle_radius_max = radius; }
629  }
630 
631 }
632 
637 static void init_ltp(void)
638 {
639 
640  FGPropagate *propagate = FDMExec->GetPropagate();
641 
642  jsbsimloc_to_loc(&fdm.ecef_pos, &propagate->GetLocation());
644 
645  fdm.ltp_g.x = 0.;
646  fdm.ltp_g.y = 0.;
647  fdm.ltp_g.z = 9.81;
648 
649 
650 #if !NPS_CALC_GEO_MAG && defined(AHRS_H_X)
651  PRINT_CONFIG_MSG("Using magnetic field as defined in airframe file (AHRS section).")
652  fdm.ltp_h.x = AHRS_H_X;
653  fdm.ltp_h.y = AHRS_H_Y;
654  fdm.ltp_h.z = AHRS_H_Z;
655 #elif !NPS_CALC_GEO_MAG && defined(INS_H_X)
656  PRINT_CONFIG_MSG("Using magnetic field as defined in airframe file (INS section).")
657  fdm.ltp_h.x = INS_H_X;
658  fdm.ltp_h.y = INS_H_Y;
659  fdm.ltp_h.z = INS_H_Z;
660 #else
661  PRINT_CONFIG_MSG("Using WMM2010 model to calculate magnetic field at simulated location.")
662  /* calculation of magnetic field according to WMM2010 model */
663  double gha[MAXCOEFF];
664 
665  /* Current date in decimal year, for example 2012.68 */
667  double sdate = 2014.5;
668 
669  llh_from_jsbsim(&fdm.lla_pos, propagate);
670  /* LLA Position in decimal degrees and altitude in km */
671  double latitude = DegOfRad(fdm.lla_pos.lat);
672  double longitude = DegOfRad(fdm.lla_pos.lon);
673  double alt = fdm.lla_pos.alt / 1e3;
674 
675  // Calculates additional coeffs
676  int32_t nmax = extrapsh(sdate, GEO_EPOCH, NMAX_1, NMAX_2, gha);
677  // Calculates absolute magnetic field
678  mag_calc(1, latitude, longitude, alt, nmax, gha,
679  &fdm.ltp_h.x, &fdm.ltp_h.y, &fdm.ltp_h.z,
682  printf("normalized magnetic field: %.4f %.4f %.4f\n", fdm.ltp_h.x, fdm.ltp_h.y, fdm.ltp_h.z);
683 #endif
684 
685 }
686 
695 static void jsbsimloc_to_loc(EcefCoor_d *fdm_location, const FGLocation *jsb_location)
696 {
697 
698  fdm_location->x = MetersOfFeet(jsb_location->Entry(1));
699  fdm_location->y = MetersOfFeet(jsb_location->Entry(2));
700  fdm_location->z = MetersOfFeet(jsb_location->Entry(3));
701 
702  VECT3_ADD(*fdm_location, offset);
703 }
704 
713 static void jsbsimvec_to_vec(DoubleVect3 *fdm_vector, const FGColumnVector3 *jsb_vector)
714 {
715 
716  fdm_vector->x = MetersOfFeet(jsb_vector->Entry(1));
717  fdm_vector->y = MetersOfFeet(jsb_vector->Entry(2));
718  fdm_vector->z = MetersOfFeet(jsb_vector->Entry(3));
719 
720 }
721 
728 static void jsbsimquat_to_quat(DoubleQuat *fdm_quat, const FGQuaternion *jsb_quat)
729 {
730 
731  fdm_quat->qi = jsb_quat->Entry(1);
732  fdm_quat->qx = jsb_quat->Entry(2);
733  fdm_quat->qy = jsb_quat->Entry(3);
734  fdm_quat->qz = jsb_quat->Entry(4);
735 
736 }
737 
744 static void jsbsimvec_to_rate(DoubleRates *fdm_rate, const FGColumnVector3 *jsb_vector)
745 {
746 
747  fdm_rate->p = jsb_vector->Entry(1);
748  fdm_rate->q = jsb_vector->Entry(2);
749  fdm_rate->r = jsb_vector->Entry(3);
750 
751 }
752 
761 void llh_from_jsbsim(LlaCoor_d *fdm_lla, FGPropagate *propagate)
762 {
763 
764  fdm_lla->lat = propagate->GetGeodLatitudeRad();
765  fdm_lla->lon = propagate->GetLongitude();
766  fdm_lla->alt = propagate->GetAltitudeASLmeters();
767  //printf("geodetic alt: %f\n", MetersOfFeet(propagate->GetGeodeticAltitude()));
768  //printf("ground alt: %f\n", MetersOfFeet(propagate->GetDistanceAGL()));
769  //printf("ASL alt: %f\n", propagate->GetAltitudeASLmeters());
770 
771 }
772 
781 void lla_from_jsbsim_geocentric(LlaCoor_d *fdm_lla, FGPropagate *propagate)
782 {
783 
784  fdm_lla->lat = propagate->GetLatitude();
785  fdm_lla->lon = propagate->GetLongitude();
786  fdm_lla->alt = MetersOfFeet(propagate->GetRadius());
787 
788 }
789 
798 void lla_from_jsbsim_geodetic(LlaCoor_d *fdm_lla, FGPropagate *propagate)
799 {
800 
801  fdm_lla->lat = propagate->GetGeodLatitudeRad();
802  fdm_lla->lon = propagate->GetLongitude();
803  fdm_lla->alt = MetersOfFeet(propagate->GetGeodeticAltitude());
804 
805 }
806 
807 #ifdef __APPLE__
808 /* Why isn't this there when we include math.h (on osx with clang)? */
810 static int isnan(double f) { return (f != f); }
811 #endif
812 
820 static int check_for_nan(void)
821 {
822  int orig_nan_count = fdm.nan_count;
823  /* Check all elements for nans */
824  if (isnan(fdm.ecef_pos.x)) { fdm.nan_count++; }
825  if (isnan(fdm.ecef_pos.y)) { fdm.nan_count++; }
826  if (isnan(fdm.ecef_pos.z)) { fdm.nan_count++; }
827  if (isnan(fdm.ltpprz_pos.x)) { fdm.nan_count++; }
828  if (isnan(fdm.ltpprz_pos.y)) { fdm.nan_count++; }
829  if (isnan(fdm.ltpprz_pos.z)) { fdm.nan_count++; }
830  if (isnan(fdm.lla_pos.lon)) { fdm.nan_count++; }
831  if (isnan(fdm.lla_pos.lat)) { fdm.nan_count++; }
832  if (isnan(fdm.lla_pos.alt)) { fdm.nan_count++; }
833  if (isnan(fdm.hmsl)) { fdm.nan_count++; }
834  // Skip debugging elements
835  if (isnan(fdm.ecef_ecef_vel.x)) { fdm.nan_count++; }
836  if (isnan(fdm.ecef_ecef_vel.y)) { fdm.nan_count++; }
837  if (isnan(fdm.ecef_ecef_vel.z)) { fdm.nan_count++; }
838  if (isnan(fdm.ecef_ecef_accel.x)) { fdm.nan_count++; }
839  if (isnan(fdm.ecef_ecef_accel.y)) { fdm.nan_count++; }
840  if (isnan(fdm.ecef_ecef_accel.z)) { fdm.nan_count++; }
841  if (isnan(fdm.body_ecef_vel.x)) { fdm.nan_count++; }
842  if (isnan(fdm.body_ecef_vel.y)) { fdm.nan_count++; }
843  if (isnan(fdm.body_ecef_vel.z)) { fdm.nan_count++; }
844  if (isnan(fdm.body_ecef_accel.x)) { fdm.nan_count++; }
845  if (isnan(fdm.body_ecef_accel.y)) { fdm.nan_count++; }
846  if (isnan(fdm.body_ecef_accel.z)) { fdm.nan_count++; }
847  if (isnan(fdm.ltp_ecef_vel.x)) { fdm.nan_count++; }
848  if (isnan(fdm.ltp_ecef_vel.y)) { fdm.nan_count++; }
849  if (isnan(fdm.ltp_ecef_vel.z)) { fdm.nan_count++; }
850  if (isnan(fdm.ltp_ecef_accel.x)) { fdm.nan_count++; }
851  if (isnan(fdm.ltp_ecef_accel.y)) { fdm.nan_count++; }
852  if (isnan(fdm.ltp_ecef_accel.z)) { fdm.nan_count++; }
853  if (isnan(fdm.ltpprz_ecef_vel.x)) { fdm.nan_count++; }
854  if (isnan(fdm.ltpprz_ecef_vel.y)) { fdm.nan_count++; }
855  if (isnan(fdm.ltpprz_ecef_vel.z)) { fdm.nan_count++; }
856  if (isnan(fdm.ltpprz_ecef_accel.x)) { fdm.nan_count++; }
857  if (isnan(fdm.ltpprz_ecef_accel.y)) { fdm.nan_count++; }
858  if (isnan(fdm.ltpprz_ecef_accel.z)) { fdm.nan_count++; }
859  if (isnan(fdm.ecef_to_body_quat.qi)) { fdm.nan_count++; }
860  if (isnan(fdm.ecef_to_body_quat.qx)) { fdm.nan_count++; }
861  if (isnan(fdm.ecef_to_body_quat.qy)) { fdm.nan_count++; }
862  if (isnan(fdm.ecef_to_body_quat.qz)) { fdm.nan_count++; }
863  if (isnan(fdm.ltp_to_body_quat.qi)) { fdm.nan_count++; }
864  if (isnan(fdm.ltp_to_body_quat.qx)) { fdm.nan_count++; }
865  if (isnan(fdm.ltp_to_body_quat.qy)) { fdm.nan_count++; }
866  if (isnan(fdm.ltp_to_body_quat.qz)) { fdm.nan_count++; }
867  if (isnan(fdm.ltp_to_body_eulers.phi)) { fdm.nan_count++; }
868  if (isnan(fdm.ltp_to_body_eulers.theta)) { fdm.nan_count++; }
869  if (isnan(fdm.ltp_to_body_eulers.psi)) { fdm.nan_count++; }
870  if (isnan(fdm.ltpprz_to_body_quat.qi)) { fdm.nan_count++; }
871  if (isnan(fdm.ltpprz_to_body_quat.qx)) { fdm.nan_count++; }
872  if (isnan(fdm.ltpprz_to_body_quat.qy)) { fdm.nan_count++; }
873  if (isnan(fdm.ltpprz_to_body_quat.qz)) { fdm.nan_count++; }
874  if (isnan(fdm.ltpprz_to_body_eulers.phi)) { fdm.nan_count++; }
875  if (isnan(fdm.ltpprz_to_body_eulers.theta)) { fdm.nan_count++; }
876  if (isnan(fdm.ltpprz_to_body_eulers.psi)) { fdm.nan_count++; }
877  if (isnan(fdm.body_ecef_rotvel.p)) { fdm.nan_count++; }
878  if (isnan(fdm.body_ecef_rotvel.q)) { fdm.nan_count++; }
879  if (isnan(fdm.body_ecef_rotvel.r)) { fdm.nan_count++; }
880  if (isnan(fdm.body_ecef_rotaccel.p)) { fdm.nan_count++; }
881  if (isnan(fdm.body_ecef_rotaccel.q)) { fdm.nan_count++; }
882  if (isnan(fdm.body_ecef_rotaccel.r)) { fdm.nan_count++; }
883  if (isnan(fdm.ltp_g.x)) { fdm.nan_count++; }
884  if (isnan(fdm.ltp_g.y)) { fdm.nan_count++; }
885  if (isnan(fdm.ltp_g.z)) { fdm.nan_count++; }
886  if (isnan(fdm.ltp_h.x)) { fdm.nan_count++; }
887  if (isnan(fdm.ltp_h.y)) { fdm.nan_count++; }
888  if (isnan(fdm.ltp_h.z)) { fdm.nan_count++; }
889 
890  return (fdm.nan_count - orig_nan_count);
891 }
#define NPS_JSBSIM_ROLL_TRIM
Roation quaternion.
double agl
Definition: nps_fdm.h:61
double z
in meters
#define NMAX_1
double total_pressure
total atmospheric pressure in Pascal
Definition: nps_fdm.h:111
uint32_t eng_state[FG_NET_FDM_MAX_ENGINES]
Definition: nps_fdm.h:125
WMM2015 Geomagnetic field model.
struct DoubleQuat ecef_to_body_quat
Definition: nps_fdm.h:90
#define MAXCOEFF
#define VECT3_ADD(_a, _b)
Definition: pprz_algebra.h:146
double time
Definition: nps_fdm.h:46
struct NedCoor_d ltpprz_ecef_accel
accel in ltppprz frame, wrt ECEF frame
Definition: nps_fdm.h:81
struct LlaCoor_d lla_pos_geoc
Definition: nps_fdm.h:60
double vehicle_radius_max
The largest distance between vehicle CG and contact point.
static struct EcefCoor_d offset
struct DoubleVect3 body_inertial_accel
acceleration in body frame, wrt ECI inertial frame
Definition: nps_fdm.h:84
struct DoubleRates body_ecef_rotvel
Definition: nps_fdm.h:97
static void lla_from_jsbsim_geocentric(LlaCoor_d *fdm_lla, FGPropagate *propagate)
Convert JSBSim location to NPS LLA.
#define NMAX_2
double phi
in radians
float left_aileron
Definition: nps_fdm.h:119
#define NPS_JSBSIM_YAW_TRIM
#define NPS_JSBSIM_AILERON_MAX_RAD
void nps_fdm_set_wind(double speed, double dir)
double gc_of_gd_lat_d(double gd_lat, double hmsl)
struct NedCoor_d ltp_ecef_accel
acceleration in LTP frame, wrt ECEF frame
Definition: nps_fdm.h:76
int16_t extrapsh(double date, double dte1, int16_t nmax1, int16_t nmax2, double *gh)
double psi
in radians
#define VECT3_DIFF(_c, _a, _b)
Definition: pprz_algebra.h:181
#define VECT3_ASSIGN(_a, _x, _y, _z)
Definition: pprz_algebra.h:124
double lat
in radians
double alt
in meters above WGS84 reference ellipsoid
angular rates
bool on_ground
Definition: nps_fdm.h:49
static float radius
Definition: chemotaxis.c:15
struct DoubleRates body_ecef_rotaccel
Definition: nps_fdm.h:98
bool launch
Definition: sim_ap.c:38
double q
in rad/s^2
void nps_fdm_set_wind_ned(double wind_north, double wind_east, double wind_down)
static void init_ltp(void)
Initialize the ltp from the JSBSim location.
double theta
in radians
struct LlaCoor_d lla_pos_pprz
Definition: nps_fdm.h:58
vector in Latitude, Longitude and Altitude
float dt
struct DoubleRates body_inertial_rotvel
Definition: nps_fdm.h:101
double r
in rad/s^2
#define NPS_JSBSIM_PITCH_TRIM
Trim values for the airframe.
static void jsbsimvec_to_vec(DoubleVect3 *fdm_vector, const FGColumnVector3 *jsb_vector)
Convert JSBSim vector format and struct to NPS vector format and struct.
#define MetersOfFeet(_f)
Macro to convert from feet to metres.
int nan_count
Definition: nps_fdm.h:50
#define NPS_JSBSIM_ELEVATOR_MAX_RAD
struct DoubleEulers ltp_to_body_eulers
Definition: nps_fdm.h:92
struct NedCoor_d ltp_ecef_vel
velocity in LTP frame, wrt ECEF frame
Definition: nps_fdm.h:74
double pressure_sl
pressure at sea level in Pascal
Definition: nps_fdm.h:114
Definition: nps_fdm.h:44
double x
in meters
void nps_fdm_set_temperature(double temp, double h)
Set temperature in degrees Celcius at given height h above MSL.
static void lla_from_jsbsim_geodetic(LlaCoor_d *fdm_lla, FGPropagate *propagate)
Convert JSBSim location to NPS LLA.
#define FALSE
Definition: std.h:5
struct NedCoor_d ltpprz_pos
Definition: nps_fdm.h:54
void nps_fdm_set_turbulence(double wind_speed, int turbulence_severity)
double hmsl
Definition: nps_fdm.h:56
#define QUAT_COPY(_qo, _qi)
Definition: pprz_algebra.h:532
Paparazzi double-precision floating point math for geodetic calculations.
Paparazzi floating point math for geodetic calculations.
struct EcefCoor_d ecef_ecef_vel
velocity in ECEF frame, wrt ECEF frame
Definition: nps_fdm.h:64
double airspeed
equivalent airspeed in m/s
Definition: nps_fdm.h:109
void nps_fdm_run_step(bool launch, double *commands, int commands_nb)
#define TRUE
Definition: std.h:4
static void double_vect3_normalize(struct DoubleVect3 *v)
normalize 3D vector in place
static struct LtpDef_d ltpdef
double y
in meters
struct DoubleVect3 body_accel
acceleration in body frame as measured by an accelerometer (incl.
Definition: nps_fdm.h:87
double x
in meters
double pressure
current (static) atmospheric pressure in Pascal
Definition: nps_fdm.h:110
Paparazzi floating point algebra.
float elevator
Definition: nps_fdm.h:117
float right_aileron
Definition: nps_fdm.h:120
double init_dt
Definition: nps_fdm.h:47
Paparazzi generic algebra macros.
uint32_t num_engines
Definition: nps_fdm.h:124
unsigned long uint32_t
Definition: types.h:18
double min_dt
Timestep used for higher fidelity near the ground.
void nps_fdm_init(double dt)
struct DoubleVect3 wind
velocity in m/s in NED
Definition: nps_fdm.h:107
static void feed_jsbsim(double *commands, int commands_nb)
Feed JSBSim with the latest actuator commands.
PRINT_CONFIG_MSG("USE_INS_NAV_INIT defaulting to TRUE")
definition of the local (flat earth) coordinate system
#define IEXT
#define NPS_JSBSIM_FLAP_MAX_RAD
struct LlaCoor_d lla_pos_geod
Definition: nps_fdm.h:59
static void fetch_state(void)
Populates the NPS fdm struct after a simulation step.
static void jsbsimvec_to_rate(DoubleRates *fdm_rate, const FGColumnVector3 *jsb_vector)
Convert JSBSim rates vector struct to NPS rates struct.
#define NPS_JSBSIM_MODEL
Name of the JSBSim model.
double dynamic_pressure
dynamic pressure in Pascal
Definition: nps_fdm.h:112
vector in EarthCenteredEarthFixed coordinates
void lla_of_ecef_d(struct LlaCoor_d *lla, struct EcefCoor_d *ecef)
double curr_dt
Definition: nps_fdm.h:48
signed long int32_t
Definition: types.h:19
void double_eulers_of_quat(struct DoubleEulers *e, struct DoubleQuat *q)
struct LlaCoor_d lla_pos
Definition: nps_fdm.h:55
#define EXT_COEFF2
struct DoubleVect3 body_ecef_vel
velocity in body frame, wrt ECEF frame
Definition: nps_fdm.h:69
void ltp_def_from_ecef_d(struct LtpDef_d *def, struct EcefCoor_d *ecef)
Paparazzi generic macros for geodetic calculations.
#define FeetOfMeters(_m)
#define NPS_JSBSIM_RUDDER_MAX_RAD
double temperature
current temperature in degrees Celcius
Definition: nps_fdm.h:113
void ned_of_ecef_point_d(struct NedCoor_d *ned, struct LtpDef_d *def, struct EcefCoor_d *ecef)
pprz_t commands[COMMANDS_NB]
Storage of intermediate command values.
Definition: commands.c:30
float rpm[FG_NET_FDM_MAX_ENGINES]
Definition: nps_fdm.h:126
static void llh_from_jsbsim(LlaCoor_d *fdm_lla, FGPropagate *propagate)
Convert JSBSim location to NPS LLH.
struct DoubleQuat ltpprz_to_body_quat
Definition: nps_fdm.h:93
struct NpsFdm fdm
Holds all necessary NPS FDM state information.
double lon
in radians
int16_t mag_calc(int16_t igdgc, double flat, double flon, double elev, int16_t nmax, double *gh, double *geo_mag_x, double *geo_mag_y, double *geo_mag_z, int16_t iext, double ext1, double ext2, double ext3)
static void init_jsbsim(double dt)
Initializes JSBSim.
struct EcefCoor_d ecef_pos
Definition: nps_fdm.h:53
struct DoubleVect3 body_ecef_accel
acceleration in body frame, wrt ECEF frame
Definition: nps_fdm.h:71
#define GEO_EPOCH
#define EULERS_COPY(_a, _b)
Definition: pprz_algebra.h:267
struct DoubleVect3 ltp_g
Definition: nps_fdm.h:104
#define EXT_COEFF1
double z
in meters
static FGFDMExec * FDMExec
The JSBSim executive object.
float rudder
Definition: nps_fdm.h:121
struct NedCoor_d ltpprz_ecef_vel
velocity in ltppprz frame, wrt ECEF frame
Definition: nps_fdm.h:79
#define CelsiusOfRankine(_r)
double p
in rad/s^2
#define EXT_COEFF3
float flap
Definition: nps_fdm.h:118
void ecef_of_lla_d(struct EcefCoor_d *ecef, struct LlaCoor_d *lla)
static int check_for_nan(void)
Checks NpsFdm struct for NaNs.
static void jsbsimloc_to_loc(EcefCoor_d *fdm_location, const FGLocation *jsb_location)
Convert JSBSim location format and struct to NPS location format and struct.
#define MIN_DT
Minimum JSBSim timestep Around 1/10000 seems to be good for ground impacts.
struct DoubleQuat ltp_to_body_quat
Definition: nps_fdm.h:91
double y
in meters
struct EcefCoor_d ecef_ecef_accel
acceleration in ECEF frame, wrt ECEF frame
Definition: nps_fdm.h:66
struct DoubleEulers ltpprz_to_body_eulers
Definition: nps_fdm.h:94
static void jsbsimquat_to_quat(DoubleQuat *fdm_quat, const FGQuaternion *jsb_quat)
Convert JSBSim quaternion struct to NPS quaternion struct.
#define PascalOfPsf(_p)
void ned_of_ecef_vect_d(struct NedCoor_d *ned, struct LtpDef_d *def, struct EcefCoor_d *ecef)
struct DoubleRates body_inertial_rotaccel
Definition: nps_fdm.h:102
struct DoubleVect3 ltp_h
Definition: nps_fdm.h:105