AP_Soaring.cpp 12 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336
  1. #include "AP_Soaring.h"
  2. #include <AP_Logger/AP_Logger.h>
  3. #include <GCS_MAVLink/GCS.h>
  4. #include <stdint.h>
  5. extern const AP_HAL::HAL& hal;
  6. // ArduSoar parameters
  7. const AP_Param::GroupInfo SoaringController::var_info[] = {
  8. // @Param: ENABLE
  9. // @DisplayName: Is the soaring mode enabled or not
  10. // @Description: Toggles the soaring mode on and off
  11. // @Values: 0:Disable,1:Enable
  12. // @User: Advanced
  13. AP_GROUPINFO_FLAGS("ENABLE", 1, SoaringController, soar_active, 0, AP_PARAM_FLAG_ENABLE),
  14. // @Param: VSPEED
  15. // @DisplayName: Vertical v-speed
  16. // @Description: Rate of climb to trigger themalling speed
  17. // @Units: m/s
  18. // @Range: 0 10
  19. // @User: Advanced
  20. AP_GROUPINFO("VSPEED", 2, SoaringController, thermal_vspeed, 0.7f),
  21. // @Param: Q1
  22. // @DisplayName: Process noise
  23. // @Description: Standard deviation of noise in process for strength
  24. // @Units:
  25. // @Range: 0 10
  26. // @User: Advanced
  27. AP_GROUPINFO("Q1", 3, SoaringController, thermal_q1, 0.001f),
  28. // @Param: Q2
  29. // @DisplayName: Process noise
  30. // @Description: Standard deviation of noise in process for position and radius
  31. // @Units:
  32. // @Range: 0 10
  33. // @User: Advanced
  34. AP_GROUPINFO("Q2", 4, SoaringController, thermal_q2, 0.03f),
  35. // @Param: R
  36. // @DisplayName: Measurement noise
  37. // @Description: Standard deviation of noise in measurement
  38. // @Units:
  39. // @Range: 0 10
  40. // @User: Advanced
  41. AP_GROUPINFO("R", 5, SoaringController, thermal_r, 0.45f),
  42. // @Param: DIST_AHEAD
  43. // @DisplayName: Distance to thermal center
  44. // @Description: Initial guess of the distance to the thermal center
  45. // @Units: m
  46. // @Range: 0 100
  47. // @User: Advanced
  48. AP_GROUPINFO("DIST_AHEAD", 6, SoaringController, thermal_distance_ahead, 5.0f),
  49. // @Param: MIN_THML_S
  50. // @DisplayName: Minimum thermalling time
  51. // @Description: Minimum number of seconds to spend thermalling
  52. // @Units: s
  53. // @Range: 0 32768
  54. // @User: Advanced
  55. AP_GROUPINFO("MIN_THML_S", 7, SoaringController, min_thermal_s, 20),
  56. // @Param: MIN_CRSE_S
  57. // @DisplayName: Minimum cruising time
  58. // @Description: Minimum number of seconds to spend cruising
  59. // @Units: s
  60. // @Range: 0 32768
  61. // @User: Advanced
  62. AP_GROUPINFO("MIN_CRSE_S", 8, SoaringController, min_cruise_s, 30),
  63. // @Param: POLAR_CD0
  64. // @DisplayName: Zero lift drag coef.
  65. // @Description: Zero lift drag coefficient
  66. // @Units:
  67. // @Range: 0 0.5
  68. // @User: Advanced
  69. AP_GROUPINFO("POLAR_CD0", 9, SoaringController, polar_CD0, 0.027),
  70. // @Param: POLAR_B
  71. // @DisplayName: Induced drag coeffient
  72. // @Description: Induced drag coeffient
  73. // @Units:
  74. // @Range: 0 0.5
  75. // @User: Advanced
  76. AP_GROUPINFO("POLAR_B", 10, SoaringController, polar_B, 0.031),
  77. // @Param: POLAR_K
  78. // @DisplayName: Cl factor
  79. // @Description: Cl factor 2*m*g/(rho*S)
  80. // @Units: m.m/s/s
  81. // @Range: 0 0.5
  82. // @User: Advanced
  83. AP_GROUPINFO("POLAR_K", 11, SoaringController, polar_K, 25.6),
  84. // @Param: ALT_MAX
  85. // @DisplayName: Maximum soaring altitude, relative to the home location
  86. // @Description: Don't thermal any higher than this.
  87. // @Units: m
  88. // @Range: 0 1000.0
  89. // @User: Advanced
  90. AP_GROUPINFO("ALT_MAX", 12, SoaringController, alt_max, 350.0),
  91. // @Param: ALT_MIN
  92. // @DisplayName: Minimum soaring altitude, relative to the home location
  93. // @Description: Don't get any lower than this.
  94. // @Units: m
  95. // @Range: 0 1000.0
  96. // @User: Advanced
  97. AP_GROUPINFO("ALT_MIN", 13, SoaringController, alt_min, 50.0),
  98. // @Param: ALT_CUTOFF
  99. // @DisplayName: Maximum power altitude, relative to the home location
  100. // @Description: Cut off throttle at this alt.
  101. // @Units: m
  102. // @Range: 0 1000.0
  103. // @User: Advanced
  104. AP_GROUPINFO("ALT_CUTOFF", 14, SoaringController, alt_cutoff, 250.0),
  105. // @Param: ENABLE_CH
  106. // @DisplayName: (Optional) RC channel that toggles the soaring controller on and off
  107. // @Description: Toggles the soaring controller on and off. This parameter has any effect only if SOAR_ENABLE is set to 1 and this parameter is set to a valid non-zero channel number. When set, soaring will be activated when RC input to the specified channel is greater than or equal to 1700.
  108. // @Range: 0 16
  109. // @User: Advanced
  110. AP_GROUPINFO("ENABLE_CH", 15, SoaringController, soar_active_ch, 0),
  111. AP_GROUPEND
  112. };
  113. SoaringController::SoaringController(AP_AHRS &ahrs, AP_SpdHgtControl &spdHgt, const AP_Vehicle::FixedWing &parms) :
  114. _ahrs(ahrs),
  115. _spdHgt(spdHgt),
  116. _vario(ahrs,parms),
  117. _loiter_rad(parms.loiter_radius),
  118. _throttle_suppressed(true)
  119. {
  120. AP_Param::setup_object_defaults(this, var_info);
  121. }
  122. void SoaringController::get_target(Location &wp)
  123. {
  124. wp = _prev_update_location;
  125. wp.offset(_ekf.X[2], _ekf.X[3]);
  126. }
  127. bool SoaringController::suppress_throttle()
  128. {
  129. float alt = 0;
  130. get_altitude_wrt_home(&alt);
  131. if (_throttle_suppressed && (alt < alt_min)) {
  132. // Time to throttle up
  133. _throttle_suppressed = false;
  134. } else if ((!_throttle_suppressed) && (alt > alt_cutoff)) {
  135. // Start glide
  136. _throttle_suppressed = true;
  137. // Zero the pitch integrator - the nose is currently raised to climb, we need to go back to glide.
  138. _spdHgt.reset_pitch_I();
  139. _cruise_start_time_us = AP_HAL::micros64();
  140. // Reset the filtered vario rate - it is currently elevated due to the climb rate and would otherwise take a while to fall again,
  141. // leading to false positives.
  142. _vario.filtered_reading = 0;
  143. }
  144. return _throttle_suppressed;
  145. }
  146. bool SoaringController::check_thermal_criteria()
  147. {
  148. return (soar_active
  149. && ((AP_HAL::micros64() - _cruise_start_time_us) > ((unsigned)min_cruise_s * 1e6))
  150. && _vario.filtered_reading > thermal_vspeed
  151. && _vario.alt < alt_max
  152. && _vario.alt > alt_min);
  153. }
  154. bool SoaringController::check_cruise_criteria()
  155. {
  156. float thermalability = (_ekf.X[0]*expf(-powf(_loiter_rad / _ekf.X[1], 2))) - EXPECTED_THERMALLING_SINK;
  157. float alt = _vario.alt;
  158. if (soar_active && (AP_HAL::micros64() - _thermal_start_time_us) > ((unsigned)min_thermal_s * 1e6) && thermalability < McCready(alt)) {
  159. gcs().send_text(MAV_SEVERITY_INFO, "Thermal weak, recommend quitting: W %f R %f th %f alt %f Mc %f", (double)_ekf.X[0], (double)_ekf.X[1], (double)thermalability, (double)alt, (double)McCready(alt));
  160. return true;
  161. } else if (soar_active && (alt>alt_max || alt<alt_min)) {
  162. gcs().send_text(MAV_SEVERITY_ALERT, "Out of allowable altitude range, beginning cruise. Alt = %f", (double)alt);
  163. return true;
  164. }
  165. return false;
  166. }
  167. bool SoaringController::check_init_thermal_criteria()
  168. {
  169. if (soar_active && (AP_HAL::micros64() - _thermal_start_time_us) < ((unsigned)min_thermal_s * 1e6)) {
  170. return true;
  171. }
  172. return false;
  173. }
  174. void SoaringController::init_thermalling()
  175. {
  176. // Calc filter matrices - so that changes to parameters can be updated by switching in and out of thermal mode
  177. float r = powf(thermal_r, 2);
  178. float cov_q1 = powf(thermal_q1, 2); // State covariance
  179. float cov_q2 = powf(thermal_q2, 2); // State covariance
  180. const float init_q[4] = {cov_q1, cov_q2, cov_q2, cov_q2};
  181. const MatrixN<float,4> q{init_q};
  182. const float init_p[4] = {INITIAL_STRENGTH_COVARIANCE, INITIAL_RADIUS_COVARIANCE, INITIAL_POSITION_COVARIANCE, INITIAL_POSITION_COVARIANCE};
  183. const MatrixN<float,4> p{init_p};
  184. // New state vector filter will be reset. Thermal location is placed in front of a/c
  185. const float init_xr[4] = {INITIAL_THERMAL_STRENGTH,
  186. INITIAL_THERMAL_RADIUS,
  187. thermal_distance_ahead * cosf(_ahrs.yaw),
  188. thermal_distance_ahead * sinf(_ahrs.yaw)};
  189. const VectorN<float,4> xr{init_xr};
  190. // Also reset covariance matrix p so filter is not affected by previous data
  191. _ekf.reset(xr, p, q, r);
  192. _ahrs.get_position(_prev_update_location);
  193. _prev_update_time = AP_HAL::micros64();
  194. _thermal_start_time_us = AP_HAL::micros64();
  195. }
  196. void SoaringController::init_cruising()
  197. {
  198. if (is_active() && suppress_throttle()) {
  199. _cruise_start_time_us = AP_HAL::micros64();
  200. // Start glide. Will be updated on the next loop.
  201. _throttle_suppressed = true;
  202. }
  203. }
  204. void SoaringController::get_wind_corrected_drift(const Location *current_loc, const Vector3f *wind, float *wind_drift_x, float *wind_drift_y, float *dx, float *dy)
  205. {
  206. const Vector2f diff = _prev_update_location.get_distance_NE(*current_loc); // get distances from previous update
  207. *dx = diff.x;
  208. *dy = diff.y;
  209. // Wind correction
  210. *wind_drift_x = wind->x * (AP_HAL::micros64() - _prev_update_time) * 1e-6;
  211. *wind_drift_y = wind->y * (AP_HAL::micros64() - _prev_update_time) * 1e-6;
  212. *dx -= *wind_drift_x;
  213. *dy -= *wind_drift_y;
  214. }
  215. void SoaringController::get_altitude_wrt_home(float *alt)
  216. {
  217. _ahrs.get_relative_position_D_home(*alt);
  218. *alt *= -1.0f;
  219. }
  220. void SoaringController::update_thermalling()
  221. {
  222. struct Location current_loc;
  223. _ahrs.get_position(current_loc);
  224. if (_vario.new_data) {
  225. float dx = 0;
  226. float dy = 0;
  227. float dx_w = 0;
  228. float dy_w = 0;
  229. Vector3f wind = _ahrs.wind_estimate();
  230. get_wind_corrected_drift(&current_loc, &wind, &dx_w, &dy_w, &dx, &dy);
  231. #if (0)
  232. // Print32_t filter info for debugging
  233. int32_t i;
  234. for (i = 0; i < 4; i++) {
  235. gcs().send_text(MAV_SEVERITY_INFO, "%e ", (double)_ekf.P[i][i]);
  236. }
  237. for (i = 0; i < 4; i++) {
  238. gcs().send_text(MAV_SEVERITY_INFO, "%e ", (double)_ekf.X[i]);
  239. }
  240. #endif
  241. // write log - save the data.
  242. AP::logger().Write("SOAR", "TimeUS,nettorate,dx,dy,x0,x1,x2,x3,lat,lng,alt,dx_w,dy_w", "QfffffffLLfff",
  243. AP_HAL::micros64(),
  244. (double)_vario.reading,
  245. (double)dx,
  246. (double)dy,
  247. (double)_ekf.X[0],
  248. (double)_ekf.X[1],
  249. (double)_ekf.X[2],
  250. (double)_ekf.X[3],
  251. current_loc.lat,
  252. current_loc.lng,
  253. (double)_vario.alt,
  254. (double)dx_w,
  255. (double)dy_w);
  256. //log_data();
  257. _ekf.update(_vario.reading,dx, dy); // update the filter
  258. _prev_update_location = current_loc; // save for next time
  259. _prev_update_time = AP_HAL::micros64();
  260. _vario.new_data = false;
  261. }
  262. }
  263. void SoaringController::update_cruising()
  264. {
  265. // Reserved for future tasks that need to run continuously while in FBWB or AUTO mode,
  266. // for example, calculation of optimal airspeed and flap angle.
  267. }
  268. void SoaringController::update_vario()
  269. {
  270. _vario.update(polar_K, polar_CD0, polar_B);
  271. }
  272. float SoaringController::McCready(float alt)
  273. {
  274. // A method shell to be filled in later
  275. return thermal_vspeed;
  276. }
  277. bool SoaringController::is_active() const
  278. {
  279. if (!soar_active) {
  280. return false;
  281. }
  282. if (soar_active_ch <= 0) {
  283. // no activation channel
  284. return true;
  285. }
  286. // active when above 1700
  287. return RC_Channels::get_radio_in(soar_active_ch-1) >= 1700;
  288. }