Paparazzi UAS
v7.0_unstable
Paparazzi is a free software Unmanned Aircraft System.
|
#include "std.h"
#include "flight_gear.h"
#include "math/pprz_geodetic_double.h"
#include "math/pprz_algebra_double.h"
Go to the source code of this file.
Data Structures | |
struct | NpsFdm |
Functions | |
void | nps_fdm_init (double dt) |
NPS FDM rover init. More... | |
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 correspond to the 'sim' target. 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... | |
struct 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 |
void nps_fdm_init | ( | double | dt | ) |
NPS FDM rover init.
NPS FDM rover init.
dt |
Definition at line 119 of file nps_fdm_crrcsim.c.
References fixedwing_sim_state::airspeed, fixedwing_sim_state::attitude, _crrcsim::buf, crrcsim, NpsFdm::curr_dt, fixedwing_sim_state::delta_pitch, fixedwing_sim_state::delta_roll, fixedwing_sim_state::delta_thrust, NpsFdm::dynamic_pressure, EULERS_ASSIGN, fdm, FDMExec, fetch_state(), gazebo_actuators, gazebo_actuators_t::highpass, NpsFdm::init_dt, init_first_order_high_pass(), init_first_order_low_pass(), init_jsbsim(), init_ltp(), inputbuf_init(), gazebo_actuators_t::lowpass, NpsFdm::ltpprz_to_body_eulers, gazebo_actuators_t::max_ang_momentum, MIN_DT, min_dt, NpsFdm::nan_count, NPS_COMMANDS_NB, NPS_CRRCSIM_HOST_IP, NPS_CRRCSIM_HOST_PORT, nps_fdm_run_step(), offset, NpsFdm::on_ground, open_udp(), DoubleEulers::phi, fixedwing_sim_state::pos, PPRZ_ISA_SEA_LEVEL_PRESSURE, NpsFdm::pressure, NpsFdm::pressure_sl, DoubleEulers::psi, python_init(), fixedwing_sim_state::rates, send_servo_cmd(), sim_state, _crrcsim::socket, fixedwing_sim_state::speed, NpsFdm::temperature, DoubleEulers::theta, NpsFdm::time, NpsFdm::total_pressure, TRUE, UDP_NONBLOCKING, VECT3_ASSIGN, and fixedwing_sim_state::wind.
Referenced by nps_main_init().
void nps_fdm_run_step | ( | bool | launch, |
double * | act_commands, | ||
int | commands_nb | ||
) |
Minimum complexity flight dynamic model In legacy Paparazzi simulator, was implemented in OCaml and correspond to the 'sim' target.
Johnson, E.N., Fontaine, S.G., and Kahn, A.D., “Minimum Complexity Uninhabited Air Vehicle Guidance And Flight Control System,” Proceedings of the 20th Digital Avionics Systems Conference, 2001. http://www.ae.gatech.edu/~ejohnson/JohnsonFontaineKahn.pdf
Johnson, E.N. and Fontaine, S.G., “Use Of Flight Simulation To Complement Flight Testing Of Low-Cost UAVs,” Proceedings of the AIAA Modeling and Simulation Technology Conference, 2001. http://www.ae.gatech.edu/~ejohnson/AIAA%202001-4059.pdf
Minimum complexity flight dynamic model In legacy Paparazzi simulator, was implemented in OCaml and correspond to the 'sim' target.
launch | |
act_commands | |
commands_nb |
Definition at line 150 of file nps_fdm_crrcsim.c.
References NpsFdm::agl, fixedwing_sim_state::airspeed, alpha, fixedwing_sim_state::attitude, AUTO_THROTTLE_NOMINAL_CRUISE_THROTTLE, NpsFdm::body_ecef_rotaccel, NpsFdm::body_ecef_rotvel, bullet_fdm, check_for_nan(), commands, crrcsim, NpsFdm::curr_dt, _crrcsim::data_buffer, decode_ahrspacket(), decode_gpspacket(), decode_imupacket(), fixedwing_sim_state::delta_pitch, fixedwing_sim_state::delta_roll, fixedwing_sim_state::delta_thrust, double_quat_of_eulers(), DRIVE_SHAFT_DISTANCE, NpsFdm::ecef_ecef_accel, NpsFdm::ecef_ecef_vel, ecef_of_enu_point_d(), ecef_of_enu_vect_d(), NpsFdm::ecef_pos, enu_of_ecef_point_d(), enu_of_ecef_vect_d(), FALSE, fdm, FDMExec, feed_jsbsim(), FeetOfMeters, fetch_state(), FLOAT_VECT2_NORM, gazebo_initialized, gazebo_read(), gazebo_write(), get_acc(), get_ang_acc(), get_ang_vel(), get_msg(), get_orient(), get_pos(), get_vel(), NpsFdm::hmsl, NpsFdm::init_dt, init_gazebo(), lla_of_ecef_d(), NpsFdm::lla_pos, NpsFdm::ltp_ecef_vel, NpsFdm::ltp_to_body_eulers, NpsFdm::ltp_to_body_quat, ltpdef, NpsFdm::ltpprz_ecef_accel, NpsFdm::ltpprz_ecef_vel, NpsFdm::ltpprz_pos, NpsFdm::ltpprz_to_body_eulers, MAX_DELTA, MAX_PPRZ, MAXIMUM_AIRSPEED, MAXIMUM_POWER, min_dt, model, mu, NpsFdm::nan_count, ned_of_ecef_point_d(), ned_of_ecef_vect_d(), DoubleRates::p, DoubleEulers::phi, PITCH_RESPONSE_FACTOR, fixedwing_sim_state::pos, PPRZ_ISA_GRAVITY, DoubleEulers::psi, py_check(), DoubleRates::q, DoubleRates::r, fixedwing_sim_state::rates, ROLL_MAX_SETPOINT, ROLL_RATE_MAX_SETPOINT, ROLL_RESPONSE_FACTOR, rover_acc, rover_pos, rover_vel, send_servo_cmd(), sim_state, fixedwing_sim_state::speed, DoubleEulers::theta, NpsFdm::time, TRUE, v2, vehicle_radius_max, WEIGHT, fixedwing_sim_state::wind, EnuCoor_d::x, EnuCoor_d::y, YAW_RESPONSE_FACTOR, NedCoor_d::z, and EnuCoor_d::z.
Referenced by nps_fdm_init(), and nps_main_run_sim_step().
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_fixedwing_sim.c.
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().
void nps_fdm_set_wind | ( | double | speed, |
double | dir | ||
) |
Definition at line 200 of file nps_fdm_crrcsim.c.
References dir, FDMExec, FeetOfMeters, sim_state, fixedwing_sim_state::wind, EnuCoor_d::x, EnuCoor_d::y, and EnuCoor_d::z.
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, FeetOfMeters, sim_state, fixedwing_sim_state::wind, EnuCoor_d::x, EnuCoor_d::y, and EnuCoor_d::z.
Referenced by nps_atmosphere_update().
|
extern |
Holds all necessary NPS FDM state information.
Definition at line 1 of file nps_fdm_crrcsim.c.
Referenced by check_for_nan(), decode_ahrspacket(), decode_gpspacket(), decode_imupacket(), fetch_state(), gazebo_read(), get_acc(), get_ang_acc(), get_ang_vel(), get_orient(), get_pos(), get_vel(), gps_feed_value(), init_ltp(), nps_fdm_init(), nps_fdm_run_step(), nps_flightgear_send(), nps_flightgear_send_fdm(), nps_ivy_display(), nps_ivy_send_WORLD_ENV_REQ(), nps_main_display(), nps_main_loop(), nps_sensor_accel_run_step(), nps_sensor_airspeed_run_step(), nps_sensor_aoa_run_step(), nps_sensor_baro_run_step(), nps_sensor_gps_run_step(), nps_sensor_gyro_run_step(), nps_sensor_mag_run_step(), nps_sensor_sideslip_run_step(), nps_sensor_sonar_run_step(), nps_sensor_temperature_run_step(), sim_overwrite_ahrs(), and sim_overwrite_ins().