MAV'RIC
simulation.h
1 /*******************************************************************************
2  * Copyright (c) 2009-2014, MAV'RIC Development Team
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * 1. Redistributions of source code must retain the above copyright notice,
9  * this list of conditions and the following disclaimer.
10  *
11  * 2. Redistributions in binary form must reproduce the above copyright notice,
12  * this list of conditions and the following disclaimer in the documentation
13  * and/or other materials provided with the distribution.
14  *
15  * 3. Neither the name of the copyright holder nor the names of its contributors
16  * may be used to endorse or promote products derived from this software without
17  * specific prior written permission.
18  *
19  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
20  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
21  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
22  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
23  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
24  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
25  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
26  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
27  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
28  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
29  * POSSIBILITY OF SUCH DAMAGE.
30  ******************************************************************************/
31 
32 /*******************************************************************************
33  * \file simulation.h
34  *
35  * \author MAV'RIC Team
36  * \author Felix Schill
37  *
38  * \brief This file is an onboard Hardware-in-the-loop simulation.
39  *
40  * \detail Simulates quad-copter dynamics based on simple aerodynamics/physics
41  * model and generates simulated raw IMU measurements
42  *
43  ******************************************************************************/
44 
45 
46 #ifndef SIMULATION_H_
47 #define SIMULATION_H_
48 
49 #ifdef __cplusplus
50 extern "C" {
51 #endif
52 
53 #include <stdint.h>
54 #include "qfilter.h"
55 
56 #include "imu.h"
57 #include "servos.h"
58 #include "bmp085.h"
59 #include "position_estimation.h"
60 #include "state.h"
61 
62 #define AIR_DENSITY 1.2
63 #define ROTORCOUNT 4
64 
65 
69 typedef struct
70 {
71  float rotor_lpf;
74 
75  float rotor_cd;
76  float rotor_cl;
79 
80  float rotor_pitch;
81  float total_mass;
82  float vehicle_drag;
84  float yaw_momentum;
85 
88 
89  float wind_x;
90  float wind_y;
91 
92  float home_coordinates[3];
93  float sim_gravity;
95 
99 typedef struct
100 {
101  float torques_bf[3];
102  float rates_bf[3];
103  float lin_forces_bf[3];
104  float vel_bf[3];
105  float vel[3];
108 
112 
113  float rotorspeeds[ROTORCOUNT];
114 
116 
117  uint32_t last_update;
118  float dt;
119 
124  const servos_t* servos;
128 
129 
145 bool simulation_init(simulation_model_t* sim, const simulation_config_t* sim_config, ahrs_t* ahrs, imu_t* imu, position_estimation_t* pos_est, barometer_t* pressure, gps_t* gps, state_t* state, const servos_t* servos, bool* waypoint_set);
146 
147 
153 void simulation_calib_set(simulation_model_t *sim);
154 
155 
161 void simulation_update(simulation_model_t *sim);
162 
163 
169 void simulation_simulate_barometer(simulation_model_t *sim);
170 
171 
177 void simulation_simulate_gps(simulation_model_t *sim);
178 
179 
186 void simulation_fake_gps_fix(simulation_model_t* sim, uint32_t timestamp_ms);
187 
188 
194 void simulation_switch_from_reality_to_simulation(simulation_model_t *sim);
195 
196 
202 void simulation_switch_from_simulation_to_reality(simulation_model_t *sim);
203 
204 
205 #ifdef __cplusplus
206 }
207 #endif
208 
209 #endif /* SIMULATION_H_ */
float wind_x
The x component of wind in global frame in m/s.
Definition: simulation.h:89
float rotor_arm_length
The distance between CoG and motor (in meter)
Definition: simulation.h:87
Structure containing the Attitude and Heading Reference System.
Definition: ahrs.h:58
bool * nav_plan_active
The pointer to the waypoint set flag.
Definition: simulation.h:126
barometer_t * pressure
The pointer to the barometer structure.
Definition: simulation.h:122
float sim_gravity
The value of gravity for the simulated forces.
Definition: simulation.h:93
float rotor_cd
The rotor drag coefficient.
Definition: simulation.h:75
float total_mass
The vehicle mass in kg.
Definition: simulation.h:81
Define the servos structure.
Definition: servos.h:82
float rotor_foil_area
The rotor foil area.
Definition: simulation.h:78
float rotor_diameter
The mean rotor diameter in m.
Definition: simulation.h:77
position_estimation_t * pos_est
The pointer to the position estimation structure.
Definition: simulation.h:121
The simulation model structure definition.
Definition: simulation.h:99
float rotor_momentum
The angular momentum of the rotor (for rotor inertia)
Definition: simulation.h:86
gps_t * gps
The pointer to the GPS structure.
Definition: simulation.h:123
Type definition for GPS data.
Definition: gps_ublox.h:635
The IMU structure.
Definition: imu.h:108
float yaw_momentum
The yaw angular momentum constants (assumed to be independent)
Definition: simulation.h:84
sensor_calib_t calib_gyro
The calibration values of the gyroscope.
Definition: simulation.h:109
const ahrs_t * estimated_attitude
The pointer to the attitude estimation structure.
Definition: simulation.h:125
The state structure.
Definition: state.h:79
float rotor_rpm_gain
The gain linking the command to rpm.
Definition: simulation.h:72
sensor_calib_t calib_accelero
The calibration values of the accelerometer.
Definition: simulation.h:110
Structure containing the accelero, gyro and magnetometer sensors' gains.
Definition: imu.h:68
float rotor_lpf
The low-pass filtered response of the rotors to simulate inertia and lag.
Definition: simulation.h:71
float rotor_pitch
The rotor pitch.
Definition: simulation.h:80
float dt
The time base of current update.
Definition: simulation.h:118
local_coordinates_t local_position
The simulated local position.
Definition: simulation.h:107
float roll_pitch_momentum
The roll and pitch angular momentum of the vehicle.
Definition: simulation.h:83
float rotor_cl
The rotor lift coefficient.
Definition: simulation.h:76
Define the barometer structure.
Definition: barometer.h:60
imu_t * imu
The pointer to the IMU structure.
Definition: simulation.h:120
float rotor_rpm_offset
The offset to convert servo commands to rpm.
Definition: simulation.h:73
simulation_config_t vehicle_config
The vehicle configuration variables.
Definition: simulation.h:115
uint32_t last_update
The last update in system ticks.
Definition: simulation.h:117
The vehicle simulation model structure definition.
Definition: simulation.h:69
float wind_y
The y component of wind in global frame in m/s.
Definition: simulation.h:90
sensor_calib_t calib_compass
The calibration values of the compass.
Definition: simulation.h:111
Local coordinates structure.
Definition: coord_conventions.h:73
ahrs_t ahrs
The simulated attitude estimation.
Definition: simulation.h:106
float vehicle_drag
The coefficient of drag of the whole vehicle.
Definition: simulation.h:82
The position estimator structure.
Definition: position_estimation.h:79
const servos_t * servos
The pointer to the servos structure.
Definition: simulation.h:124