34 #pragma GCC diagnostic push
35 #pragma GCC diagnostic ignored "-Wunused-parameter"
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>
49 #include <models/propulsion/FGThruster.h>
50 #include <models/propulsion/FGPropeller.h>
53 #pragma GCC diagnostic pop
65 #include "generated/airframe.h"
66 #include "generated/flight_plan.h"
69 #define MetersOfFeet(_f) ((_f)/3.2808399)
70 #define FeetOfMeters(_m) ((_m)*3.2808399)
72 #define PascalOfPsf(_p) ((_p) * 47.8802588889)
73 #define CelsiusOfRankine(_r) (((_r) - 491.67) / 1.8)
78 #ifndef NPS_JSBSIM_MODEL
79 #define NPS_JSBSIM_MODEL AIRFRAME_NAME
82 #ifdef NPS_INITIAL_CONDITITONS
83 #warning NPS_INITIAL_CONDITITONS was replaced by NPS_JSBSIM_INIT!
84 #warning Defaulting to flight plan location.
90 #ifndef NPS_JSBSIM_PITCH_TRIM
91 #define NPS_JSBSIM_PITCH_TRIM 0.0
94 #ifndef NPS_JSBSIM_ROLL_TRIM
95 #define NPS_JSBSIM_ROLL_TRIM 0.0
98 #ifndef NPS_JSBSIM_YAW_TRIM
99 #define NPS_JSBSIM_YAW_TRIM 0.0
105 #define DEG2RAD 0.017
107 #ifndef NPS_JSBSIM_ELEVATOR_MAX_RAD
108 #define NPS_JSBSIM_ELEVATOR_MAX_RAD (20.0*DEG2RAD)
111 #ifndef NPS_JSBSIM_AILERON_MAX_RAD
112 #define NPS_JSBSIM_AILERON_MAX_RAD (20.0*DEG2RAD)
115 #ifndef NPS_JSBSIM_RUDDER_MAX_RAD
116 #define NPS_JSBSIM_RUDDER_MAX_RAD (20.0*DEG2RAD)
119 #ifndef NPS_JSBSIM_FLAP_MAX_RAD
120 #define NPS_JSBSIM_FLAP_MAX_RAD (20.0*DEG2RAD)
126 #define MIN_DT (1.0/10240.0)
132 static void feed_jsbsim(
double throttle,
double aileron,
double elevator,
double rudder);
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");
194 #ifdef NPS_JSBSIM_LAUNCHSPEED
195 static bool already_launched =
FALSE;
197 if (
launch && !already_launched) {
198 printf(
"Launching with speed of %.1f m/s!\n", (
float)NPS_JSBSIM_LAUNCHSPEED);
201 already_launched =
TRUE;
228 if (numDT_to_impact <= 1.0) {
243 for (i = 0; i < num_steps; i++) {
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");
261 FGWinds *Winds =
FDMExec->GetWinds();
263 Winds->SetWindPsi(dir);
268 FGWinds *Winds =
FDMExec->GetWinds();
275 FGWinds *Winds =
FDMExec->GetWinds();
278 Winds->SetProbabilityOfExceedence(turbulence_severity);
283 FDMExec->GetAtmosphere()->SetTemperature(temp, h, FGAtmosphere::eCelsius);
294 #ifdef NPS_ACTUATOR_NAMES
296 const char *names[] = NPS_ACTUATOR_NAMES;
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]);
306 if (commands_nb != 4) {
307 cerr <<
"commands_nb must be 4!" << endl;
311 feed_jsbsim(commands[COMMAND_THROTTLE], commands[COMMAND_ROLL], commands[COMMAND_PITCH], commands[3]);
315 static void feed_jsbsim(
double throttle,
double aileron,
double elevator,
double rudder)
317 FGFCS *FCS =
FDMExec->GetFCS();
318 FGPropulsion *FProp =
FDMExec->GetPropulsion();
326 FCS->SetDaCmd(aileron);
327 FCS->SetDeCmd(elevator);
328 FCS->SetDrCmd(rudder);
330 for (
unsigned int i = 0; i <
FDMExec->GetPropulsion()->GetNumEngines(); i++) {
331 FCS->SetThrottleCmd(i, throttle);
333 if (throttle > 0.01) {
334 FProp->SetStarter(1);
336 FProp->SetStarter(0);
348 fdm.
time =
FDMExec->GetPropertyManager()->GetNode(
"simulation/sim-time-sec")->getDoubleValue();
354 FGPropagate *propagate =
FDMExec->GetPropagate();
355 FGAccelerations *accelerations =
FDMExec->GetAccelerations();
363 fdm.
hmsl = propagate->GetAltitudeASLmeters();
381 const FGColumnVector3 &fg_ltp_ecef_accel = propagate->GetTb2l() * accelerations->GetUVWdot();
389 const FGColumnVector3 &fg_ecef_ecef_vel = propagate->GetECEFVelocity();
392 const FGColumnVector3 &fg_ecef_ecef_accel = propagate->GetTb2ec() * accelerations->GetUVWdot();
424 const FGQuaternion jsb_quat = propagate->GetQuaternion();
446 const FGColumnVector3 &fg_wind_ned =
FDMExec->GetWinds()->GetTotalWindNED();
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()) /
469 fdm.
elevator = (
FDMExec->GetPropertyManager()->GetNode(
"fcs/elevator-pos-rad")->getDoubleValue()) /
476 FGPropulsion *FGProp =
FDMExec->GetPropulsion();
485 FGEngine *FGEng = FGProp->GetEngine(k);
486 FGThruster *FGThrst = FGEng->GetThruster();
488 fdm.
rpm[k] = (float) FGThrst->GetRPM();
509 string jsbsim_home =
"/conf/simulator/jsbsim/";
510 string jsbsim_ic_name;
512 char* pprz_home = getenv(
"PAPARAZZI_HOME");
515 if (strlen(pprz_home) <
sizeof(buf)) {
516 cnt = snprintf(buf, strlen(pprz_home) + 1,
"%s", pprz_home);
517 rootdir = string(buf) + jsbsim_home;
524 cout <<
"PPRZ_HOME not set correctly, exiting..." << endl;
531 #ifdef NPS_JSBSIM_INIT
532 jsbsim_ic_name = NPS_JSBSIM_INIT;
543 if (!
FDMExec->LoadModel(rootdir +
"aircraft",
549 cerr <<
" JSBSim could not be started" << endl << endl;
556 cerr <<
"NumEngines: " <<
FDMExec->GetPropulsion()->GetNumEngines() << endl;
557 cerr <<
"NumGearUnits: " <<
FDMExec->GetGroundReactions()->GetNumGearUnits() << endl;
563 FGInitialCondition *IC =
FDMExec->GetIC();
564 if (!jsbsim_ic_name.empty()) {
565 if (! IC->Load(jsbsim_ic_name)) {
567 cerr <<
"Initialization unsuccessful" << endl;
574 cout <<
"JSBSim initial conditions loaded from " << jsbsim_ic_name << endl;
579 IC->SetVgroundFpsIC(0.);
583 double gd_lat = RadOfDeg(NAV_LAT0 / 1e7);
585 IC->SetLatitudeDegIC(DegOfRad(gc_lat));
586 IC->SetLongitudeDegIC(NAV_LON0 / 1e7);
588 IC->SetWindNEDFpsIC(0.0, 0.0, 0.0);
591 IC->SetPsiDegIC(QFU);
592 IC->SetVgroundFpsIC(0.);
594 lla0.
lon = RadOfDeg(NAV_LON0 / 1e7);
596 lla0.
alt = (double)(NAV_ALT0 + NAV_MSL0) / 1000.0;
604 cerr <<
"Initialization unsuccessful" << endl;
609 FDMExec->GetPropulsion()->InitRunning(-1);
623 int num_gear =
FDMExec->GetGroundReactions()->GetNumGearUnits();
625 for (i = 0; i < num_gear; i++) {
626 FGColumnVector3 gear_location =
FDMExec->GetGroundReactions()->GetGearUnit(i)->GetBodyLocation();
640 FGPropagate *propagate =
FDMExec->GetPropagate();
650 #if !NPS_CALC_GEO_MAG && defined(AHRS_H_X)
651 PRINT_CONFIG_MSG(
"Using magnetic field as defined in airframe file (AHRS section).")
655 #elif !NPS_CALC_GEO_MAG && defined(INS_H_X)
656 PRINT_CONFIG_MSG(
"Using magnetic field as defined in airframe file (INS section).")
661 PRINT_CONFIG_MSG(
"Using WMM2010 model to calculate magnetic field at simulated location.")
667 double sdate = 2014.5;
678 mag_calc(1, latitude, longitude, alt, nmax, gha,
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);
747 fdm_rate->
p = jsb_vector->Entry(1);
748 fdm_rate->
q = jsb_vector->Entry(2);
749 fdm_rate->
r = jsb_vector->Entry(3);
764 fdm_lla->
lat = propagate->GetGeodLatitudeRad();
765 fdm_lla->
lon = propagate->GetLongitude();
766 fdm_lla->
alt = propagate->GetAltitudeASLmeters();
784 fdm_lla->
lat = propagate->GetLatitude();
785 fdm_lla->
lon = propagate->GetLongitude();
801 fdm_lla->
lat = propagate->GetGeodLatitudeRad();
802 fdm_lla->
lon = propagate->GetLongitude();
810 static int isnan(
double f) {
return (f != f); }
#define NPS_JSBSIM_ROLL_TRIM
double total_pressure
total atmospheric pressure in Pascal
uint32_t eng_state[FG_NET_FDM_MAX_ENGINES]
WMM2015 Geomagnetic field model.
struct DoubleQuat ecef_to_body_quat
#define VECT3_ADD(_a, _b)
struct NedCoor_d ltpprz_ecef_accel
accel in ltppprz frame, wrt ECEF frame
struct LlaCoor_d lla_pos_geoc
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
struct DoubleRates body_ecef_rotvel
static void lla_from_jsbsim_geocentric(LlaCoor_d *fdm_lla, FGPropagate *propagate)
Convert JSBSim location to NPS LLA.
#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
int16_t extrapsh(double date, double dte1, int16_t nmax1, int16_t nmax2, double *gh)
#define VECT3_DIFF(_c, _a, _b)
#define VECT3_ASSIGN(_a, _x, _y, _z)
double alt
in meters above WGS84 reference ellipsoid
struct DoubleRates body_ecef_rotaccel
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.
struct LlaCoor_d lla_pos_pprz
vector in Latitude, Longitude and Altitude
struct DoubleRates body_inertial_rotvel
#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.
#define NPS_JSBSIM_ELEVATOR_MAX_RAD
struct DoubleEulers ltp_to_body_eulers
struct NedCoor_d ltp_ecef_vel
velocity in LTP frame, wrt ECEF frame
double pressure_sl
pressure at sea level in Pascal
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.
struct NedCoor_d ltpprz_pos
void nps_fdm_set_turbulence(double wind_speed, int turbulence_severity)
#define QUAT_COPY(_qo, _qi)
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
double airspeed
equivalent airspeed in m/s
void nps_fdm_run_step(bool launch, double *commands, int commands_nb)
static void double_vect3_normalize(struct DoubleVect3 *v)
normalize 3D vector in place
static struct LtpDef_d ltpdef
struct DoubleVect3 body_accel
acceleration in body frame as measured by an accelerometer (incl.
double pressure
current (static) atmospheric pressure in Pascal
Paparazzi floating point algebra.
Paparazzi generic algebra macros.
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
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 NPS_JSBSIM_FLAP_MAX_RAD
struct LlaCoor_d lla_pos_geod
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
vector in EarthCenteredEarthFixed coordinates
void lla_of_ecef_d(struct LlaCoor_d *lla, struct EcefCoor_d *ecef)
void double_eulers_of_quat(struct DoubleEulers *e, struct DoubleQuat *q)
struct DoubleVect3 body_ecef_vel
velocity in body frame, wrt ECEF frame
void ltp_def_from_ecef_d(struct LtpDef_d *def, struct EcefCoor_d *ecef)
Paparazzi generic macros for geodetic calculations.
#define NPS_JSBSIM_RUDDER_MAX_RAD
double temperature
current temperature in degrees Celcius
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.
float rpm[FG_NET_FDM_MAX_ENGINES]
static void llh_from_jsbsim(LlaCoor_d *fdm_lla, FGPropagate *propagate)
Convert JSBSim location to NPS LLH.
struct DoubleQuat ltpprz_to_body_quat
struct NpsFdm fdm
Holds all necessary NPS FDM state information.
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
struct DoubleVect3 body_ecef_accel
acceleration in body frame, wrt ECEF frame
#define EULERS_COPY(_a, _b)
static FGFDMExec * FDMExec
The JSBSim executive object.
struct NedCoor_d ltpprz_ecef_vel
velocity in ltppprz frame, wrt ECEF frame
#define CelsiusOfRankine(_r)
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
struct EcefCoor_d ecef_ecef_accel
acceleration in ECEF frame, wrt ECEF frame
struct DoubleEulers ltpprz_to_body_eulers
static void jsbsimquat_to_quat(DoubleQuat *fdm_quat, const FGQuaternion *jsb_quat)
Convert JSBSim quaternion struct to NPS quaternion struct.
void ned_of_ecef_vect_d(struct NedCoor_d *ned, struct LtpDef_d *def, struct EcefCoor_d *ecef)
struct DoubleRates body_inertial_rotaccel