APM:Libraries
SIM_Aircraft.h
Go to the documentation of this file.
1 /*
2  This program is free software: you can redistribute it and/or modify
3  it under the terms of the GNU General Public License as published by
4  the Free Software Foundation, either version 3 of the License, or
5  (at your option) any later version.
6 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 /*
16  parent class for aircraft simulators
17 */
18 
19 #pragma once
20 
21 #include <AP_Math/AP_Math.h>
22 
23 #include "SITL.h"
24 #include <AP_Terrain/AP_Terrain.h>
25 
26 
27 namespace SITL {
28 
29 /*
30  parent class for all simulator types
31  */
32 class Aircraft {
33  friend class Gripper_Servo;
34 
35 public:
36  Aircraft(const char *home_str, const char *frame_str);
37 
38  /*
39  structure passed in giving servo positions as PWM values in
40  microseconds
41  */
42  struct sitl_input {
43  uint16_t servos[16];
44  struct {
45  float speed; // m/s
46  float direction; // degrees 0..360
47  float turbulence;
48  float dir_z; //degrees -90..90
49  } wind;
50  };
51 
52  /*
53  set simulation speedup
54  */
55  void set_speedup(float speedup);
56 
57  /*
58  set instance number
59  */
60  void set_instance(uint8_t _instance) {
61  instance = _instance;
62  }
63 
64  /*
65  set directory for additional files such as aircraft models
66  */
67  void set_autotest_dir(const char *_autotest_dir) {
68  autotest_dir = _autotest_dir;
69  }
70 
71  /* Create and set in/out socket for extenal simulator */
72  virtual void set_interface_ports(const char* address, const int port_in, const int port_out) {};
73 
74  /*
75  step the FDM by one time step
76  */
77  virtual void update(const struct sitl_input &input) = 0;
78 
79  /* fill a sitl_fdm structure from the simulator state */
80  void fill_fdm(struct sitl_fdm &fdm);
81 
82  /* smooth sensors to provide kinematic consistancy */
83  void smooth_sensors(void);
84 
85  /* return normal distribution random numbers */
86  static double rand_normal(double mean, double stddev);
87 
88  /* parse a home location string */
89  static bool parse_home(const char *home_str, Location &loc, float &yaw_degrees);
90 
91  // get frame rate of model in Hz
92  float get_rate_hz(void) const { return rate_hz; }
93 
94  const Vector3f &get_gyro(void) const {
95  return gyro;
96  }
97 
98  const Vector3f &get_velocity_ef(void) const {
99  return velocity_ef;
100  }
101 
102  const Vector3f &get_velocity_air_ef(void) const {
103  return velocity_air_ef;
104  }
105 
106  const Matrix3f &get_dcm(void) const {
107  return dcm;
108  }
109 
110  const Vector3f &get_mag_field_bf(void) const {
111  return mag_bf;
112  }
113 
114  virtual float gross_mass() const { return mass; }
115 
116  const Location &get_location() const { return location; }
117 
118  const Vector3f &get_position() const { return position; }
119 
120  void get_attitude(Quaternion &attitude) const {
121  attitude.from_rotation_matrix(dcm);
122  }
123 
124 protected:
128 
130  float home_yaw;
132  Matrix3f dcm; // rotation matrix, APM conventions, from body to earth
133  Vector3f gyro; // rad/s
134  Vector3f gyro_prev; // rad/s
135  Vector3f ang_accel; // rad/s/s
136  Vector3f velocity_ef; // m/s, earth frame
137  Vector3f wind_ef; // m/s, earth frame
138  Vector3f velocity_air_ef; // velocity relative to airmass, earth frame
139  Vector3f velocity_air_bf; // velocity relative to airmass, body frame
140  Vector3f position; // meters, NED from origin
141  float mass; // kg
142  Vector3f accel_body; // m/s/s NED, body frame
143  float airspeed; // m/s, apparent airspeed
144  float airspeed_pitot; // m/s, apparent airspeed, as seen by fwd pitot tube
145  float battery_voltage = -1.0f;
146  float battery_current = 0.0f;
147  float rpm1 = 0;
148  float rpm2 = 0;
149  uint8_t rcin_chan_count = 0;
150  float rcin[8];
151  float range = -1.0f; // rangefinder detection in m
152 
153  // Wind Turbulence simulated Data
154  float turbulence_azimuth = 0.0f;
155  float turbulence_horizontal_speed = 0.0f; // m/s
156  float turbulence_vertical_speed = 0.0f; // m/s
157 
158  Vector3f mag_bf; // local earth magnetic field vector in Gauss, earth frame
159 
160  uint64_t time_now_us;
161 
162  const float gyro_noise;
163  const float accel_noise;
164  float rate_hz;
167  uint64_t frame_time_us;
170  uint8_t instance;
171  const char *autotest_dir;
172  const char *frame;
173  bool use_time_sync = true;
174  float last_speedup = -1.0f;
175 
176  // allow for AHRS_ORIENTATION
178 
179  enum {
184  } ground_behavior;
185 
187 
188  AP_Terrain *terrain;
189  float ground_height_difference() const;
190 
191  const float FEET_TO_METERS = 0.3048f;
192  const float KNOTS_TO_METERS_PER_SECOND = 0.51444f;
193 
194  virtual bool on_ground() const;
195 
196  // returns height above ground level in metres
197  float hagl() const; // metres
198 
199  /* update location from position */
200  void update_position(void);
201 
202  /* update body frame magnetic field */
203  void update_mag_field_bf(void);
204 
205  /* advance time by deltat in seconds */
206  void time_advance();
207 
208  /* setup the frame step time */
209  void setup_frame_time(float rate, float speedup);
210 
211  /* adjust frame_time calculation */
212  void adjust_frame_time(float rate);
213 
214  /* try to synchronise simulation time with wall clock time, taking
215  into account desired speedup */
216  void sync_frame_time(void);
217 
218  /* add noise based on throttle level (from 0..1) */
219  void add_noise(float throttle);
220 
221  /* return wall clock time in microseconds since 1970 */
222  uint64_t get_wall_time_us(void) const;
223 
224  // update attitude and relative position
225  void update_dynamics(const Vector3f &rot_accel);
226 
227  // update wind vector
228  void update_wind(const struct sitl_input &input);
229 
230  // return filtered servo input as -1 to 1 range
231  float filtered_idx(float v, uint8_t idx);
232  float filtered_servo_angle(const struct sitl_input &input, uint8_t idx);
233  float filtered_servo_range(const struct sitl_input &input, uint8_t idx);
234 
235  // extrapolate sensors by a given delta time in seconds
236  void extrapolate_sensors(float delta_time);
237 
238 private:
239  uint64_t last_time_us = 0;
240  uint32_t frame_counter = 0;
242  const uint32_t min_sleep_time;
243 
244  struct {
245  bool enabled;
247  Vector3f gyro;
251  uint64_t last_update_us;
253  } smoothing;
254 
256 };
257 
258 } // namespace SITL
Vector3f accel_body
Definition: SIM_Aircraft.h:142
Vector3f position
Definition: SIM_Aircraft.h:140
const Vector3f & get_gyro(void) const
Definition: SIM_Aircraft.h:94
Aircraft(const char *home_str, const char *frame_str)
void sync_frame_time(void)
struct SITL::Aircraft::@200 smoothing
void update_wind(const struct sitl_input &input)
LowPassFilterFloat servo_filter[4]
Definition: SIM_Aircraft.h:255
const Vector3f & get_position() const
Definition: SIM_Aircraft.h:118
float filtered_idx(float v, uint8_t idx)
const float gyro_noise
Definition: SIM_Aircraft.h:162
virtual float gross_mass() const
Definition: SIM_Aircraft.h:114
Vector3f velocity_air_ef
Definition: SIM_Aircraft.h:138
uint64_t last_time_us
Definition: SIM_Aircraft.h:239
struct SITL::Aircraft::sitl_input::@201 wind
const Vector3f & get_velocity_air_ef(void) const
Definition: SIM_Aircraft.h:102
float turbulence_horizontal_speed
Definition: SIM_Aircraft.h:155
void add_noise(float throttle)
float battery_voltage
Definition: SIM_Aircraft.h:145
void set_speedup(float speedup)
void setup_frame_time(float rate, float speedup)
float filtered_servo_range(const struct sitl_input &input, uint8_t idx)
uint8_t instance
Definition: SIM_Aircraft.h:170
Vector3f ang_accel
Definition: SIM_Aircraft.h:135
const uint32_t min_sleep_time
Definition: SIM_Aircraft.h:242
float turbulence_vertical_speed
Definition: SIM_Aircraft.h:156
void set_instance(uint8_t _instance)
Definition: SIM_Aircraft.h:60
float turbulence_azimuth
Definition: SIM_Aircraft.h:154
Location location
Definition: SIM_Aircraft.h:127
void from_rotation_matrix(const Matrix3f &m)
Definition: quaternion.cpp:76
float battery_current
Definition: SIM_Aircraft.h:146
uint64_t get_wall_time_us(void) const
const Vector3f & get_mag_field_bf(void) const
Definition: SIM_Aircraft.h:110
float hagl() const
float ground_height_difference() const
Vector3f mag_bf
Definition: SIM_Aircraft.h:158
virtual bool on_ground() const
static double rand_normal(double mean, double stddev)
Matrix3f rotation_b2e
Definition: SIM_Aircraft.h:248
float airspeed_pitot
Definition: SIM_Aircraft.h:144
AP_Int8 * ahrs_orientation
Definition: SIM_Aircraft.h:177
uint32_t last_ground_contact_ms
Definition: SIM_Aircraft.h:241
virtual void set_interface_ports(const char *address, const int port_in, const int port_out)
Definition: SIM_Aircraft.h:72
const float accel_noise
Definition: SIM_Aircraft.h:163
const char * autotest_dir
Definition: SIM_Aircraft.h:171
Vector3f velocity_ef
Definition: SIM_Aircraft.h:136
float get_rate_hz(void) const
Definition: SIM_Aircraft.h:92
const Vector3f & get_velocity_ef(void) const
Definition: SIM_Aircraft.h:98
uint64_t time_now_us
Definition: SIM_Aircraft.h:160
Vector3f velocity_air_bf
Definition: SIM_Aircraft.h:139
static bool parse_home(const char *home_str, Location &loc, float &yaw_degrees)
float achieved_rate_hz
Definition: SIM_Aircraft.h:165
float v
Definition: Printf.cpp:15
uint8_t rcin_chan_count
Definition: SIM_Aircraft.h:149
AP_Terrain * terrain
Definition: SIM_Aircraft.h:188
void set_autotest_dir(const char *_autotest_dir)
Definition: SIM_Aircraft.h:67
void adjust_frame_time(float rate)
void update_mag_field_bf(void)
uint64_t frame_time_us
Definition: SIM_Aircraft.h:167
void smooth_sensors(void)
uint64_t last_update_us
Definition: SIM_Aircraft.h:251
const Location & get_location() const
Definition: SIM_Aircraft.h:116
void update_position(void)
uint32_t frame_counter
Definition: SIM_Aircraft.h:240
void extrapolate_sensors(float delta_time)
virtual void update(const struct sitl_input &input)=0
void update_dynamics(const Vector3f &rot_accel)
void get_attitude(Quaternion &attitude) const
Definition: SIM_Aircraft.h:120
Vector3f gyro_prev
Definition: SIM_Aircraft.h:134
float scaled_frame_time_us
Definition: SIM_Aircraft.h:168
uint64_t last_wall_time_us
Definition: SIM_Aircraft.h:169
const float KNOTS_TO_METERS_PER_SECOND
Definition: SIM_Aircraft.h:192
float target_speedup
Definition: SIM_Aircraft.h:166
const float FEET_TO_METERS
Definition: SIM_Aircraft.h:191
const char * frame
Definition: SIM_Aircraft.h:172
void fill_fdm(struct sitl_fdm &fdm)
enum SITL::Aircraft::@199 ground_behavior
float filtered_servo_angle(const struct sitl_input &input, uint8_t idx)
Vector3f wind_ef
Definition: SIM_Aircraft.h:137
const Matrix3f & get_dcm(void) const
Definition: SIM_Aircraft.h:106