SITL.h 9.9 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308
  1. #pragma once
  2. #include <AP_Math/AP_Math.h>
  3. #include <GCS_MAVLink/GCS_MAVLink.h>
  4. #include <AP_Common/Location.h>
  5. #include "SIM_Sprayer.h"
  6. #include "SIM_Gripper_Servo.h"
  7. #include "SIM_Gripper_EPM.h"
  8. #include "SIM_Parachute.h"
  9. #include "SIM_Precland.h"
  10. namespace SITL {
  11. struct vector3f_array {
  12. uint16_t length;
  13. Vector3f *data;
  14. };
  15. struct float_array {
  16. uint16_t length;
  17. float *data;
  18. };
  19. struct sitl_fdm {
  20. // this is the structure passed between FDM models and the main SITL code
  21. uint64_t timestamp_us;
  22. Location home;
  23. double latitude, longitude; // degrees
  24. double altitude; // MSL
  25. double heading; // degrees
  26. double speedN, speedE, speedD; // m/s
  27. double xAccel, yAccel, zAccel; // m/s/s in body frame
  28. double rollRate, pitchRate, yawRate; // degrees/s/s in body frame
  29. double rollDeg, pitchDeg, yawDeg; // euler angles, degrees
  30. Quaternion quaternion;
  31. double airspeed; // m/s
  32. double battery_voltage; // Volts
  33. double battery_current; // Amps
  34. double rpm1; // main prop RPM
  35. double rpm2; // secondary RPM
  36. uint8_t rcin_chan_count;
  37. float rcin[8]; // RC input 0..1
  38. double range; // rangefinder value
  39. Vector3f bodyMagField; // Truth XYZ magnetic field vector in body-frame. Includes motor interference. Units are milli-Gauss.
  40. Vector3f angAccel; // Angular acceleration in degrees/s/s about the XYZ body axes
  41. struct {
  42. // data from simulated laser scanner, if available
  43. struct vector3f_array points;
  44. struct float_array ranges;
  45. } scanner;
  46. };
  47. // number of rc output channels
  48. #define SITL_NUM_CHANNELS 16
  49. class SITL {
  50. public:
  51. SITL() {
  52. // set a default compass offset
  53. mag_ofs.set(Vector3f(5, 13, -18));
  54. AP_Param::setup_object_defaults(this, var_info);
  55. AP_Param::setup_object_defaults(this, var_info2);
  56. if (_singleton != nullptr) {
  57. AP_HAL::panic("Too many SITL instances");
  58. }
  59. _singleton = this;
  60. }
  61. /* Do not allow copies */
  62. SITL(const SITL &other) = delete;
  63. SITL &operator=(const SITL&) = delete;
  64. static SITL *_singleton;
  65. static SITL *get_singleton() { return _singleton; }
  66. enum SITL_RCFail {
  67. SITL_RCFail_None = 0,
  68. SITL_RCFail_NoPulses = 1,
  69. SITL_RCFail_Throttle950 = 2,
  70. };
  71. enum GPSType {
  72. GPS_TYPE_NONE = 0,
  73. GPS_TYPE_UBLOX = 1,
  74. GPS_TYPE_MTK = 2,
  75. GPS_TYPE_MTK16 = 3,
  76. GPS_TYPE_MTK19 = 4,
  77. GPS_TYPE_NMEA = 5,
  78. GPS_TYPE_SBP = 6,
  79. GPS_TYPE_FILE = 7,
  80. GPS_TYPE_NOVA = 8,
  81. GPS_TYPE_SBP2 = 9,
  82. };
  83. struct sitl_fdm state;
  84. // loop update rate in Hz
  85. uint16_t update_rate_hz;
  86. // true when motors are active
  87. bool motors_on;
  88. // height above ground
  89. float height_agl;
  90. static const struct AP_Param::GroupInfo var_info[];
  91. static const struct AP_Param::GroupInfo var_info2[];
  92. // noise levels for simulated sensors
  93. AP_Float baro_noise; // in metres
  94. AP_Float baro_drift; // in metres per second
  95. AP_Float baro_glitch; // glitch in meters
  96. AP_Float gyro_noise; // in degrees/second
  97. AP_Vector3f gyro_scale; // percentage
  98. AP_Float accel_noise; // in m/s/s
  99. AP_Float accel2_noise; // in m/s/s
  100. AP_Vector3f accel_bias; // in m/s/s
  101. AP_Vector3f accel2_bias; // in m/s/s
  102. AP_Float arspd_noise; // in m/s
  103. AP_Float arspd_fail; // 1st pitot tube failure
  104. AP_Float arspd2_fail; // 2nd pitot tube failure
  105. AP_Float arspd_fail_pressure; // 1st pitot tube failure pressure
  106. AP_Float arspd_fail_pitot_pressure; // 1st pitot tube failure pressure
  107. AP_Float arspd2_fail_pressure; // 2nd pitot tube failure pressure
  108. AP_Float arspd2_fail_pitot_pressure; // 2nd pitot tube failure pressure
  109. AP_Float gps_noise; // amplitude of the gps altitude error
  110. AP_Int16 gps_lock_time; // delay in seconds before GPS gets lock
  111. AP_Int16 gps_alt_offset; // gps alt error
  112. AP_Int8 vicon_observation_history_length; // frame delay for vicon messages
  113. AP_Float mag_noise; // in mag units (earth field is 818)
  114. AP_Float mag_error; // in degrees
  115. AP_Vector3f mag_mot; // in mag units per amp
  116. AP_Vector3f mag_ofs; // in mag units
  117. AP_Vector3f mag_diag; // diagonal corrections
  118. AP_Vector3f mag_offdiag; // off-diagonal corrections
  119. AP_Int8 mag_orient; // external compass orientation
  120. AP_Float servo_speed; // servo speed in seconds
  121. AP_Float sonar_glitch;// probablility between 0-1 that any given sonar sample will read as max distance
  122. AP_Float sonar_noise; // in metres
  123. AP_Float sonar_scale; // meters per volt
  124. AP_Float drift_speed; // degrees/second/minute
  125. AP_Float drift_time; // period in minutes
  126. AP_Float engine_mul; // engine multiplier
  127. AP_Int8 engine_fail; // engine servo to fail (0-7)
  128. AP_Int8 gps_disable; // disable simulated GPS
  129. AP_Int8 gps2_enable; // enable 2nd simulated GPS
  130. AP_Int8 gps_delay; // delay in samples
  131. AP_Int8 gps_type; // see enum GPSType
  132. AP_Int8 gps2_type; // see enum GPSType
  133. AP_Float gps_byteloss;// byte loss as a percent
  134. AP_Int8 gps_numsats; // number of visible satellites
  135. AP_Vector3f gps_glitch; // glitch offsets in lat, lon and altitude
  136. AP_Vector3f gps2_glitch; // glitch offsets in lat, lon and altitude for 2nd GPS
  137. AP_Int8 gps_hertz; // GPS update rate in Hz
  138. AP_Float batt_voltage; // battery voltage base
  139. AP_Float accel_fail; // accelerometer failure value
  140. AP_Int8 rc_fail; // fail RC input
  141. AP_Int8 rc_chancount; // channel count
  142. AP_Int8 baro_disable; // disable simulated barometer
  143. AP_Int8 float_exception; // enable floating point exception checks
  144. AP_Int8 flow_enable; // enable simulated optflow
  145. AP_Int16 flow_rate; // optflow data rate (Hz)
  146. AP_Int8 flow_delay; // optflow data delay
  147. AP_Int8 terrain_enable; // enable using terrain for height
  148. AP_Int16 pin_mask; // for GPIO emulation
  149. AP_Float speedup; // simulation speedup
  150. AP_Int8 odom_enable; // enable visual odomotry data
  151. AP_Int8 telem_baudlimit_enable; // enable baudrate limiting on links
  152. AP_Float flow_noise; // optical flow measurement noise (rad/sec)
  153. AP_Int8 baro_count; // number of simulated baros to create
  154. AP_Int8 gps_hdg_enabled; // enable the output of a NMEA heading HDT sentence
  155. AP_Int32 loop_delay; // extra delay to add to every loop
  156. // wind control
  157. enum WindType {
  158. WIND_TYPE_SQRT = 0,
  159. WIND_TYPE_NO_LIMIT = 1,
  160. WIND_TYPE_COEF = 2,
  161. };
  162. float wind_speed_active;
  163. float wind_direction_active;
  164. float wind_dir_z_active;
  165. AP_Float wind_speed;
  166. AP_Float wind_direction;
  167. AP_Float wind_turbulance;
  168. AP_Float gps_drift_alt;
  169. AP_Float wind_dir_z;
  170. AP_Int8 wind_type; // enum WindLimitType
  171. AP_Float wind_type_alt;
  172. AP_Float wind_type_coef;
  173. AP_Int16 baro_delay; // barometer data delay in ms
  174. AP_Int16 mag_delay; // magnetometer data delay in ms
  175. AP_Int16 wind_delay; // windspeed data delay in ms
  176. // ADSB related run-time options
  177. AP_Int16 adsb_plane_count;
  178. AP_Float adsb_radius_m;
  179. AP_Float adsb_altitude_m;
  180. AP_Int8 adsb_tx;
  181. // Earth magnetic field anomaly
  182. AP_Vector3f mag_anomaly_ned; // NED anomaly vector at ground level (mGauss)
  183. AP_Float mag_anomaly_hgt; // height above ground where anomally strength has decayed to 1/8 of the ground level value (m)
  184. // Body frame sensor position offsets
  185. AP_Vector3f imu_pos_offset; // XYZ position of the IMU accelerometer relative to the body frame origin (m)
  186. AP_Vector3f gps_pos_offset; // XYZ position of the GPS antenna phase centre relative to the body frame origin (m)
  187. AP_Vector3f rngfnd_pos_offset; // XYZ position of the range finder zero range datum relative to the body frame origin (m)
  188. AP_Vector3f optflow_pos_offset; // XYZ position of the optical flow sensor focal point relative to the body frame origin (m)
  189. // temperature control
  190. AP_Float temp_start;
  191. AP_Float temp_flight;
  192. AP_Float temp_tconst;
  193. AP_Float temp_baro_factor;
  194. // differential pressure sensor tube order
  195. AP_Int8 arspd_signflip;
  196. // weight on wheels pin
  197. AP_Int8 wow_pin;
  198. // vibration frequencies in Hz on each axis
  199. AP_Vector3f vibe_freq;
  200. // gyro and accel fail masks
  201. AP_Int8 gyro_fail_mask;
  202. AP_Int8 accel_fail_mask;
  203. struct {
  204. AP_Float x;
  205. AP_Float y;
  206. AP_Float z;
  207. AP_Int32 t;
  208. uint32_t start_ms;
  209. } shove;
  210. struct {
  211. AP_Float x;
  212. AP_Float y;
  213. AP_Float z;
  214. AP_Int32 t;
  215. uint32_t start_ms;
  216. } twist;
  217. AP_Int8 gnd_behav;
  218. struct {
  219. AP_Int8 enable; // 0: disabled, 1: roll and pitch, 2: roll, pitch and heave
  220. AP_Float length; // m
  221. AP_Float amp; // m
  222. AP_Float direction; // deg (direction wave is coming from)
  223. AP_Float speed; // m/s
  224. } wave;
  225. struct {
  226. AP_Float direction; // deg (direction tide is coming from)
  227. AP_Float speed; // m/s
  228. } tide;
  229. // original simulated position
  230. struct {
  231. AP_Float lat;
  232. AP_Float lng;
  233. AP_Float alt; // metres
  234. AP_Float hdg; // 0 to 360
  235. } opos;
  236. uint16_t irlock_port;
  237. void simstate_send(mavlink_channel_t chan);
  238. void Log_Write_SIMSTATE();
  239. // convert a set of roll rates from earth frame to body frame
  240. static void convert_body_frame(double rollDeg, double pitchDeg,
  241. double rollRate, double pitchRate, double yawRate,
  242. double *p, double *q, double *r);
  243. // convert a set of roll rates from body frame to earth frame
  244. static Vector3f convert_earth_frame(const Matrix3f &dcm, const Vector3f &gyro);
  245. Sprayer sprayer_sim;
  246. Gripper_Servo gripper_sim;
  247. Gripper_EPM gripper_epm_sim;
  248. Parachute parachute_sim;
  249. SIM_Precland precland_sim;
  250. };
  251. } // namespace SITL
  252. namespace AP {
  253. SITL::SITL *sitl();
  254. };