Paparazzi UAS  v5.14.0_stable-0-g3f680d1
Paparazzi is a free software Unmanned Aircraft System.
 All Data Structures Namespaces Files Functions Variables Typedefs Enumerations Enumerator Macros Modules Pages
nps_fdm.h File Reference
#include "std.h"
#include "../flight_gear.h"
#include "math/pprz_geodetic_double.h"
#include "math/pprz_algebra_double.h"
+ Include dependency graph for nps_fdm.h:
+ This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Data Structures

struct  NpsFdm
 

Functions

void nps_fdm_init (double dt)
 Initialize actuator dynamics, set unused fields in fdm. More...
 
void nps_fdm_run_step (bool launch, double *commands, int commands_nb)
 Update the simulation state. More...
 
void nps_fdm_set_wind (double speed, double dir)
 
void nps_fdm_set_wind_ned (double wind_north, double wind_east, double wind_down)
 
void nps_fdm_set_turbulence (double wind_speed, int turbulence_severity)
 
void nps_fdm_set_temperature (double temp, double h)
 Set temperature in degrees Celcius at given height h above MSL. More...
 

Variables

struct NpsFdm fdm
 Holds all necessary NPS FDM state information. More...
 

Data Structure Documentation

struct NpsFdm

Definition at line 44 of file nps_fdm.h.

+ Collaboration diagram for NpsFdm:
Data Fields
double agl
double airspeed equivalent airspeed in m/s
double aoa angle of attack in rad
struct DoubleVect3 body_accel acceleration in body frame as measured by an accelerometer (incl.

gravity)

struct DoubleVect3 body_ecef_accel acceleration in body frame, wrt ECEF frame
struct DoubleRates body_ecef_rotaccel
struct DoubleRates body_ecef_rotvel
struct DoubleVect3 body_ecef_vel velocity in body frame, wrt ECEF frame
struct DoubleVect3 body_inertial_accel acceleration in body frame, wrt ECI inertial frame
struct DoubleRates body_inertial_rotaccel
struct DoubleRates body_inertial_rotvel
double curr_dt
double dynamic_pressure dynamic pressure in Pascal
struct EcefCoor_d ecef_ecef_accel acceleration in ECEF frame, wrt ECEF frame
struct EcefCoor_d ecef_ecef_vel velocity in ECEF frame, wrt ECEF frame
struct EcefCoor_d ecef_pos
struct DoubleQuat ecef_to_body_quat
float elevator
uint32_t eng_state[FG_NET_FDM_MAX_ENGINES]
float flap
double hmsl
double init_dt
float left_aileron
struct LlaCoor_d lla_pos
struct LlaCoor_d lla_pos_geoc
struct LlaCoor_d lla_pos_geod
struct LlaCoor_d lla_pos_pprz
struct NedCoor_d ltp_ecef_accel acceleration in LTP frame, wrt ECEF frame
struct NedCoor_d ltp_ecef_vel velocity in LTP frame, wrt ECEF frame
struct DoubleVect3 ltp_g
struct DoubleVect3 ltp_h
struct DoubleEulers ltp_to_body_eulers
struct DoubleQuat ltp_to_body_quat
struct NedCoor_d ltpprz_ecef_accel accel in ltppprz frame, wrt ECEF frame
struct NedCoor_d ltpprz_ecef_vel velocity in ltppprz frame, wrt ECEF frame
struct NedCoor_d ltpprz_pos
struct DoubleEulers ltpprz_to_body_eulers
struct DoubleQuat ltpprz_to_body_quat
int nan_count
uint32_t num_engines
bool on_ground
double pressure current (static) atmospheric pressure in Pascal
double pressure_sl pressure at sea level in Pascal
float right_aileron
float rpm[FG_NET_FDM_MAX_ENGINES]
float rudder
double sideslip sideslip angle in rad
double temperature current temperature in degrees Celcius
double time
double total_pressure total atmospheric pressure in Pascal
struct DoubleVect3 wind velocity in m/s in NED

Function Documentation

void nps_fdm_run_step ( bool  launch,
double *  act_commands,
int  commands_nb 
)

Update the simulation state.

Parameters
launch
act_commands
commands_nb

Definition at line 150 of file nps_fdm_crrcsim.c.

References NpsFdm::agl, check_for_nan(), crrcsim, NpsFdm::curr_dt, _crrcsim::data_buffer, decode_ahrspacket(), decode_gpspacket(), decode_imupacket(), FALSE, fdm, FDMExec, feed_jsbsim(), FeetOfMeters, fetch_state(), gazebo_initialized, gazebo_read(), gazebo_write(), get_msg(), NpsFdm::init_dt, init_gazebo(), NpsFdm::ltp_ecef_vel, min_dt, model, NpsFdm::nan_count, send_servo_cmd(), NpsFdm::time, TRUE, vehicle_radius_max, and NedCoor_d::z.

Referenced by nps_main_run_sim_step().

+ Here is the call graph for this function:

+ Here is the caller graph for this function:

void nps_fdm_set_temperature ( double  temp,
double  h 
)

Set temperature in degrees Celcius at given height h above MSL.

Definition at line 306 of file nps_fdm_gazebo.cpp.

References FDMExec.

void nps_fdm_set_turbulence ( double  wind_speed,
int  turbulence_severity 
)

Definition at line 211 of file nps_fdm_crrcsim.c.

References FDMExec, and FeetOfMeters.

Referenced by nps_atmosphere_update().

+ Here is the caller graph for this function:

void nps_fdm_set_wind ( double  speed,
double  dir 
)

Definition at line 200 of file nps_fdm_crrcsim.c.

References FDMExec, and FeetOfMeters.

void nps_fdm_set_wind_ned ( double  wind_north,
double  wind_east,
double  wind_down 
)

Definition at line 205 of file nps_fdm_crrcsim.c.

References FDMExec, and FeetOfMeters.

Referenced by nps_atmosphere_update().

+ Here is the caller graph for this function:

Variable Documentation