SITL.cpp 12 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306
  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. This program is distributed in the hope that it will be useful,
  7. but WITHOUT ANY WARRANTY; without even the implied warranty of
  8. MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  9. GNU General Public License for more details.
  10. You should have received a copy of the GNU General Public License
  11. along with this program. If not, see <http://www.gnu.org/licenses/>.
  12. */
  13. /*
  14. SITL.cpp - software in the loop state
  15. */
  16. #include "SITL.h"
  17. #include <AP_Common/AP_Common.h>
  18. #include <AP_HAL/AP_HAL.h>
  19. #include <GCS_MAVLink/GCS_MAVLink.h>
  20. #include <AP_Logger/AP_Logger.h>
  21. extern const AP_HAL::HAL& hal;
  22. namespace SITL {
  23. SITL *SITL::_singleton = nullptr;
  24. // table of user settable parameters
  25. const AP_Param::GroupInfo SITL::var_info[] = {
  26. AP_GROUPINFO("BARO_RND", 0, SITL, baro_noise, 0.2f),
  27. AP_GROUPINFO("GYR_RND", 1, SITL, gyro_noise, 0),
  28. AP_GROUPINFO("ACC_RND", 2, SITL, accel_noise, 0),
  29. AP_GROUPINFO("MAG_RND", 3, SITL, mag_noise, 0),
  30. AP_GROUPINFO("GPS_DISABLE",4, SITL, gps_disable, 0),
  31. AP_GROUPINFO("DRIFT_SPEED",5, SITL, drift_speed, 0.05f),
  32. AP_GROUPINFO("DRIFT_TIME", 6, SITL, drift_time, 5),
  33. AP_GROUPINFO("GPS_DELAY", 7, SITL, gps_delay, 1),
  34. AP_GROUPINFO("ENGINE_MUL", 8, SITL, engine_mul, 1),
  35. AP_GROUPINFO("WIND_SPD", 9, SITL, wind_speed, 0),
  36. AP_GROUPINFO("WIND_DIR", 10, SITL, wind_direction, 180),
  37. AP_GROUPINFO("WIND_TURB", 11, SITL, wind_turbulance, 0),
  38. AP_GROUPINFO("GPS_TYPE", 12, SITL, gps_type, SITL::GPS_TYPE_UBLOX),
  39. AP_GROUPINFO("GPS_BYTELOSS", 13, SITL, gps_byteloss, 0),
  40. AP_GROUPINFO("GPS_NUMSATS", 14, SITL, gps_numsats, 10),
  41. AP_GROUPINFO("MAG_ERROR", 15, SITL, mag_error, 0),
  42. AP_GROUPINFO("SERVO_SPEED", 16, SITL, servo_speed, 0.14),
  43. AP_GROUPINFO("GPS_GLITCH", 17, SITL, gps_glitch, 0),
  44. AP_GROUPINFO("GPS_HZ", 18, SITL, gps_hertz, 5),
  45. AP_GROUPINFO("BATT_VOLTAGE", 19, SITL, batt_voltage, 12.6f),
  46. AP_GROUPINFO("ARSPD_RND", 20, SITL, arspd_noise, 0.5f),
  47. AP_GROUPINFO("ACCEL_FAIL", 21, SITL, accel_fail, 0),
  48. AP_GROUPINFO("BARO_DRIFT", 22, SITL, baro_drift, 0),
  49. AP_GROUPINFO("SONAR_GLITCH", 23, SITL, sonar_glitch, 0),
  50. AP_GROUPINFO("SONAR_RND", 24, SITL, sonar_noise, 0),
  51. AP_GROUPINFO("RC_FAIL", 25, SITL, rc_fail, 0),
  52. AP_GROUPINFO("GPS2_ENABLE", 26, SITL, gps2_enable, 0),
  53. AP_GROUPINFO("BARO_DISABLE", 27, SITL, baro_disable, 0),
  54. AP_GROUPINFO("FLOAT_EXCEPT", 28, SITL, float_exception, 1),
  55. AP_GROUPINFO("MAG_MOT", 29, SITL, mag_mot, 0),
  56. AP_GROUPINFO("ACC_BIAS", 30, SITL, accel_bias, 0),
  57. AP_GROUPINFO("BARO_GLITCH", 31, SITL, baro_glitch, 0),
  58. AP_GROUPINFO("SONAR_SCALE", 32, SITL, sonar_scale, 12.1212f),
  59. AP_GROUPINFO("FLOW_ENABLE", 33, SITL, flow_enable, 0),
  60. AP_GROUPINFO("TERRAIN", 34, SITL, terrain_enable, 1),
  61. AP_GROUPINFO("FLOW_RATE", 35, SITL, flow_rate, 10),
  62. AP_GROUPINFO("FLOW_DELAY", 36, SITL, flow_delay, 0),
  63. AP_GROUPINFO("GPS_DRIFTALT", 37, SITL, gps_drift_alt, 0),
  64. AP_GROUPINFO("BARO_DELAY", 38, SITL, baro_delay, 0),
  65. AP_GROUPINFO("MAG_DELAY", 39, SITL, mag_delay, 0),
  66. AP_GROUPINFO("WIND_DELAY", 40, SITL, wind_delay, 0),
  67. AP_GROUPINFO("MAG_OFS", 41, SITL, mag_ofs, 0),
  68. AP_GROUPINFO("ACC2_RND", 42, SITL, accel2_noise, 0),
  69. AP_GROUPINFO("ARSPD_FAIL", 43, SITL, arspd_fail, 0),
  70. AP_GROUPINFO("GYR_SCALE", 44, SITL, gyro_scale, 0),
  71. AP_GROUPINFO("ADSB_COUNT", 45, SITL, adsb_plane_count, -1),
  72. AP_GROUPINFO("ADSB_RADIUS", 46, SITL, adsb_radius_m, 10000),
  73. AP_GROUPINFO("ADSB_ALT", 47, SITL, adsb_altitude_m, 1000),
  74. AP_GROUPINFO("MAG_ALY", 48, SITL, mag_anomaly_ned, 0),
  75. AP_GROUPINFO("MAG_ALY_HGT", 49, SITL, mag_anomaly_hgt, 1.0f),
  76. AP_GROUPINFO("PIN_MASK", 50, SITL, pin_mask, 0),
  77. AP_GROUPINFO("ADSB_TX", 51, SITL, adsb_tx, 0),
  78. AP_GROUPINFO("SPEEDUP", 52, SITL, speedup, -1),
  79. AP_GROUPINFO("IMU_POS", 53, SITL, imu_pos_offset, 0),
  80. AP_GROUPINFO("GPS_POS", 54, SITL, gps_pos_offset, 0),
  81. AP_GROUPINFO("SONAR_POS", 55, SITL, rngfnd_pos_offset, 0),
  82. AP_GROUPINFO("FLOW_POS", 56, SITL, optflow_pos_offset, 0),
  83. AP_GROUPINFO("ACC2_BIAS", 57, SITL, accel2_bias, 0),
  84. AP_GROUPINFO("GPS_NOISE", 58, SITL, gps_noise, 0),
  85. AP_GROUPINFO("GP2_GLITCH", 59, SITL, gps2_glitch, 0),
  86. AP_GROUPINFO("ENGINE_FAIL", 60, SITL, engine_fail, 0),
  87. AP_GROUPINFO("GPS2_TYPE", 61, SITL, gps2_type, SITL::GPS_TYPE_UBLOX),
  88. AP_GROUPINFO("ODOM_ENABLE", 62, SITL, odom_enable, 0),
  89. AP_SUBGROUPEXTENSION("", 63, SITL, var_info2),
  90. AP_GROUPEND
  91. };
  92. // second table of user settable parameters for SITL.
  93. const AP_Param::GroupInfo SITL::var_info2[] = {
  94. AP_GROUPINFO("TEMP_START", 1, SITL, temp_start, 25),
  95. AP_GROUPINFO("TEMP_FLIGHT", 2, SITL, temp_flight, 35),
  96. AP_GROUPINFO("TEMP_TCONST", 3, SITL, temp_tconst, 30),
  97. AP_GROUPINFO("TEMP_BFACTOR", 4, SITL, temp_baro_factor, 0),
  98. AP_GROUPINFO("GPS_LOCKTIME", 5, SITL, gps_lock_time, 0),
  99. AP_GROUPINFO("ARSPD_FAIL_P", 6, SITL, arspd_fail_pressure, 0),
  100. AP_GROUPINFO("ARSPD_PITOT", 7, SITL, arspd_fail_pitot_pressure, 0),
  101. AP_GROUPINFO("GPS_ALT_OFS", 8, SITL, gps_alt_offset, 0),
  102. AP_GROUPINFO("ARSPD_SIGN", 9, SITL, arspd_signflip, 0),
  103. AP_GROUPINFO("WIND_DIR_Z", 10, SITL, wind_dir_z, 0),
  104. AP_GROUPINFO("ARSPD2_FAIL", 11, SITL, arspd2_fail, 0),
  105. AP_GROUPINFO("ARSPD2_FAILP",12, SITL, arspd2_fail_pressure, 0),
  106. AP_GROUPINFO("ARSPD2_PITOT",13, SITL, arspd2_fail_pitot_pressure, 0),
  107. AP_GROUPINFO("VICON_HSTLEN",14, SITL, vicon_observation_history_length, 0),
  108. AP_GROUPINFO("WIND_T" ,15, SITL, wind_type, SITL::WIND_TYPE_SQRT),
  109. AP_GROUPINFO("WIND_T_ALT" ,16, SITL, wind_type_alt, 60),
  110. AP_GROUPINFO("WIND_T_COEF", 17, SITL, wind_type_coef, 0.01f),
  111. AP_GROUPINFO("MAG_DIA", 18, SITL, mag_diag, 0),
  112. AP_GROUPINFO("MAG_ODI", 19, SITL, mag_offdiag, 0),
  113. AP_GROUPINFO("MAG_ORIENT", 20, SITL, mag_orient, 0),
  114. AP_GROUPINFO("RC_CHANCOUNT",21, SITL, rc_chancount, 16),
  115. // @Group: SPR_
  116. // @Path: ./SIM_Sprayer.cpp
  117. AP_SUBGROUPINFO(sprayer_sim, "SPR_", 22, SITL, Sprayer),
  118. // @Group: GRPS_
  119. // @Path: ./SIM_Gripper_Servo.cpp
  120. AP_SUBGROUPINFO(gripper_sim, "GRPS_", 23, SITL, Gripper_Servo),
  121. // @Group: GRPE_
  122. // @Path: ./SIM_Gripper_EPM.cpp
  123. AP_SUBGROUPINFO(gripper_epm_sim, "GRPE_", 24, SITL, Gripper_EPM),
  124. // weight on wheels pin
  125. AP_GROUPINFO("WOW_PIN", 25, SITL, wow_pin, -1),
  126. // vibration frequencies on each axis
  127. AP_GROUPINFO("VIB_FREQ", 26, SITL, vibe_freq, 0),
  128. // @Path: ./SIM_Parachute.cpp
  129. AP_SUBGROUPINFO(parachute_sim, "PARA_", 27, SITL, Parachute),
  130. // enable bandwidth limitting on telemetry ports:
  131. AP_GROUPINFO("BAUDLIMIT_EN", 28, SITL, telem_baudlimit_enable, 0),
  132. // @Group: PLD_
  133. // @Path: ./SIM_Precland.cpp
  134. AP_SUBGROUPINFO(precland_sim, "PLD_", 29, SITL, SIM_Precland),
  135. // apply a force to the vehicle over a period of time:
  136. AP_GROUPINFO("SHOVE_X", 30, SITL, shove.x, 0),
  137. AP_GROUPINFO("SHOVE_Y", 31, SITL, shove.y, 0),
  138. AP_GROUPINFO("SHOVE_Z", 32, SITL, shove.z, 0),
  139. AP_GROUPINFO("SHOVE_TIME", 33, SITL, shove.t, 0),
  140. // optical flow sensor measurement noise in rad/sec
  141. AP_GROUPINFO("FLOW_RND", 34, SITL, flow_noise, 0.05f),
  142. // accel and gyro fail masks
  143. AP_GROUPINFO("GYR_FAIL_MSK", 35, SITL, gyro_fail_mask, 0),
  144. AP_GROUPINFO("ACC_FAIL_MSK", 36, SITL, accel_fail_mask, 0),
  145. AP_GROUPINFO("TWIST_X", 37, SITL, twist.x, 0),
  146. AP_GROUPINFO("TWIST_Y", 38, SITL, twist.y, 0),
  147. AP_GROUPINFO("TWIST_Z", 39, SITL, twist.z, 0),
  148. AP_GROUPINFO("TWIST_TIME", 40, SITL, twist.t, 0),
  149. AP_GROUPINFO("GND_BEHAV", 41, SITL, gnd_behav, -1),
  150. AP_GROUPINFO("BARO_COUNT", 42, SITL, baro_count, 1),
  151. AP_GROUPINFO("GPS_HDG", 43, SITL, gps_hdg_enabled, 0),
  152. // sailboat wave and tide simulation parameters
  153. AP_GROUPINFO("WAVE_ENABLE", 44, SITL, wave.enable, 0.0f),
  154. AP_GROUPINFO("WAVE_LENGTH", 45, SITL, wave.length, 10.0f),
  155. AP_GROUPINFO("WAVE_AMP", 46, SITL, wave.amp, 0.5f),
  156. AP_GROUPINFO("WAVE_DIR", 47, SITL, wave.direction, 0.0f),
  157. AP_GROUPINFO("WAVE_SPEED", 48, SITL, wave.speed, 0.5f),
  158. AP_GROUPINFO("TIDE_DIR", 49, SITL, tide.direction, 0.0f),
  159. AP_GROUPINFO("TIDE_SPEED", 50, SITL, tide.speed, 0.0f),
  160. // the following coordinates are for CMAC, in Canberra
  161. AP_GROUPINFO("OPOS_LAT", 51, SITL, opos.lat, -35.363261f),
  162. AP_GROUPINFO("OPOS_LNG", 52, SITL, opos.lng, 149.165230f),
  163. AP_GROUPINFO("OPOS_ALT", 53, SITL, opos.alt, 584.0f),
  164. AP_GROUPINFO("OPOS_HDG", 54, SITL, opos.hdg, 353.0f),
  165. // extra delay per main loop
  166. AP_GROUPINFO("LOOP_DELAY", 55, SITL, loop_delay, 0),
  167. AP_GROUPEND
  168. };
  169. /* report SITL state via MAVLink */
  170. void SITL::simstate_send(mavlink_channel_t chan)
  171. {
  172. float yaw;
  173. // convert to same conventions as DCM
  174. yaw = state.yawDeg;
  175. if (yaw > 180) {
  176. yaw -= 360;
  177. }
  178. mavlink_msg_simstate_send(chan,
  179. ToRad(state.rollDeg),
  180. ToRad(state.pitchDeg),
  181. ToRad(yaw),
  182. state.xAccel,
  183. state.yAccel,
  184. state.zAccel,
  185. radians(state.rollRate),
  186. radians(state.pitchRate),
  187. radians(state.yawRate),
  188. state.latitude*1.0e7,
  189. state.longitude*1.0e7);
  190. }
  191. /* report SITL state to AP_Logger */
  192. void SITL::Log_Write_SIMSTATE()
  193. {
  194. float yaw;
  195. // convert to same conventions as DCM
  196. yaw = state.yawDeg;
  197. if (yaw > 180) {
  198. yaw -= 360;
  199. }
  200. struct log_AHRS pkt = {
  201. LOG_PACKET_HEADER_INIT(LOG_SIMSTATE_MSG),
  202. time_us : AP_HAL::micros64(),
  203. roll : (int16_t)(state.rollDeg*100),
  204. pitch : (int16_t)(state.pitchDeg*100),
  205. yaw : (uint16_t)(wrap_360_cd(yaw*100)),
  206. alt : (float)state.altitude,
  207. lat : (int32_t)(state.latitude*1.0e7),
  208. lng : (int32_t)(state.longitude*1.0e7),
  209. q1 : state.quaternion.q1,
  210. q2 : state.quaternion.q2,
  211. q3 : state.quaternion.q3,
  212. q4 : state.quaternion.q4,
  213. };
  214. AP::logger().WriteBlock(&pkt, sizeof(pkt));
  215. }
  216. /*
  217. convert a set of roll rates from earth frame to body frame
  218. output values are in radians/second
  219. */
  220. void SITL::convert_body_frame(double rollDeg, double pitchDeg,
  221. double rollRate, double pitchRate, double yawRate,
  222. double *p, double *q, double *r)
  223. {
  224. double phi, theta, phiDot, thetaDot, psiDot;
  225. phi = ToRad(rollDeg);
  226. theta = ToRad(pitchDeg);
  227. phiDot = ToRad(rollRate);
  228. thetaDot = ToRad(pitchRate);
  229. psiDot = ToRad(yawRate);
  230. *p = phiDot - psiDot*sin(theta);
  231. *q = cos(phi)*thetaDot + sin(phi)*psiDot*cos(theta);
  232. *r = cos(phi)*psiDot*cos(theta) - sin(phi)*thetaDot;
  233. }
  234. /*
  235. convert angular velocities from body frame to
  236. earth frame.
  237. all inputs and outputs are in radians/s
  238. */
  239. Vector3f SITL::convert_earth_frame(const Matrix3f &dcm, const Vector3f &gyro)
  240. {
  241. float p = gyro.x;
  242. float q = gyro.y;
  243. float r = gyro.z;
  244. float phi, theta, psi;
  245. dcm.to_euler(&phi, &theta, &psi);
  246. float phiDot = p + tanf(theta)*(q*sinf(phi) + r*cosf(phi));
  247. float thetaDot = q*cosf(phi) - r*sinf(phi);
  248. if (fabsf(cosf(theta)) < 1.0e-20f) {
  249. theta += 1.0e-10f;
  250. }
  251. float psiDot = (q*sinf(phi) + r*cosf(phi))/cosf(theta);
  252. return Vector3f(phiDot, thetaDot, psiDot);
  253. }
  254. } // namespace SITL
  255. namespace AP {
  256. SITL::SITL *sitl()
  257. {
  258. return SITL::SITL::get_singleton();
  259. }
  260. };