Paparazzi UAS
v5.14.0_stable-0-g3f680d1
Paparazzi is a free software Unmanned Aircraft System.
|
Flight Dynamics Model (FDM) for NPS using Gazebo. More...
#include <cstdio>
#include <cstdlib>
#include <string>
#include <iostream>
#include <sys/time.h>
#include <gazebo/gazebo.hh>
#include <gazebo/physics/physics.hh>
#include <gazebo/sensors/sensors.hh>
#include <sdf/sdf.hh>
#include <gazebo/gazebo_config.h>
#include "nps_fdm.h"
#include "nps_autopilot.h"
#include "generated/airframe.h"
#include "generated/flight_plan.h"
#include "autopilot.h"
#include "subsystems/abi.h"
#include "math/pprz_isa.h"
#include "math/pprz_algebra_double.h"
#include "filters/low_pass_filter.h"
#include "filters/high_pass_filter.h"
#include "subsystems/actuators/motor_mixing_types.h"
Go to the source code of this file.
Data Structures | |
struct | gazebo_actuators_t |
Macros | |
#define | NPS_GAZEBO_WORLD "empty.world" |
#define | NPS_GAZEBO_AC_NAME "ardrone" |
Functions | |
static void | init_gazebo (void) |
Set up a Gazebo server. More... | |
static void | gazebo_read (void) |
Read Gazebo's simulation state and store the results in the fdm struct used by NPS. More... | |
static void | gazebo_write (double act_commands[], int commands_nb) |
Write actuator commands to Gazebo. More... | |
struct EcefCoor_d | to_pprz_ecef (ignition::math::Vector3d ecef_i) |
struct NedCoor_d | to_pprz_ned (ignition::math::Vector3d global) |
struct LlaCoor_d | to_pprz_lla (ignition::math::Vector3d lla_i) |
struct DoubleVect3 | to_pprz_body (ignition::math::Vector3d body_g) |
struct DoubleRates | to_pprz_rates (ignition::math::Vector3d body_g) |
struct DoubleEulers | to_pprz_eulers (ignition::math::Quaterniond quat) |
struct DoubleEulers | to_global_pprz_eulers (ignition::math::Quaterniond quat) |
struct DoubleVect3 | to_pprz_ltp (ignition::math::Vector3d xyz) |
void | nps_fdm_init (double dt) |
Initialize actuator dynamics, set unused fields in fdm. More... | |
void | nps_fdm_run_step (bool launch, double *act_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 gazebo_actuators_t | gazebo_actuators = { NPS_ACTUATOR_NAMES, NPS_ACTUATOR_THRUSTS, NPS_ACTUATOR_TORQUES, { }, { }, { }} |
struct NpsFdm | fdm |
Holds all necessary NPS FDM state information. More... | |
static bool | gazebo_initialized = false |
static gazebo::physics::ModelPtr | model = NULL |
static gazebo::sensors::ContactSensorPtr | ct |
Flight Dynamics Model (FDM) for NPS using Gazebo.
This is an FDM for NPS that uses Gazebo as the simulation engine.
Definition in file nps_fdm_gazebo.cpp.
struct gazebo_actuators_t |
Definition at line 103 of file nps_fdm_gazebo.cpp.
Data Fields | ||
---|---|---|
struct FirstOrderHighPass | highpass[NPS_COMMANDS_NB] | |
struct FirstOrderLowPass | lowpass[NPS_COMMANDS_NB] | |
double | max_ang_momentum[NPS_COMMANDS_NB] | |
string | names[NPS_COMMANDS_NB] | |
double | thrusts[NPS_COMMANDS_NB] | |
double | torques[NPS_COMMANDS_NB] |
#define NPS_GAZEBO_AC_NAME "ardrone" |
Definition at line 75 of file nps_fdm_gazebo.cpp.
Referenced by init_gazebo().
#define NPS_GAZEBO_WORLD "empty.world" |
Definition at line 72 of file nps_fdm_gazebo.cpp.
Referenced by init_gazebo().
|
static |
Read Gazebo's simulation state and store the results in the fdm struct used by NPS.
Not all fields are filled at the moment, as some of them are unused by paparazzi (see comments) and others are not available in Gazebo 7 (atmosphere).
Definition at line 459 of file nps_fdm_gazebo.cpp.
References NpsFdm::agl, NpsFdm::airspeed, NpsFdm::aoa, NpsFdm::body_accel, NpsFdm::body_ecef_accel, NpsFdm::body_ecef_rotvel, NpsFdm::body_ecef_vel, NpsFdm::body_inertial_accel, NpsFdm::body_inertial_rotvel, double_quat_of_eulers(), NpsFdm::dynamic_pressure, NpsFdm::ecef_ecef_accel, NpsFdm::ecef_ecef_vel, NpsFdm::ecef_pos, NpsFdm::elevator, fdm, NpsFdm::flap, NpsFdm::hmsl, NpsFdm::left_aileron, NpsFdm::lla_pos, NpsFdm::lla_pos_geoc, NpsFdm::lla_pos_geod, NpsFdm::lla_pos_pprz, NpsFdm::ltp_ecef_accel, NpsFdm::ltp_ecef_vel, NpsFdm::ltp_g, NpsFdm::ltp_h, NpsFdm::ltp_to_body_eulers, NpsFdm::ltp_to_body_quat, NpsFdm::ltpprz_ecef_accel, NpsFdm::ltpprz_ecef_vel, NpsFdm::ltpprz_pos, NpsFdm::ltpprz_to_body_eulers, NpsFdm::ltpprz_to_body_quat, model, NpsFdm::num_engines, pprz_isa_pressure_of_height(), NpsFdm::pressure, NpsFdm::pressure_sl, NpsFdm::right_aileron, NpsFdm::rudder, NpsFdm::sideslip, NpsFdm::temperature, NpsFdm::time, to_global_pprz_eulers(), to_pprz_body(), to_pprz_ecef(), to_pprz_lla(), to_pprz_ltp(), to_pprz_ned(), to_pprz_rates(), and NpsFdm::wind.
Referenced by nps_fdm_run_step().
|
static |
Write actuator commands to Gazebo.
This function takes the normalized commands and applies them as forces and torques in Gazebo. Since the commands are normalized in [0,1], their thrusts (NPS_ACTUATOR_THRUSTS) and torques (NPS_ACTUATOR_TORQUES) need to be specified in the airframe file. Their values need to be specified in the same order as the NPS_ACTUATOR_NAMES and should be provided in SI units. See conf/airframes/examples/ardrone2_gazebo.xml for an example.
The forces and torques are applied to (the origin of) the links named in NPS_ACTUATOR_NAMES. See conf/simulator/gazebo/models/ardrone/ardrone.sdf for an example.
act_commands | |
commands_nb |
Definition at line 584 of file nps_fdm_gazebo.cpp.
References autopilot, gazebo_actuators_t::highpass, gazebo_actuators_t::lowpass, gazebo_actuators_t::max_ang_momentum, model, pprz_autopilot::motors_on, gazebo_actuators_t::names, gazebo_actuators_t::thrusts, gazebo_actuators_t::torques, update_first_order_high_pass(), and update_first_order_low_pass().
Referenced by nps_fdm_run_step().
|
static |
Set up a Gazebo server.
Starts a Gazebo server, adds conf/simulator/gazebo/models to its model path and loads the world specified by NPS_GAZEBO_WORLD.
This function also obtaines a pointer to the aircraft model, named NPS_GAZEBO_AC_NAME ('paparazzi_uav' by default). This pointer, 'model', is used to read the state and write actuator commands in gazebo_read and _write.
Definition at line 324 of file nps_fdm_gazebo.cpp.
References ct, h(), init, gazebo_actuators_t::max_ang_momentum, model, MT9F002_OUTPUT_SCALER, MT9F002_TARGET_FPS, NPS_COMMANDS_NB, NPS_GAZEBO_AC_NAME, NPS_GAZEBO_WORLD, gazebo_actuators_t::torques, and yaw_coef.
Referenced by nps_fdm_run_step().
void nps_fdm_init | ( | double | dt | ) |
Initialize actuator dynamics, set unused fields in fdm.
dt |
Definition at line 218 of file nps_fdm_gazebo.cpp.
References NpsFdm::curr_dt, fdm, gazebo_actuators_t::highpass, NpsFdm::init_dt, init_first_order_high_pass(), init_first_order_low_pass(), gazebo_actuators_t::lowpass, gazebo_actuators_t::max_ang_momentum, NpsFdm::nan_count, and NPS_COMMANDS_NB.
void nps_fdm_run_step | ( | bool | launch, |
double * | act_commands, | ||
int | commands_nb | ||
) |
Update the simulation state.
launch | |
act_commands | |
commands_nb |
Definition at line 247 of file nps_fdm_gazebo.cpp.
References gazebo_initialized, gazebo_read(), gazebo_write(), init_gazebo(), and model.
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.
void nps_fdm_set_turbulence | ( | double | wind_speed, |
int | turbulence_severity | ||
) |
Definition at line 299 of file nps_fdm_gazebo.cpp.
void nps_fdm_set_wind | ( | double | speed, |
double | dir | ||
) |
Definition at line 286 of file nps_fdm_gazebo.cpp.
void nps_fdm_set_wind_ned | ( | double | wind_north, |
double | wind_east, | ||
double | wind_down | ||
) |
Definition at line 292 of file nps_fdm_gazebo.cpp.
struct DoubleEulers to_global_pprz_eulers | ( | ignition::math::Quaterniond | quat | ) |
Definition at line 194 of file nps_fdm_gazebo.cpp.
References DoubleEulers::phi, DoubleEulers::psi, and DoubleEulers::theta.
Referenced by gazebo_read().
struct DoubleVect3 to_pprz_body | ( | ignition::math::Vector3d | body_g | ) |
Definition at line 167 of file nps_fdm_gazebo.cpp.
References DoubleVect3::x, DoubleVect3::y, and DoubleVect3::z.
Referenced by gazebo_read().
struct EcefCoor_d to_pprz_ecef | ( | ignition::math::Vector3d | ecef_i | ) |
Definition at line 140 of file nps_fdm_gazebo.cpp.
References EcefCoor_d::x, EcefCoor_d::y, and EcefCoor_d::z.
Referenced by gazebo_read().
struct DoubleEulers to_pprz_eulers | ( | ignition::math::Quaterniond | quat | ) |
Definition at line 185 of file nps_fdm_gazebo.cpp.
References DoubleEulers::phi, DoubleEulers::psi, and DoubleEulers::theta.
struct LlaCoor_d to_pprz_lla | ( | ignition::math::Vector3d | lla_i | ) |
Definition at line 158 of file nps_fdm_gazebo.cpp.
References LlaCoor_d::alt, LlaCoor_d::lat, and LlaCoor_d::lon.
Referenced by gazebo_read().
struct DoubleVect3 to_pprz_ltp | ( | ignition::math::Vector3d | xyz | ) |
Definition at line 203 of file nps_fdm_gazebo.cpp.
References DoubleVect3::x, DoubleVect3::y, and DoubleVect3::z.
Referenced by gazebo_read().
struct NedCoor_d to_pprz_ned | ( | ignition::math::Vector3d | global | ) |
Definition at line 149 of file nps_fdm_gazebo.cpp.
References NedCoor_d::x, NedCoor_d::y, and NedCoor_d::z.
Referenced by gazebo_read().
struct DoubleRates to_pprz_rates | ( | ignition::math::Vector3d | body_g | ) |
Definition at line 176 of file nps_fdm_gazebo.cpp.
References DoubleRates::p, DoubleRates::q, and DoubleRates::r.
Referenced by gazebo_read().
|
static |
Definition at line 132 of file nps_fdm_gazebo.cpp.
Referenced by init_gazebo().
struct NpsFdm fdm |
Holds all necessary NPS FDM state information.
Definition at line 125 of file nps_fdm_gazebo.cpp.
Referenced by gazebo_read(), and nps_fdm_init().
struct gazebo_actuators_t gazebo_actuators = { NPS_ACTUATOR_NAMES, NPS_ACTUATOR_THRUSTS, NPS_ACTUATOR_TORQUES, { }, { }, { }} |
Definition at line 112 of file nps_fdm_gazebo.cpp.
|
static |
Definition at line 128 of file nps_fdm_gazebo.cpp.
Referenced by nps_fdm_run_step().
|
static |
Definition at line 129 of file nps_fdm_gazebo.cpp.
Referenced by gazebo_read(), gazebo_write(), init_gazebo(), and nps_fdm_run_step().