APM:Libraries
SITL.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <AP_Math/AP_Math.h>
5 
6 class DataFlash_Class;
7 
8 namespace SITL {
9 
10 struct sitl_fdm {
11  // this is the structure passed between FDM models and the main SITL code
12  uint64_t timestamp_us;
14  double latitude, longitude; // degrees
15  double altitude; // MSL
16  double heading; // degrees
17  double speedN, speedE, speedD; // m/s
18  double xAccel, yAccel, zAccel; // m/s/s in body frame
19  double rollRate, pitchRate, yawRate; // degrees/s/s in body frame
20  double rollDeg, pitchDeg, yawDeg; // euler angles, degrees
22  double airspeed; // m/s
23  double battery_voltage; // Volts
24  double battery_current; // Amps
25  double rpm1; // main prop RPM
26  double rpm2; // secondary RPM
27  uint8_t rcin_chan_count;
28  float rcin[8]; // RC input 0..1
29  double range; // rangefinder value
30  Vector3f bodyMagField; // Truth XYZ magnetic field vector in body-frame. Includes motor interference. Units are milli-Gauss.
31  Vector3f angAccel; // Angular acceleration in degrees/s/s about the XYZ body axes
32 };
33 
34 // number of rc output channels
35 #define SITL_NUM_CHANNELS 16
36 
37 class SITL {
38 public:
39 
40  SITL() {
41  // set a default compass offset
42  mag_ofs.set(Vector3f(5, 13, -18));
43  AP_Param::setup_object_defaults(this, var_info);
44  AP_Param::setup_object_defaults(this, var_info2);
45  if (_s_instance != nullptr) {
46  AP_HAL::panic("Too many SITL instances");
47  }
48  _s_instance = this;
49  }
50 
51  /* Do not allow copies */
52  SITL(const SITL &other) = delete;
53  SITL &operator=(const SITL&) = delete;
54 
55  static SITL *_s_instance;
56  static SITL *get_instance() { return _s_instance; }
57 
58  enum GPSType {
59  GPS_TYPE_NONE = 0,
60  GPS_TYPE_UBLOX = 1,
61  GPS_TYPE_MTK = 2,
62  GPS_TYPE_MTK16 = 3,
63  GPS_TYPE_MTK19 = 4,
64  GPS_TYPE_NMEA = 5,
65  GPS_TYPE_SBP = 6,
66  GPS_TYPE_FILE = 7,
67  GPS_TYPE_NOVA = 8,
68  GPS_TYPE_SBP2 = 9,
69  };
70 
71  struct sitl_fdm state;
72 
73  // loop update rate in Hz
74  uint16_t update_rate_hz;
75 
76  // true when motors are active
77  bool motors_on;
78 
79  // height above ground
80  float height_agl;
81 
82  static const struct AP_Param::GroupInfo var_info[];
83  static const struct AP_Param::GroupInfo var_info2[];
84 
85  // noise levels for simulated sensors
86  AP_Float baro_noise; // in metres
87  AP_Float baro_drift; // in metres per second
88  AP_Float baro_glitch; // glitch in meters
89  AP_Float gyro_noise; // in degrees/second
90  AP_Vector3f gyro_scale; // percentage
91  AP_Float accel_noise; // in m/s/s
92  AP_Float accel2_noise; // in m/s/s
93  AP_Vector3f accel_bias; // in m/s/s
94  AP_Vector3f accel2_bias; // in m/s/s
95  AP_Float arspd_noise; // in m/s
96  AP_Float arspd_fail; // 1st pitot tube failure
97  AP_Float arspd2_fail; // 2nd pitot tube failure
98  AP_Float arspd_fail_pressure; // 1st pitot tube failure pressure
99  AP_Float arspd_fail_pitot_pressure; // 1st pitot tube failure pressure
100  AP_Float arspd2_fail_pressure; // 2nd pitot tube failure pressure
101  AP_Float arspd2_fail_pitot_pressure; // 2nd pitot tube failure pressure
102  AP_Float gps_noise; // amplitude of the gps altitude error
103  AP_Int16 gps_lock_time; // delay in seconds before GPS gets lock
104  AP_Int16 gps_alt_offset; // gps alt error
105  AP_Int8 vicon_observation_history_length; // frame delay for vicon messages
106 
107  AP_Float mag_noise; // in mag units (earth field is 818)
108  AP_Float mag_error; // in degrees
109  AP_Vector3f mag_mot; // in mag units per amp
110  AP_Vector3f mag_ofs; // in mag units
111  AP_Float servo_speed; // servo speed in seconds
112 
113  AP_Float sonar_glitch;// probablility between 0-1 that any given sonar sample will read as max distance
114  AP_Float sonar_noise; // in metres
115  AP_Float sonar_scale; // meters per volt
116 
117  AP_Float drift_speed; // degrees/second/minute
118  AP_Float drift_time; // period in minutes
119  AP_Float engine_mul; // engine multiplier
120  AP_Int8 engine_fail; // engine servo to fail (0-7)
121  AP_Int8 gps_disable; // disable simulated GPS
122  AP_Int8 gps2_enable; // enable 2nd simulated GPS
123  AP_Int8 gps_delay; // delay in samples
124  AP_Int8 gps_type; // see enum GPSType
125  AP_Int8 gps2_type; // see enum GPSType
126  AP_Float gps_byteloss;// byte loss as a percent
127  AP_Int8 gps_numsats; // number of visible satellites
128  AP_Vector3f gps_glitch; // glitch offsets in lat, lon and altitude
129  AP_Vector3f gps2_glitch; // glitch offsets in lat, lon and altitude for 2nd GPS
130  AP_Int8 gps_hertz; // GPS update rate in Hz
131  AP_Float batt_voltage; // battery voltage base
132  AP_Float accel_fail; // accelerometer failure value
133  AP_Int8 rc_fail; // fail RC input
134  AP_Int8 baro_disable; // disable simulated barometer
135  AP_Int8 float_exception; // enable floating point exception checks
136  AP_Int8 flow_enable; // enable simulated optflow
137  AP_Int16 flow_rate; // optflow data rate (Hz)
138  AP_Int8 flow_delay; // optflow data delay
139  AP_Int8 terrain_enable; // enable using terrain for height
140  AP_Int16 pin_mask; // for GPIO emulation
141  AP_Float speedup; // simulation speedup
142  AP_Int8 odom_enable; // enable visual odomotry data
143 
144  // wind control
145  enum WindType {
146  WIND_TYPE_SQRT = 0,
147  WIND_TYPE_NO_LIMIT = 1,
148  WIND_TYPE_COEF = 2,
149  };
150 
154  AP_Float wind_speed;
155  AP_Float wind_direction;
156  AP_Float wind_turbulance;
157  AP_Float gps_drift_alt;
158  AP_Float wind_dir_z;
159  AP_Int8 wind_type; // enum WindLimitType
160  AP_Float wind_type_alt;
161  AP_Float wind_type_coef;
162 
163  AP_Int16 baro_delay; // barometer data delay in ms
164  AP_Int16 mag_delay; // magnetometer data delay in ms
165  AP_Int16 wind_delay; // windspeed data delay in ms
166 
167  // ADSB related run-time options
169  AP_Float adsb_radius_m;
170  AP_Float adsb_altitude_m;
171  AP_Int8 adsb_tx;
172 
173  // Earth magnetic field anomaly
174  AP_Vector3f mag_anomaly_ned; // NED anomaly vector at ground level (mGauss)
175  AP_Float mag_anomaly_hgt; // height above ground where anomally strength has decayed to 1/8 of the ground level value (m)
176 
177  // Body frame sensor position offsets
178  AP_Vector3f imu_pos_offset; // XYZ position of the IMU accelerometer relative to the body frame origin (m)
179  AP_Vector3f gps_pos_offset; // XYZ position of the GPS antenna phase centre relative to the body frame origin (m)
180  AP_Vector3f rngfnd_pos_offset; // XYZ position of the range finder zero range datum relative to the body frame origin (m)
181  AP_Vector3f optflow_pos_offset; // XYZ position of the optical flow sensor focal point relative to the body frame origin (m)
182 
183  // temperature control
184  AP_Float temp_start;
185  AP_Float temp_flight;
186  AP_Float temp_tconst;
188 
189  // differential pressure sensor tube order
190  AP_Int8 arspd_signflip;
191 
192  uint16_t irlock_port;
193 
194  void simstate_send(mavlink_channel_t chan);
195 
196  void Log_Write_SIMSTATE(DataFlash_Class *dataflash);
197 
198  // convert a set of roll rates from earth frame to body frame
199  static void convert_body_frame(double rollDeg, double pitchDeg,
200  double rollRate, double pitchRate, double yawRate,
201  double *p, double *q, double *r);
202 
203  // convert a set of roll rates from body frame to earth frame
204  static Vector3f convert_earth_frame(const Matrix3f &dcm, const Vector3f &gyro);
205 };
206 
207 } // namespace SITL
208 
209 
210 namespace AP {
211  SITL::SITL *sitl();
212 };
double range
Definition: SITL.h:29
AP_Int8 wind_type
Definition: SITL.h:159
AP_Vector3f mag_anomaly_ned
Definition: SITL.h:174
AP_Int8 baro_disable
Definition: SITL.h:134
float rcin[8]
Definition: SITL.h:28
AP_Int8 gps_hertz
Definition: SITL.h:130
AP_Int8 adsb_tx
Definition: SITL.h:171
uint64_t timestamp_us
Definition: SITL.h:12
AP_Int16 adsb_plane_count
Definition: SITL.h:168
Vector3< float > Vector3f
Definition: vector3.h:246
AP_Vector3f gps2_glitch
Definition: SITL.h:129
AP_Float baro_glitch
Definition: SITL.h:88
AP_Float adsb_altitude_m
Definition: SITL.h:170
static SITL * _s_instance
Definition: SITL.h:55
AP_Int8 gps2_enable
Definition: SITL.h:122
AP_Int8 gps_delay
Definition: SITL.h:123
double pitchDeg
Definition: SITL.h:20
double xAccel
Definition: SITL.h:18
uint16_t update_rate_hz
Definition: SITL.h:74
float wind_dir_z_active
Definition: SITL.h:153
uint16_t irlock_port
Definition: SITL.h:192
AP_Vector3f gps_glitch
Definition: SITL.h:128
AP_Float arspd2_fail_pressure
Definition: SITL.h:100
float height_agl
Definition: SITL.h:80
AP_Float arspd_fail
Definition: SITL.h:96
uint8_t rcin_chan_count
Definition: SITL.h:27
Vector3f angAccel
Definition: SITL.h:31
AP_Float adsb_radius_m
Definition: SITL.h:169
AP_Float sonar_scale
Definition: SITL.h:115
Quaternion quaternion
Definition: SITL.h:21
AP_Float wind_turbulance
Definition: SITL.h:156
Vector3f bodyMagField
Definition: SITL.h:30
double longitude
Definition: SITL.h:14
double speedE
Definition: SITL.h:17
AP_Float mag_noise
Definition: SITL.h:107
AP_Vector3f mag_mot
Definition: SITL.h:109
AP_Int16 gps_lock_time
Definition: SITL.h:103
AP_Vector3f imu_pos_offset
Definition: SITL.h:178
AP_Int8 rc_fail
Definition: SITL.h:133
AP_Vector3f accel2_bias
Definition: SITL.h:94
AP_Int8 arspd_signflip
Definition: SITL.h:190
bool motors_on
Definition: SITL.h:77
AP_Float mag_anomaly_hgt
Definition: SITL.h:175
AP_Int8 odom_enable
Definition: SITL.h:142
double airspeed
Definition: SITL.h:22
AP_Float wind_direction
Definition: SITL.h:155
double rpm1
Definition: SITL.h:25
double rollRate
Definition: SITL.h:19
AP_Float arspd_fail_pressure
Definition: SITL.h:98
double battery_current
Definition: SITL.h:24
AP_Float sonar_noise
Definition: SITL.h:114
AP_Int8 float_exception
Definition: SITL.h:135
double speedD
Definition: SITL.h:17
Location home
Definition: SITL.h:13
AP_Float wind_speed
Definition: SITL.h:154
AP_Float wind_type_coef
Definition: SITL.h:161
SITL::SITL * sitl()
Definition: SITL.cpp:229
AP_Int16 pin_mask
Definition: SITL.h:140
AP_Float temp_baro_factor
Definition: SITL.h:187
AP_Float mag_error
Definition: SITL.h:108
double yawRate
Definition: SITL.h:19
AP_Int16 flow_rate
Definition: SITL.h:137
AP_Float engine_mul
Definition: SITL.h:119
AP_Vector3f gyro_scale
Definition: SITL.h:90
double rollDeg
Definition: SITL.h:20
Definition: AP_AHRS.cpp:486
double heading
Definition: SITL.h:16
AP_Float arspd_noise
Definition: SITL.h:95
float wind_direction_active
Definition: SITL.h:152
SITL()
Definition: SITL.h:40
AP_Vector3f gps_pos_offset
Definition: SITL.h:179
AP_Float wind_type_alt
Definition: SITL.h:160
double yawDeg
Definition: SITL.h:20
AP_Float gyro_noise
Definition: SITL.h:89
AP_Float temp_tconst
Definition: SITL.h:186
double yAccel
Definition: SITL.h:18
double speedN
Definition: SITL.h:17
AP_Float drift_speed
Definition: SITL.h:117
AP_Float wind_dir_z
Definition: SITL.h:158
static int state
Definition: Util.cpp:20
GPSType
Definition: SITL.h:58
AP_Float baro_noise
Definition: SITL.h:86
double zAccel
Definition: SITL.h:18
AP_Float temp_flight
Definition: SITL.h:185
AP_Float gps_byteloss
Definition: SITL.h:126
AP_Int8 flow_delay
Definition: SITL.h:138
AP_Float accel_noise
Definition: SITL.h:91
AP_Float arspd2_fail
Definition: SITL.h:97
AP_Float servo_speed
Definition: SITL.h:111
double rpm2
Definition: SITL.h:26
AP_Vector3f optflow_pos_offset
Definition: SITL.h:181
AP_Int8 terrain_enable
Definition: SITL.h:139
AP_Int8 engine_fail
Definition: SITL.h:120
AP_Float gps_noise
Definition: SITL.h:102
AP_Float baro_drift
Definition: SITL.h:87
AP_Vector3f accel_bias
Definition: SITL.h:93
WindType
Definition: SITL.h:145
AP_Float sonar_glitch
Definition: SITL.h:113
double pitchRate
Definition: SITL.h:19
float wind_speed_active
Definition: SITL.h:151
AP_Float gps_drift_alt
Definition: SITL.h:157
AP_HAL::AnalogSource * chan
Definition: AnalogIn.cpp:8
AP_Float arspd2_fail_pitot_pressure
Definition: SITL.h:101
AP_Float accel2_noise
Definition: SITL.h:92
AP_Int8 vicon_observation_history_length
Definition: SITL.h:105
AP_Int16 gps_alt_offset
Definition: SITL.h:104
AP_Float speedup
Definition: SITL.h:141
double latitude
Definition: SITL.h:14
AP_Float temp_start
Definition: SITL.h:184
AP_Int8 gps_numsats
Definition: SITL.h:127
AP_Int8 gps_disable
Definition: SITL.h:121
AP_Float arspd_fail_pitot_pressure
Definition: SITL.h:99
AP_Float drift_time
Definition: SITL.h:118
void panic(const char *errormsg,...) FMT_PRINTF(1
Definition: system.cpp:140
AP_Vector3f rngfnd_pos_offset
Definition: SITL.h:180
AP_Float batt_voltage
Definition: SITL.h:131
AP_Float accel_fail
Definition: SITL.h:132
AP_Int8 flow_enable
Definition: SITL.h:136
static SITL * get_instance()
Definition: SITL.h:56
AP_Int16 mag_delay
Definition: SITL.h:164
double altitude
Definition: SITL.h:15
AP_Int16 baro_delay
Definition: SITL.h:163
AP_Vector3f mag_ofs
Definition: SITL.h:110
double battery_voltage
Definition: SITL.h:23
AP_Int16 wind_delay
Definition: SITL.h:165
AP_Int8 gps_type
Definition: SITL.h:124
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
Definition: AP_Param.cpp:1214
AP_Int8 gps2_type
Definition: SITL.h:125