Paparazzi UAS
v7.0_unstable
Paparazzi is a free software Unmanned Aircraft System.
|
#include "nps_fdm.h"
#include <stdlib.h>
#include <stdio.h>
#include "math/pprz_geodetic.h"
#include "math/pprz_geodetic_double.h"
#include "math/pprz_geodetic_float.h"
#include "math/pprz_algebra.h"
#include "math/pprz_algebra_float.h"
#include "math/pprz_isa.h"
#include "generated/airframe.h"
#include "generated/flight_plan.h"
#include "firmwares/rover/guidance/rover_guidance_steering.h"
#include "state.h"
Go to the source code of this file.
Functions | |
static void | init_ltp (void) |
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... | |
static struct LtpDef_d | ltpdef |
static struct EnuCoor_d | rover_pos |
Physical model structures. More... | |
static struct EnuCoor_d | rover_vel |
static struct EnuCoor_d | rover_acc |
static float | mu = 0.01 |
Physical model parameters. More... | |
|
static |
Definition at line 166 of file nps_fdm_rover.c.
References ecef_of_lla_d(), NpsFdm::ecef_pos, fdm, LlaCoor_d::lat, LlaCoor_d::lon, ltp_def_from_ecef_d(), NpsFdm::ltp_g, NpsFdm::ltp_h, ltpdef, PRINT_CONFIG_MSG(), DoubleVect3::x, DoubleVect3::y, and DoubleVect3::z.
Referenced by nps_fdm_init().
void nps_fdm_init | ( | double | dt | ) |
NPS FDM rover init.
NPS FDM rover init.
dt |
Definition at line 64 of file nps_fdm_rover.c.
References _crrcsim::buf, crrcsim, NpsFdm::curr_dt, NpsFdm::dynamic_pressure, fdm, NpsFdm::init_dt, init_ltp(), inputbuf_init(), NpsFdm::ltpprz_to_body_eulers, NpsFdm::nan_count, NPS_CRRCSIM_HOST_IP, NPS_CRRCSIM_HOST_PORT, NpsFdm::on_ground, open_udp(), PPRZ_ISA_SEA_LEVEL_PRESSURE, NpsFdm::pressure, NpsFdm::pressure_sl, DoubleEulers::psi, send_servo_cmd(), _crrcsim::socket, NpsFdm::temperature, NpsFdm::time, NpsFdm::total_pressure, TRUE, and UDP_NONBLOCKING.
Referenced by nps_main_init().
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.
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 83 of file nps_fdm_rover.c.
References NpsFdm::body_ecef_rotaccel, NpsFdm::body_ecef_rotvel, commands, crrcsim, NpsFdm::curr_dt, _crrcsim::data_buffer, decode_ahrspacket(), decode_gpspacket(), decode_imupacket(), 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(), fdm, FLOAT_VECT2_NORM, get_msg(), 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, mu, ned_of_ecef_point_d(), ned_of_ecef_vect_d(), DoubleEulers::psi, DoubleRates::r, rover_acc, rover_pos, rover_vel, send_servo_cmd(), EnuCoor_d::x, and EnuCoor_d::y.
Referenced by 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 217 of file nps_fdm_rover.c.
void nps_fdm_set_turbulence | ( | double | wind_speed, |
int | turbulence_severity | ||
) |
Definition at line 212 of file nps_fdm_rover.c.
Referenced by nps_atmosphere_update().
void nps_fdm_set_wind | ( | double | speed, |
double | dir | ||
) |
Definition at line 201 of file nps_fdm_rover.c.
void nps_fdm_set_wind_ned | ( | double | wind_north, |
double | wind_east, | ||
double | wind_down | ||
) |
Definition at line 206 of file nps_fdm_rover.c.
Referenced by nps_atmosphere_update().
struct NpsFdm fdm |
Holds all necessary NPS FDM state information.
Definition at line 1 of file nps_fdm_rover.c.
Referenced by 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().
|
static |
Definition at line 1 of file nps_fdm_rover.c.
Referenced by init_ltp(), and nps_fdm_run_step().
|
static |
Physical model parameters.
Definition at line 60 of file nps_fdm_rover.c.
Referenced by calc_g1_element(), calc_g2_element(), find_contour(), and nps_fdm_run_step().
|
static |
Definition at line 52 of file nps_fdm_rover.c.
Referenced by nps_fdm_run_step().
|
static |
Physical model structures.
Definition at line 52 of file nps_fdm_rover.c.
Referenced by nps_fdm_run_step().
|
static |
Definition at line 52 of file nps_fdm_rover.c.
Referenced by nps_fdm_run_step().