Paparazzi UAS v7.0_unstable
Paparazzi is a free software Unmanned Aircraft System.
Loading...
Searching...
No Matches
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/FGAircraft.h>
46#include <models/FGFCS.h>
47#include <models/atmosphere/FGWinds.h>
48
49// Thrusters
50#include <models/propulsion/FGThruster.h>
51#include <models/propulsion/FGPropeller.h>
52
53// end ignore unused param warnings in JSBSim
54#pragma GCC diagnostic pop
55
56#include "nps_autopilot.h"
57#include "nps_fdm.h"
58#include "math/pprz_geodetic.h"
61#include "math/pprz_algebra.h"
63
65
66#include "generated/airframe.h"
67#include "generated/flight_plan.h"
68
70#define MetersOfFeet(_f) ((_f)/3.2808399)
71#define FeetOfMeters(_m) ((_m)*3.2808399)
72
73#define PascalOfPsf(_p) ((_p) * 47.8802588889)
74#define CelsiusOfRankine(_r) (((_r) - 491.67) / 1.8)
75
77#if NPS_JSBSIM_USE_SGPATH
78#define JSBSIM_PATH(_x) SGPath(_x)
79#else
80#define JSBSIM_PATH(_x) _x
81#endif
82
83/* Actuator naming*/
84#ifdef NPS_USE_COMMANDS
85#define NPS_AUTOMATIC_JSBSIM_ACTUATOR_NAMES TRUE
86#endif
87
88#ifdef NPS_ACTUATOR_NAMES
89#define NPS_AUTOMATIC_JSBSIM_ACTUATOR_NAMES TRUE
90#endif
91
92#ifndef NPS_AUTOMATIC_JSBSIM_ACTUATOR_NAMES
93#define NPS_AUTOMATIC_JSBSIM_ACTUATOR_NAMES FALSE
94#endif
95
99#ifndef NPS_JSBSIM_MODEL
100#define NPS_JSBSIM_MODEL AIRFRAME_NAME
101#endif
102
103#ifdef NPS_INITIAL_CONDITITONS
104#warning NPS_INITIAL_CONDITITONS was replaced by NPS_JSBSIM_INIT!
105#warning Defaulting to flight plan location.
106#endif
107
111#ifndef NPS_JSBSIM_PITCH_TRIM
112#define NPS_JSBSIM_PITCH_TRIM 0.0
113#endif
114
115#ifndef NPS_JSBSIM_ROLL_TRIM
116#define NPS_JSBSIM_ROLL_TRIM 0.0
117#endif
118
119#ifndef NPS_JSBSIM_YAW_TRIM
120#define NPS_JSBSIM_YAW_TRIM 0.0
121#endif
122
126#define DEG2RAD 0.017
127
128#ifndef NPS_JSBSIM_ELEVATOR_MAX_RAD
129#define NPS_JSBSIM_ELEVATOR_MAX_RAD (20.0*DEG2RAD)
130#endif
131
132#ifndef NPS_JSBSIM_AILERON_MAX_RAD
133#define NPS_JSBSIM_AILERON_MAX_RAD (20.0*DEG2RAD)
134#endif
135
136#ifndef NPS_JSBSIM_RUDDER_MAX_RAD
137#define NPS_JSBSIM_RUDDER_MAX_RAD (20.0*DEG2RAD)
138#endif
139
140#ifndef NPS_JSBSIM_FLAP_MAX_RAD
141#define NPS_JSBSIM_FLAP_MAX_RAD (20.0*DEG2RAD)
142#endif
143
147#define MIN_DT (1.0/10240.0)
148// TODO: maybe lower for slower CPUs & HITL?
149//#define MIN_DT (1.0/1000.0)
150
151using namespace JSBSim;
152using namespace std;
153
154static void feed_jsbsim(double *commands, int commands_nb);
155static void fetch_state(void);
156static int check_for_nan(void);
157
165
166static void init_jsbsim(double dt);
167static void init_ltp(void);
168
170struct NpsFdm fdm;
171
174
175static struct LtpDef_d ltpdef;
176
177// Offset between ecef in geodetic and geocentric coordinates
178static struct EcefCoor_d offset;
179
182
184double min_dt;
185
186void nps_fdm_init(double dt)
187{
188
189 fdm.init_dt = dt;
190 fdm.curr_dt = dt;
191 //Sets up the high fidelity timestep as a multiple of the normal timestep
192 for (min_dt = (1.0 / dt); min_dt < (1 / MIN_DT); min_dt += (1 / dt)) {}
193 min_dt = (1 / min_dt);
194
195 fdm.nan_count = 0;
196
197 VECT3_ASSIGN(offset, 0., 0., 0.);
198
199 init_jsbsim(dt);
200
201 FDMExec->RunIC();
202
203 // Fix getting initial incorrect accel measurements
204 for(uint16_t i = 0; i < 1500; i++)
205 FDMExec->Run();
206
207 init_ltp();
208
209#if DEBUG_NPS_JSBSIM
210 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");
211#endif
212
213 fetch_state();
214
215}
216
217void nps_fdm_run_step(bool launch __attribute__((unused)), double *commands, int commands_nb)
218{
219
220#ifdef NPS_JSBSIM_LAUNCHSPEED
221 static bool already_launched = FALSE;
222
223 if (launch && !already_launched) {
224 printf("Launching with speed of %.1f m/s!\n", (float)NPS_JSBSIM_LAUNCHSPEED);
225 FDMExec->GetIC()->SetUBodyFpsIC(FeetOfMeters(NPS_JSBSIM_LAUNCHSPEED));
226 FDMExec->RunIC();
228 }
229#endif
230
232
233 /* To deal with ground interaction issues, we decrease the time
234 step as the vehicle is close to the ground. This is done predictively
235 to ensure no weird accelerations or oscillations. From tests with a bouncing
236 ball model in JSBSim, it seems that 10k steps per second is reasonable to capture
237 all the dynamics. Higher might be a bit more stable, but really starting to push
238 the simulation CPU requirements, especially for more complex models.
239 - at init: get the largest radius from CG to any contact point (landing gear)
240 - if descending...
241 - find current number of timesteps to impact
242 - if impact imminent, calculate a new timestep to use (with limit)
243 - if ascending...
244 - change timestep back to init value
245 - run sim for as many steps as needed to reach init_dt amount of time
246
247 Of course, could probably be improved...
248 */
249 // If the vehicle has a downwards velocity
250 if (fdm.ltp_ecef_vel.z > 0) {
251 // Get the current number of timesteps until impact at current velocity
253 // If impact imminent within next timestep, use high sim rate
254 if (numDT_to_impact <= 1.0) {
256 }
257 }
258 // If the vehicle is moving upwards and out of the ground, reset timestep
259 else if ((fdm.ltp_ecef_vel.z <= 0) && ((fdm.agl + vehicle_radius_max) > 0)) {
261 }
262
263 // Calculate the number of sim steps for correct amount of time elapsed
265
266 // Set the timestep then run sim
267 FDMExec->Setdt(fdm.curr_dt);
268 int i;
269 for (i = 0; i < num_steps; i++) {
270 FDMExec->Run();
271 }
272
273 fetch_state();
274
275 /* Check the current state to make sure it is valid (no NaNs) */
276 if (check_for_nan()) {
277 printf("Error: FDM simulation encountered a total of %i NaN values at simulation time %f.\n", fdm.nan_count, fdm.time);
278 printf("It is likely the simulation diverged and gave non-physical results. If you did\n");
279 printf("not crash, check your model and/or initial conditions. Exiting with status 1.\n");
280 exit(1);
281 }
282
283}
284
285void nps_fdm_set_wind(double speed, double dir)
286{
287 FGWinds *Winds = FDMExec->GetWinds();
288 Winds->SetWindspeed(FeetOfMeters(speed));
289 Winds->SetWindPsi(dir);
290}
291
293{
294 FGWinds *Winds = FDMExec->GetWinds();
297}
298
299void nps_fdm_set_turbulence(double wind_speed, int turbulence_severity)
300{
301 FGWinds *Winds = FDMExec->GetWinds();
302 /* wind speed used for turbulence */
303 Winds->SetWindspeed20ft(FeetOfMeters(wind_speed) / 2);
304 Winds->SetProbabilityOfExceedence(turbulence_severity);
305}
306
307void nps_fdm_set_temperature(double temp, double h)
308{
309 FDMExec->GetAtmosphere()->SetTemperature(temp, h, FGAtmosphere::eCelsius);
310}
311
318static void feed_jsbsim(double *commands, int commands_nb __attribute__((unused)))
319{
320#if NPS_AUTOMATIC_JSBSIM_ACTUATOR_NAMES
321 char buf[64];
322#if defined(NPS_USE_COMMANDS)
323 const char *names[] = COMMAND_NAMES;
324#elif defined(NPS_ACTUATOR_NAMES)
325 const char *names[] = NPS_ACTUATOR_NAMES;
326#endif
327 string property;
328 int i;
329 for (i = 0; i < commands_nb; i++) {
330 sprintf(buf, "fcs/%s", names[i]);
331 property = string(buf);
332 FDMExec->GetPropertyManager()->GetNode(property)->SetDouble("", commands[i]);
333 }
334#else /*Use manually defined commands*/
335 // get FGFCS instance
336 FGFCS *FCS = FDMExec->GetFCS();
337
338 // Set trims
339 FCS->SetPitchTrimCmd(NPS_JSBSIM_PITCH_TRIM);
340 FCS->SetRollTrimCmd(NPS_JSBSIM_ROLL_TRIM);
341 FCS->SetYawTrimCmd(NPS_JSBSIM_YAW_TRIM);
342
343#ifdef COMMAND_THROTTLE
344 FGPropulsion *FProp = FDMExec->GetPropulsion();
345 for (unsigned int i = 0; i < FDMExec->GetPropulsion()->GetNumEngines(); i++) {
346 FCS->SetThrottleCmd(i, commands[COMMAND_THROTTLE]);
347
348 // Hack to show spinning propellers in flight gear models
349 if (commands[COMMAND_THROTTLE] > 0.01) {
350 FProp->SetStarter(1);
351 } else {
352 FProp->SetStarter(0);
353 }
354 }
355#endif /* COMMAND_THROTTLE */
356
357#ifdef COMMAND_ROLL
358 FCS->SetDaCmd(commands[COMMAND_ROLL]);
359#endif /* COMMAND_ROLL */
360
361#ifdef COMMAND_PITCH
362 FCS->SetDeCmd(commands[COMMAND_PITCH]);
363#endif /* COMMAND_PITCH */
364
365#ifdef COMMAND_YAW
366 FCS->SetDrCmd(commands[COMMAND_YAW]);
367#endif /* COMMAND_YAW */
368
369#ifdef COMMAND_FLAP
370 FCS->SetDfCmd(commands[COMMAND_FLAP]);
371#endif /* COMMAND_FLAP */
372
373#endif /* NPS_AUTOMATIC_JSBSIM_ACTUATOR_NAMES */
374}
375
379static void fetch_state(void)
380{
381
382 fdm.time = FDMExec->GetPropertyManager()->GetNode("simulation/sim-time-sec")->getDoubleValue();
383
384#if DEBUG_NPS_JSBSIM
385 printf("%f,", fdm.time);
386#endif
387
388 FGPropagate *propagate = FDMExec->GetPropagate();
389 FGAccelerations *accelerations = FDMExec->GetAccelerations();
390
391 fdm.on_ground = FDMExec->GetGroundReactions()->GetWOW();
392
393 /*
394 * position
395 */
396 jsbsimloc_to_loc(&fdm.ecef_pos, &propagate->GetLocation());
397 fdm.hmsl = propagate->GetAltitudeASLmeters();
398
399 /*
400 * linear speed and accelerations
401 */
402
403 /* in body frame */
407 jsbsimvec_to_vec(&fdm.body_accel, &accelerations->GetBodyAccel());
408
409#if DEBUG_NPS_JSBSIM
411#endif
412
413 /* in LTP frame */
415 const FGColumnVector3 &fg_ltp_ecef_accel = propagate->GetTb2l() * accelerations->GetUVWdot();
417
418#if DEBUG_NPS_JSBSIM
420#endif
421
422 /* in ECEF frame */
423 const FGColumnVector3 &fg_ecef_ecef_vel = propagate->GetECEFVelocity();
425
426 const FGColumnVector3 &fg_ecef_ecef_accel = propagate->GetTb2ec() * accelerations->GetUVWdot();
428
429#if DEBUG_NPS_JSBSIM
431#endif
432
433 /* in LTP pprz */
437
438#if DEBUG_NPS_JSBSIM
440#endif
441
442 /* llh */
444
445 //for debug
449 fdm.agl = MetersOfFeet(propagate->GetDistanceAGL());
450
451#if DEBUG_NPS_JSBSIM
452 printf("%f\n", fdm.agl);
453#endif
454
455 /*
456 * attitude
457 */
458 const FGQuaternion jsb_quat = propagate->GetQuaternion();
460 /* convert to eulers */
462 /* the "false" pprz lpt */
463 /* FIXME: use jsbsim ltp for now */
466
467 /*
468 * rotational speed and accelerations
469 */
472
475
476
477 /*
478 * wind
479 */
480 const FGColumnVector3 &fg_wind_ned = FDMExec->GetWinds()->GetTotalWindNED();
482
483 /*
484 * Equivalent Airspeed, atmospheric pressure and temperature.
485 */
486 fdm.airspeed = MetersOfFeet(FDMExec->GetAuxiliary()->GetVequivalentFPS());
487 fdm.pressure = PascalOfPsf(FDMExec->GetAtmosphere()->GetPressure());
488 fdm.pressure_sl = PascalOfPsf(FDMExec->GetAtmosphere()->GetPressureSL());
489 fdm.total_pressure = PascalOfPsf(FDMExec->GetAuxiliary()->GetTotalPressure());
490 fdm.dynamic_pressure = PascalOfPsf(FDMExec->GetAuxiliary()->Getqbar());
491 fdm.temperature = CelsiusOfRankine(FDMExec->GetAtmosphere()->GetTemperature());
492
493 /*
494 * angle of attack and SlideSlip.
495 */
496 fdm.aoa= FDMExec->GetPropertyManager()->GetNode("aero/alpha-rad")->getDoubleValue();
497 fdm.sideslip = FDMExec->GetPropertyManager()->GetNode("aero/beta-rad")->getDoubleValue();
498
499 /*
500 * Control surface positions
501 *
502 */
503 fdm.rudder = (FDMExec->GetPropertyManager()->GetNode("fcs/rudder-pos-rad")->getDoubleValue()) /
505 fdm.left_aileron = (-1 * FDMExec->GetPropertyManager()->GetNode("fcs/left-aileron-pos-rad")->getDoubleValue()) /
507 fdm.right_aileron = (FDMExec->GetPropertyManager()->GetNode("fcs/right-aileron-pos-rad")->getDoubleValue()) /
509 fdm.elevator = (FDMExec->GetPropertyManager()->GetNode("fcs/elevator-pos-rad")->getDoubleValue()) /
511 fdm.flap = (FDMExec->GetPropertyManager()->GetNode("fcs/flap-pos-rad")->getDoubleValue()) / NPS_JSBSIM_FLAP_MAX_RAD;
512
513 /*
514 * Propulsion
515 */
516 FGPropulsion *FGProp = FDMExec->GetPropulsion();
517 fdm.num_engines = FGProp->GetNumEngines();
518
519 /*
520 * Note that JSBSim for some reason has very high momentum for the propeller
521 * (even when the moment of inertia of the propeller has the right value)
522 * As a result after switching the motor off
523 */
524 for (uint32_t k = 0; k < fdm.num_engines; k++) {
525 FGEngine *FGEng = FGProp->GetEngine(k);
526 FGThruster *FGThrst = FGEng->GetThruster();
527 fdm.eng_state[k] = FGEng->GetStarter();
528 fdm.rpm[k] = (float) FGThrst->GetRPM();
529 //printf("RPM: %f\n", fdm.rpm[k]);
530 //printf("STATE: %u\n", fdm.eng_state[k]);
531 }
532}
533
544static void init_jsbsim(double dt)
545{
546
547 char buf[1024];
548 string rootdir;
549 string jsbsim_home = "/conf/simulator/jsbsim/";
550 string jsbsim_ic_name;
551
552 char* pprz_home = getenv("PAPARAZZI_HOME");
553
554 int cnt = -1;
555 if (strlen(pprz_home) < sizeof(buf)) {
556 cnt = snprintf(buf, strlen(pprz_home) + 1, "%s", pprz_home);
557 rootdir = string(buf) + jsbsim_home;
558 }
559
560 // check the results
561 if (cnt < 0){
562 // Either pprz_home path too long for the buffer
563 // or writing the string was not successful.
564 cout << "PPRZ_HOME not set correctly, exiting..." << endl;
565 exit(-1);
566 }
567
568 /* if jsbsim initial conditions are defined, use them
569 * otherwise use flightplan location
570 */
571#ifdef NPS_JSBSIM_INIT
573#endif
574
575 FDMExec = new FGFDMExec();
576
577 FDMExec->Setsim_time(0.);
578 FDMExec->Setdt(dt);
579
580 FDMExec->DisableOutput();
581 FDMExec->SetDebugLevel(0); // No DEBUG messages
582
583 if (! FDMExec->LoadModel(JSBSIM_PATH(rootdir + "aircraft"),
584 JSBSIM_PATH(rootdir + "engine"),
585 JSBSIM_PATH(rootdir + "systems"),
587 false)) {
588#ifdef DEBUG
589 cerr << " JSBSim could not be started" << endl << endl;
590#endif
591 delete FDMExec;
592 exit(-1);
593 }
594 cout << "JSBSim model loaded from " << NPS_JSBSIM_MODEL << endl;
595
596#ifdef DEBUG
597 cerr << "NumEngines: " << FDMExec->GetPropulsion()->GetNumEngines() << endl;
598 cerr << "NumGearUnits: " << FDMExec->GetGroundReactions()->GetNumGearUnits() << endl;
599#endif
600
601 // LLA initial coordinates (geodetic lat, geoid alt)
602 struct LlaCoor_d lla0;
603
604 FGInitialCondition *IC = FDMExec->GetIC();
605 if (!jsbsim_ic_name.empty()) {
606 if (! IC->Load(JSBSIM_PATH(jsbsim_ic_name))) {
607#ifdef DEBUG
608 cerr << "Initialization unsuccessful" << endl;
609#endif
610 delete FDMExec;
611 exit(-1);
612 }
613
614 llh_from_jsbsim(&lla0, FDMExec->GetPropagate());
615 cout << "JSBSim initial conditions loaded from " << jsbsim_ic_name << endl;
616 } else {
617 // FGInitialCondition::SetAltitudeASLFtIC
618 // requires this function to be called
619 // before itself
620 IC->SetVgroundFpsIC(0.);
621
622 // Use flight plan initial conditions
623 // convert geodetic lat from flight plan to geocentric
624 double gd_lat = RadOfDeg(NAV_LAT0 / 1e7);
626 IC->SetLatitudeDegIC(DegOfRad(gc_lat));
627 IC->SetLongitudeDegIC(NAV_LON0 / 1e7);
628
629 IC->SetWindNEDFpsIC(0.0, 0.0, 0.0);
630 IC->SetAltitudeASLFtIC(FeetOfMeters(GROUND_ALT + 2.0));
631 IC->SetTerrainElevationFtIC(FeetOfMeters(GROUND_ALT));
632 IC->SetPsiDegIC(QFU);
633 IC->SetVgroundFpsIC(0.);
634
635 lla0.lon = RadOfDeg(NAV_LON0 / 1e7);
636 lla0.lat = gd_lat;
637 lla0.alt = (double)(NAV_ALT0 + NAV_MSL0) / 1000.0;
638 }
639
640 // initial commands to zero
641 double init_commands[NPS_COMMANDS_NB] = {0.0};
643
644 //loop JSBSim once w/o integrating
645 if (!FDMExec->RunIC()) {
646 cerr << "Initialization unsuccessful" << endl;
647 exit(-1);
648 }
649
650 //initRunning for all engines
651 FDMExec->GetPropulsion()->InitRunning(-1);
652
653
654 // compute offset between geocentric and geodetic ecef
656 struct EcefCoor_d ecef0 = {
657 MetersOfFeet(FDMExec->GetPropagate()->GetLocation().Entry(1)),
658 MetersOfFeet(FDMExec->GetPropagate()->GetLocation().Entry(2)),
659 MetersOfFeet(FDMExec->GetPropagate()->GetLocation().Entry(3))
660 };
662
663 // calculate vehicle max radius in m
664 vehicle_radius_max = 0.01; // specify not 0.0 in case no gear
665 int num_gear = FDMExec->GetGroundReactions()->GetNumGearUnits();
666 int i;
667 for (i = 0; i < num_gear; i++) {
668 FGColumnVector3 gear_location = FDMExec->GetGroundReactions()->GetGearUnit(i)->GetBodyLocation();
669 double radius = MetersOfFeet(gear_location.Magnitude());
670 if (radius > vehicle_radius_max) { vehicle_radius_max = radius; }
671 }
672
673}
674
679static void init_ltp(void)
680{
681
682 FGPropagate *propagate = FDMExec->GetPropagate();
683
684 jsbsimloc_to_loc(&fdm.ecef_pos, &propagate->GetLocation());
686
687 fdm.ltp_g.x = 0.;
688 fdm.ltp_g.y = 0.;
689 fdm.ltp_g.z = 9.81;
690
691
692#if !NPS_CALC_GEO_MAG && defined(AHRS_H_X)
693 PRINT_CONFIG_MSG("Using magnetic field as defined in airframe file (AHRS section).")
697#elif !NPS_CALC_GEO_MAG && defined(INS_H_X)
698 PRINT_CONFIG_MSG("Using magnetic field as defined in airframe file (INS section).")
699 fdm.ltp_h.x = INS_H_X;
700 fdm.ltp_h.y = INS_H_Y;
701 fdm.ltp_h.z = INS_H_Z;
702#else
703 PRINT_CONFIG_MSG("Using WMM2010 model to calculate magnetic field at simulated location.")
704 /* calculation of magnetic field according to WMM2010 model */
705 double gha[MAXCOEFF];
706
707 /* Current date in decimal year, for example 2012.68 */
709 double sdate = 2019.0;
710
712 /* LLA Position in decimal degrees and altitude in km */
713 double latitude = DegOfRad(fdm.lla_pos.lat);
714 double longitude = DegOfRad(fdm.lla_pos.lon);
715 double alt = fdm.lla_pos.alt / 1e3;
716
717 // Calculates additional coeffs
719 // Calculates absolute magnetic field
720 mag_calc(1, latitude, longitude, alt, nmax, gha,
721 &fdm.ltp_h.x, &fdm.ltp_h.y, &fdm.ltp_h.z,
724 printf("normalized magnetic field: %.4f %.4f %.4f\n", fdm.ltp_h.x, fdm.ltp_h.y, fdm.ltp_h.z);
725#endif
726
727}
728
746
756{
757
758 fdm_vector->x = MetersOfFeet(jsb_vector->Entry(1));
759 fdm_vector->y = MetersOfFeet(jsb_vector->Entry(2));
760 fdm_vector->z = MetersOfFeet(jsb_vector->Entry(3));
761
762}
763
771{
772
773 fdm_quat->qi = jsb_quat->Entry(1);
774 fdm_quat->qx = jsb_quat->Entry(2);
775 fdm_quat->qy = jsb_quat->Entry(3);
776 fdm_quat->qz = jsb_quat->Entry(4);
777
778}
779
787{
788
789 fdm_rate->p = jsb_vector->Entry(1);
790 fdm_rate->q = jsb_vector->Entry(2);
791 fdm_rate->r = jsb_vector->Entry(3);
792
793}
794
804{
805
806 fdm_lla->lat = propagate->GetGeodLatitudeRad();
807 fdm_lla->lon = propagate->GetLongitude();
808 fdm_lla->alt = propagate->GetAltitudeASLmeters();
809 //printf("geodetic alt: %f\n", MetersOfFeet(propagate->GetGeodeticAltitude()));
810 //printf("ground alt: %f\n", MetersOfFeet(propagate->GetDistanceAGL()));
811 //printf("ASL alt: %f\n", propagate->GetAltitudeASLmeters());
812
813}
814
824{
825
826 fdm_lla->lat = propagate->GetLatitude();
827 fdm_lla->lon = propagate->GetLongitude();
828 fdm_lla->alt = MetersOfFeet(propagate->GetRadius());
829
830}
831
841{
842
843 fdm_lla->lat = propagate->GetGeodLatitudeRad();
844 fdm_lla->lon = propagate->GetLongitude();
845 fdm_lla->alt = MetersOfFeet(propagate->GetGeodeticAltitude());
846
847}
848
849#ifdef __APPLE__
850/* Why isn't this there when we include math.h (on osx with clang)? */
852static int isnan(double f) { return (f != f); }
853#endif
854
862static int check_for_nan(void)
863{
865 /* Check all elements for nans */
866 if (isnan(fdm.ecef_pos.x)) { fdm.nan_count++; }
867 if (isnan(fdm.ecef_pos.y)) { fdm.nan_count++; }
868 if (isnan(fdm.ecef_pos.z)) { fdm.nan_count++; }
869 if (isnan(fdm.ltpprz_pos.x)) { fdm.nan_count++; }
870 if (isnan(fdm.ltpprz_pos.y)) { fdm.nan_count++; }
871 if (isnan(fdm.ltpprz_pos.z)) { fdm.nan_count++; }
872 if (isnan(fdm.lla_pos.lon)) { fdm.nan_count++; }
873 if (isnan(fdm.lla_pos.lat)) { fdm.nan_count++; }
874 if (isnan(fdm.lla_pos.alt)) { fdm.nan_count++; }
875 if (isnan(fdm.hmsl)) { fdm.nan_count++; }
876 // Skip debugging elements
877 if (isnan(fdm.ecef_ecef_vel.x)) { fdm.nan_count++; }
878 if (isnan(fdm.ecef_ecef_vel.y)) { fdm.nan_count++; }
879 if (isnan(fdm.ecef_ecef_vel.z)) { fdm.nan_count++; }
883 if (isnan(fdm.body_ecef_vel.x)) { fdm.nan_count++; }
884 if (isnan(fdm.body_ecef_vel.y)) { fdm.nan_count++; }
885 if (isnan(fdm.body_ecef_vel.z)) { fdm.nan_count++; }
889 if (isnan(fdm.ltp_ecef_vel.x)) { fdm.nan_count++; }
890 if (isnan(fdm.ltp_ecef_vel.y)) { fdm.nan_count++; }
891 if (isnan(fdm.ltp_ecef_vel.z)) { fdm.nan_count++; }
925 if (isnan(fdm.ltp_g.x)) { fdm.nan_count++; }
926 if (isnan(fdm.ltp_g.y)) { fdm.nan_count++; }
927 if (isnan(fdm.ltp_g.z)) { fdm.nan_count++; }
928 if (isnan(fdm.ltp_h.x)) { fdm.nan_count++; }
929 if (isnan(fdm.ltp_h.y)) { fdm.nan_count++; }
930 if (isnan(fdm.ltp_h.z)) { fdm.nan_count++; }
931
932 return (fdm.nan_count - orig_nan_count);
933}
static void h(const real32_T x[7], const real32_T q[4], real32_T y[6])
double psi
in radians
double p
in rad/s^2
double theta
in radians
double q
in rad/s^2
double phi
in radians
double r
in rad/s^2
void double_eulers_of_quat(struct DoubleEulers *e, struct DoubleQuat *q)
static void double_vect3_normalize(struct DoubleVect3 *v)
normalize 3D vector in place
Roation quaternion.
angular rates
#define EULERS_COPY(_a, _b)
#define VECT3_ASSIGN(_a, _x, _y, _z)
#define QUAT_COPY(_qo, _qi)
#define VECT3_DIFF(_c, _a, _b)
#define VECT3_ADD(_a, _b)
double x
in meters
double y
in meters
double y
in meters
double z
in meters
double z
in meters
double lat
in radians
double alt
in meters above WGS84 reference ellipsoid
double lon
in radians
double x
in meters
double gc_of_gd_lat_d(double gd_lat, double hmsl)
void ltp_def_from_ecef_d(struct LtpDef_d *def, struct EcefCoor_d *ecef)
void ned_of_ecef_vect_d(struct NedCoor_d *ned, struct LtpDef_d *def, struct EcefCoor_d *ecef)
void lla_of_ecef_d(struct LlaCoor_d *lla, struct EcefCoor_d *ecef)
void ned_of_ecef_point_d(struct NedCoor_d *ned, struct LtpDef_d *def, struct EcefCoor_d *ecef)
void ecef_of_lla_d(struct EcefCoor_d *ecef, struct LlaCoor_d *lla)
vector in EarthCenteredEarthFixed coordinates
vector in Latitude, Longitude and Altitude
definition of the local (flat earth) coordinate system
#define EXT_COEFF2
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)
#define NMAX_2
int16_t extrapsh(double date, double dte1, int16_t nmax1, int16_t nmax2, double *gh)
#define EXT_COEFF3
#define IEXT
#define MAXCOEFF
#define GEO_EPOCH
#define EXT_COEFF1
#define NMAX_1
PRINT_CONFIG_MSG("USE_INS_NAV_INIT defaulting to TRUE")
uint16_t foo
Definition main_demo5.c:58
#define NPS_COMMANDS_NB
Number of commands sent to the FDM of NPS.
float rudder
Definition nps_fdm.h:123
double time
Definition nps_fdm.h:46
double aoa
angle of attack in rad
Definition nps_fdm.h:115
struct NedCoor_d ltpprz_ecef_vel
velocity in ltppprz frame, wrt ECEF frame
Definition nps_fdm.h:79
struct DoubleVect3 ltp_g
Definition nps_fdm.h:104
double pressure_sl
pressure at sea level in Pascal
Definition nps_fdm.h:114
float elevator
Definition nps_fdm.h:119
struct DoubleQuat ecef_to_body_quat
Definition nps_fdm.h:90
struct DoubleQuat ltpprz_to_body_quat
Definition nps_fdm.h:93
double init_dt
Definition nps_fdm.h:47
double total_pressure
total atmospheric pressure in Pascal
Definition nps_fdm.h:111
double hmsl
Definition nps_fdm.h:56
struct EcefCoor_d ecef_pos
Definition nps_fdm.h:53
struct NedCoor_d ltpprz_pos
Definition nps_fdm.h:54
struct LlaCoor_d lla_pos_pprz
Definition nps_fdm.h:58
struct DoubleVect3 body_inertial_accel
acceleration in body frame, wrt ECI inertial frame
Definition nps_fdm.h:84
struct DoubleRates body_inertial_rotvel
Definition nps_fdm.h:101
double airspeed
equivalent airspeed in m/s
Definition nps_fdm.h:109
struct NedCoor_d ltp_ecef_vel
velocity in LTP frame, wrt ECEF frame
Definition nps_fdm.h:74
struct NedCoor_d ltpprz_ecef_accel
accel in ltppprz frame, wrt ECEF frame
Definition nps_fdm.h:81
struct DoubleVect3 body_ecef_vel
velocity in body frame, wrt ECEF frame
Definition nps_fdm.h:69
double agl
Definition nps_fdm.h:61
struct DoubleVect3 ltp_h
Definition nps_fdm.h:105
double dynamic_pressure
dynamic pressure in Pascal
Definition nps_fdm.h:112
struct DoubleEulers ltp_to_body_eulers
Definition nps_fdm.h:92
struct EcefCoor_d ecef_ecef_accel
acceleration in ECEF frame, wrt ECEF frame
Definition nps_fdm.h:66
double pressure
current (static) atmospheric pressure in Pascal
Definition nps_fdm.h:110
double curr_dt
Definition nps_fdm.h:48
struct DoubleQuat ltp_to_body_quat
Definition nps_fdm.h:91
struct DoubleRates body_ecef_rotvel
Definition nps_fdm.h:97
struct EcefCoor_d ecef_ecef_vel
velocity in ECEF frame, wrt ECEF frame
Definition nps_fdm.h:64
struct DoubleVect3 body_ecef_accel
acceleration in body frame, wrt ECEF frame
Definition nps_fdm.h:71
struct DoubleRates body_inertial_rotaccel
Definition nps_fdm.h:102
double temperature
current temperature in degrees Celcius
Definition nps_fdm.h:113
struct DoubleRates body_ecef_rotaccel
Definition nps_fdm.h:98
float left_aileron
Definition nps_fdm.h:121
float right_aileron
Definition nps_fdm.h:122
struct DoubleEulers ltpprz_to_body_eulers
Definition nps_fdm.h:94
float rpm[FG_NET_FDM_MAX_ENGINES]
Definition nps_fdm.h:128
uint32_t eng_state[FG_NET_FDM_MAX_ENGINES]
Definition nps_fdm.h:127
struct LlaCoor_d lla_pos
Definition nps_fdm.h:55
double sideslip
sideslip angle in rad
Definition nps_fdm.h:116
struct DoubleVect3 body_accel
acceleration in body frame as measured by an accelerometer (incl.
Definition nps_fdm.h:87
struct LlaCoor_d lla_pos_geoc
Definition nps_fdm.h:60
struct DoubleVect3 wind
velocity in m/s in NED
Definition nps_fdm.h:107
bool on_ground
Definition nps_fdm.h:49
int nan_count
Definition nps_fdm.h:50
float flap
Definition nps_fdm.h:120
uint32_t num_engines
Definition nps_fdm.h:126
struct LlaCoor_d lla_pos_geod
Definition nps_fdm.h:59
struct NedCoor_d ltp_ecef_accel
acceleration in LTP frame, wrt ECEF frame
Definition nps_fdm.h:76
#define CelsiusOfRankine(_r)
void nps_fdm_set_wind_ned(double wind_north, double wind_east, double wind_down)
#define NPS_JSBSIM_RUDDER_MAX_RAD
double vehicle_radius_max
The largest distance between vehicle CG and contact point.
#define NPS_JSBSIM_PITCH_TRIM
Trim values for the airframe.
#define NPS_JSBSIM_MODEL
Name of the JSBSim model.
static FGFDMExec * FDMExec
The JSBSim executive object.
void nps_fdm_init(double dt)
NPS FDM rover init.
#define FeetOfMeters(_m)
static void init_jsbsim(double dt)
Initializes JSBSim.
static void fetch_state(void)
Populates the NPS fdm struct after a simulation step.
static void lla_from_jsbsim_geodetic(LlaCoor_d *fdm_lla, FGPropagate *propagate)
Convert JSBSim location to NPS LLA.
static void init_ltp(void)
Initialize the ltp from the JSBSim location.
#define MIN_DT
Minimum JSBSim timestep Around 1/10000 seems to be good for ground impacts.
void nps_fdm_run_step(bool launch, double *commands, int commands_nb)
Minimum complexity flight dynamic model In legacy Paparazzi simulator, was implemented in OCaml and c...
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 NPS_JSBSIM_ELEVATOR_MAX_RAD
#define NPS_JSBSIM_FLAP_MAX_RAD
void nps_fdm_set_temperature(double temp, double h)
Set temperature in degrees Celcius at given height h above MSL.
static void jsbsimquat_to_quat(DoubleQuat *fdm_quat, const FGQuaternion *jsb_quat)
Convert JSBSim quaternion struct to NPS quaternion struct.
#define PascalOfPsf(_p)
static void lla_from_jsbsim_geocentric(LlaCoor_d *fdm_lla, FGPropagate *propagate)
Convert JSBSim location to NPS LLA.
#define NPS_JSBSIM_YAW_TRIM
static int check_for_nan(void)
Checks NpsFdm struct for NaNs.
#define JSBSIM_PATH(_x)
Macro to build file path according to the lib version.
void nps_fdm_set_turbulence(double wind_speed, int turbulence_severity)
static void feed_jsbsim(double *commands, int commands_nb)
Feed JSBSim with the latest actuator commands.
static void jsbsimvec_to_vec(DoubleVect3 *fdm_vector, const FGColumnVector3 *jsb_vector)
Convert JSBSim vector format and struct to NPS vector format and struct.
static void jsbsimvec_to_rate(DoubleRates *fdm_rate, const FGColumnVector3 *jsb_vector)
Convert JSBSim rates vector struct to NPS rates struct.
#define NPS_JSBSIM_AILERON_MAX_RAD
void nps_fdm_set_wind(double speed, double dir)
double min_dt
Timestep used for higher fidelity near the ground.
#define MetersOfFeet(_f)
Macro to convert from feet to metres.
struct NpsFdm fdm
Holds all necessary NPS FDM state information.
static void llh_from_jsbsim(LlaCoor_d *fdm_lla, FGPropagate *propagate)
Convert JSBSim location to NPS LLH.
static struct LtpDef_d ltpdef
static struct EcefCoor_d offset
#define NPS_JSBSIM_ROLL_TRIM
Paparazzi generic algebra macros.
Paparazzi floating point algebra.
Paparazzi generic macros for geodetic calculations.
Paparazzi double-precision floating point math for geodetic calculations.
Paparazzi floating point math for geodetic calculations.
WMM2020 Geomagnetic field model.
static const ShellCommand commands[]
Definition shell_arch.c:78
static const float dir[]
#define TRUE
Definition std.h:4
#define FALSE
Definition std.h:5
unsigned short uint16_t
Typedef defining 16 bit unsigned short type.
int int32_t
Typedef defining 32 bit int type.
unsigned int uint32_t
Typedef defining 32 bit unsigned int type.
uint16_t f
Camera baseline, in meters (i.e. horizontal distance between the two cameras of the stereo setup)
Definition wedgebug.c:204