AP_Landing_Deepstall.cpp 26 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640
  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. * AP_Landing_Deepstall.cpp - Landing logic handler for ArduPlane for deepstall landings
  15. */
  16. #include "AP_Landing.h"
  17. #include <GCS_MAVLink/GCS.h>
  18. #include <AP_HAL/AP_HAL.h>
  19. #include <SRV_Channel/SRV_Channel.h>
  20. #include <AP_Common/Location.h>
  21. #include <AP_AHRS/AP_AHRS.h>
  22. // table of user settable parameters for deepstall
  23. const AP_Param::GroupInfo AP_Landing_Deepstall::var_info[] = {
  24. // @Param: V_FWD
  25. // @DisplayName: Deepstall forward velocity
  26. // @Description: The forward velocity of the aircraft while stalled
  27. // @Range: 0 20
  28. // @Units: m/s
  29. // @User: Advanced
  30. AP_GROUPINFO("V_FWD", 1, AP_Landing_Deepstall, forward_speed, 1),
  31. // @Param: SLOPE_A
  32. // @DisplayName: Deepstall slope a
  33. // @Description: The a component of distance = a*wind + b
  34. // @User: Advanced
  35. AP_GROUPINFO("SLOPE_A", 2, AP_Landing_Deepstall, slope_a, 1),
  36. // @Param: SLOPE_B
  37. // @DisplayName: Deepstall slope b
  38. // @Description: The a component of distance = a*wind + b
  39. // @User: Advanced
  40. AP_GROUPINFO("SLOPE_B", 3, AP_Landing_Deepstall, slope_b, 1),
  41. // @Param: APP_EXT
  42. // @DisplayName: Deepstall approach extension
  43. // @Description: The forward velocity of the aircraft while stalled
  44. // @Range: 10 200
  45. // @Units: m
  46. // @User: Advanced
  47. AP_GROUPINFO("APP_EXT", 4, AP_Landing_Deepstall, approach_extension, 50),
  48. // @Param: V_DWN
  49. // @DisplayName: Deepstall velocity down
  50. // @Description: The downward velocity of the aircraft while stalled
  51. // @Range: 0 20
  52. // @Units: m/s
  53. // @User: Advanced
  54. AP_GROUPINFO("V_DWN", 5, AP_Landing_Deepstall, down_speed, 2),
  55. // @Param: SLEW_SPD
  56. // @DisplayName: Deepstall slew speed
  57. // @Description: The speed at which the elevator slews to deepstall
  58. // @Range: 0 2
  59. // @Units: s
  60. // @User: Advanced
  61. AP_GROUPINFO("SLEW_SPD", 6, AP_Landing_Deepstall, slew_speed, 0.5),
  62. // @Param: ELEV_PWM
  63. // @DisplayName: Deepstall elevator PWM
  64. // @Description: The PWM value in microseconds for the elevator at full deflection in deepstall
  65. // @Range: 900 2100
  66. // @Units: PWM
  67. // @User: Advanced
  68. AP_GROUPINFO("ELEV_PWM", 7, AP_Landing_Deepstall, elevator_pwm, 1500),
  69. // @Param: ARSP_MAX
  70. // @DisplayName: Deepstall enabled airspeed
  71. // @Description: The maximum aispeed where the deepstall steering controller is allowed to have control
  72. // @Range: 5 20
  73. // @Units: m/s
  74. // @User: Advanced
  75. AP_GROUPINFO("ARSP_MAX", 8, AP_Landing_Deepstall, handoff_airspeed, 15.0),
  76. // @Param: ARSP_MIN
  77. // @DisplayName: Deepstall minimum derating airspeed
  78. // @Description: Deepstall lowest airspeed where the deepstall controller isn't allowed full control
  79. // @Range: 5 20
  80. // @Units: m/s
  81. // @User: Advanced
  82. AP_GROUPINFO("ARSP_MIN", 9, AP_Landing_Deepstall, handoff_lower_limit_airspeed, 10.0),
  83. // @Param: L1
  84. // @DisplayName: Deepstall L1 period
  85. // @Description: Deepstall L1 navigational controller period
  86. // @Range: 5 50
  87. // @Units: m
  88. // @User: Advanced
  89. AP_GROUPINFO("L1", 10, AP_Landing_Deepstall, L1_period, 30.0),
  90. // @Param: L1_I
  91. // @DisplayName: Deepstall L1 I gain
  92. // @Description: Deepstall L1 integratior gain
  93. // @Range: 0 1
  94. // @User: Advanced
  95. AP_GROUPINFO("L1_I", 11, AP_Landing_Deepstall, L1_i, 0),
  96. // @Param: YAW_LIM
  97. // @DisplayName: Deepstall yaw rate limit
  98. // @Description: The yaw rate limit while navigating in deepstall
  99. // @Range: 0 90
  100. // @Units degrees per second
  101. // @User: Advanced
  102. AP_GROUPINFO("YAW_LIM", 12, AP_Landing_Deepstall, yaw_rate_limit, 10),
  103. // @Param: L1_TCON
  104. // @DisplayName: Deepstall L1 time constant
  105. // @Description: Time constant for deepstall L1 control
  106. // @Range: 0 1
  107. // @Units seconds
  108. // @User: Advanced
  109. AP_GROUPINFO("L1_TCON", 13, AP_Landing_Deepstall, time_constant, 0.4),
  110. // @Group: DS_
  111. // @Path: ../PID/PID.cpp
  112. AP_SUBGROUPINFO(ds_PID, "", 14, AP_Landing_Deepstall, PID),
  113. // @Param: ABORTALT
  114. // @DisplayName: Deepstall minimum abort altitude
  115. // @Description: The minimum altitude which the aircraft must be above to abort a deepstall landing
  116. // @Range: 0 50
  117. // @Units meters
  118. // @User: Advanced
  119. AP_GROUPINFO("ABORTALT", 15, AP_Landing_Deepstall, min_abort_alt, 0.0f),
  120. // @Param: AIL_SCL
  121. // @DisplayName: Aileron landing gain scalaing
  122. // @Description: A scalar to reduce or increase the aileron control
  123. // @Range: 0 2.0
  124. // @User: Advanced
  125. AP_GROUPINFO("AIL_SCL", 16, AP_Landing_Deepstall, aileron_scalar, 1.0f),
  126. AP_GROUPEND
  127. };
  128. // if DEBUG_PRINTS is defined statustexts will be sent to the GCS for debug purposes
  129. // #define DEBUG_PRINTS
  130. void AP_Landing_Deepstall::do_land(const AP_Mission::Mission_Command& cmd, const float relative_altitude)
  131. {
  132. stage = DEEPSTALL_STAGE_FLY_TO_LANDING;
  133. ds_PID.reset();
  134. L1_xtrack_i = 0.0f;
  135. hold_level = false; // come out of yaw lock
  136. // load the landing point in, the rest of path building is deferred for a better wind estimate
  137. memcpy(&landing_point, &cmd.content.location, sizeof(Location));
  138. if (!landing_point.relative_alt && !landing_point.terrain_alt) {
  139. approach_alt_offset = cmd.p1;
  140. landing_point.alt += approach_alt_offset * 100;
  141. } else {
  142. approach_alt_offset = 0.0f;
  143. }
  144. }
  145. // currently identical to the slope aborts
  146. void AP_Landing_Deepstall::verify_abort_landing(const Location &prev_WP_loc, Location &next_WP_loc, bool &throttle_suppressed)
  147. {
  148. // when aborting a landing, mimic the verify_takeoff with steering hold. Once
  149. // the altitude has been reached, restart the landing sequence
  150. throttle_suppressed = false;
  151. landing.nav_controller->update_heading_hold(prev_WP_loc.get_bearing_to(next_WP_loc));
  152. }
  153. /*
  154. update navigation for landing
  155. */
  156. bool AP_Landing_Deepstall::verify_land(const Location &prev_WP_loc, Location &next_WP_loc, const Location &current_loc,
  157. const float height, const float sink_rate, const float wp_proportion, const uint32_t last_flying_ms,
  158. const bool is_armed, const bool is_flying, const bool rangefinder_state_in_range)
  159. {
  160. switch (stage) {
  161. case DEEPSTALL_STAGE_FLY_TO_LANDING:
  162. if (current_loc.get_distance(landing_point) > abs(2 * landing.aparm.loiter_radius)) {
  163. landing.nav_controller->update_waypoint(current_loc, landing_point);
  164. return false;
  165. }
  166. stage = DEEPSTALL_STAGE_ESTIMATE_WIND;
  167. loiter_sum_cd = 0; // reset the loiter counter
  168. FALLTHROUGH;
  169. case DEEPSTALL_STAGE_ESTIMATE_WIND:
  170. {
  171. landing.nav_controller->update_loiter(landing_point, landing.aparm.loiter_radius, landing_point.loiter_ccw ? -1 : 1);
  172. if (!landing.nav_controller->reached_loiter_target() || (fabsf(height - approach_alt_offset) > DEEPSTALL_LOITER_ALT_TOLERANCE)) {
  173. // wait until the altitude is correct before considering a breakout
  174. return false;
  175. }
  176. // only count loiter progress when within the target altitude
  177. int32_t target_bearing = landing.nav_controller->target_bearing_cd();
  178. int32_t delta = wrap_180_cd(target_bearing - last_target_bearing);
  179. delta *= (landing_point.loiter_ccw ? -1 : 1);
  180. if (delta > 0) { // only accumulate turns in the correct direction
  181. loiter_sum_cd += delta;
  182. }
  183. last_target_bearing = target_bearing;
  184. if (loiter_sum_cd < 36000) {
  185. // wait until we've done at least one complete loiter at the correct altitude
  186. return false;
  187. }
  188. stage = DEEPSTALL_STAGE_WAIT_FOR_BREAKOUT;
  189. loiter_sum_cd = 0; // reset the loiter counter
  190. FALLTHROUGH;
  191. }
  192. case DEEPSTALL_STAGE_WAIT_FOR_BREAKOUT:
  193. // rebuild the approach path if we have done less then a full circle to allow it to be
  194. // more into the wind as the estimator continues to refine itself, and allow better
  195. // compensation on windy days. This is limited to a single full circle though, as on
  196. // a no wind day you could be in this loop forever otherwise.
  197. if (loiter_sum_cd < 36000) {
  198. build_approach_path(false);
  199. }
  200. if (!verify_breakout(current_loc, arc_entry, height - approach_alt_offset)) {
  201. int32_t target_bearing = landing.nav_controller->target_bearing_cd();
  202. int32_t delta = wrap_180_cd(target_bearing - last_target_bearing);
  203. if (delta > 0) { // only accumulate turns in the correct direction
  204. loiter_sum_cd += delta;
  205. }
  206. last_target_bearing = target_bearing;
  207. landing.nav_controller->update_loiter(landing_point, landing.aparm.loiter_radius, landing_point.loiter_ccw ? -1 : 1);
  208. return false;
  209. }
  210. stage = DEEPSTALL_STAGE_FLY_TO_ARC;
  211. memcpy(&breakout_location, &current_loc, sizeof(Location));
  212. FALLTHROUGH;
  213. case DEEPSTALL_STAGE_FLY_TO_ARC:
  214. if (current_loc.get_distance(arc_entry) > 2 * landing.aparm.loiter_radius) {
  215. landing.nav_controller->update_waypoint(breakout_location, arc_entry);
  216. return false;
  217. }
  218. stage = DEEPSTALL_STAGE_ARC;
  219. FALLTHROUGH;
  220. case DEEPSTALL_STAGE_ARC:
  221. {
  222. Vector2f groundspeed = landing.ahrs.groundspeed_vector();
  223. if (!landing.nav_controller->reached_loiter_target() ||
  224. (fabsf(wrap_180(target_heading_deg -
  225. degrees(atan2f(-groundspeed.y, -groundspeed.x) + M_PI))) >= 10.0f)) {
  226. landing.nav_controller->update_loiter(arc, landing.aparm.loiter_radius, landing_point.loiter_ccw ? -1 : 1);
  227. return false;
  228. }
  229. stage = DEEPSTALL_STAGE_APPROACH;
  230. }
  231. FALLTHROUGH;
  232. case DEEPSTALL_STAGE_APPROACH:
  233. {
  234. Location entry_point;
  235. landing.nav_controller->update_waypoint(arc_exit, extended_approach);
  236. float height_above_target;
  237. if (is_zero(approach_alt_offset)) {
  238. landing.ahrs.get_relative_position_D_home(height_above_target);
  239. height_above_target = -height_above_target;
  240. } else {
  241. Location position;
  242. if (landing.ahrs.get_position(position)) {
  243. height_above_target = (position.alt - landing_point.alt + approach_alt_offset * 100) * 1e-2f;
  244. } else {
  245. height_above_target = approach_alt_offset;
  246. }
  247. }
  248. const float travel_distance = predict_travel_distance(landing.ahrs.wind_estimate(), height_above_target, false);
  249. memcpy(&entry_point, &landing_point, sizeof(Location));
  250. entry_point.offset_bearing(target_heading_deg + 180.0, travel_distance);
  251. if (!current_loc.past_interval_finish_line(arc_exit, entry_point)) {
  252. if (current_loc.past_interval_finish_line(arc_exit, extended_approach)) {
  253. // this should never happen, but prevent against an indefinite fly away
  254. stage = DEEPSTALL_STAGE_FLY_TO_LANDING;
  255. }
  256. return false;
  257. }
  258. predict_travel_distance(landing.ahrs.wind_estimate(), height_above_target, true);
  259. stage = DEEPSTALL_STAGE_LAND;
  260. stall_entry_time = AP_HAL::millis();
  261. const SRV_Channel* elevator = SRV_Channels::get_channel_for(SRV_Channel::k_elevator);
  262. if (elevator != nullptr) {
  263. // take the last used elevator angle as the starting deflection
  264. // don't worry about bailing here if the elevator channel can't be found
  265. // that will be handled within override_servos
  266. initial_elevator_pwm = elevator->get_output_pwm();
  267. }
  268. }
  269. FALLTHROUGH;
  270. case DEEPSTALL_STAGE_LAND:
  271. // while in deepstall the only thing verify needs to keep the extended approach point sufficently far away
  272. landing.nav_controller->update_waypoint(current_loc, extended_approach);
  273. landing.disarm_if_autoland_complete_fn();
  274. return false;
  275. default:
  276. return true;
  277. }
  278. }
  279. bool AP_Landing_Deepstall::override_servos(void)
  280. {
  281. if (stage != DEEPSTALL_STAGE_LAND) {
  282. return false;
  283. }
  284. SRV_Channel* elevator = SRV_Channels::get_channel_for(SRV_Channel::k_elevator);
  285. if (elevator == nullptr) {
  286. // deepstalls are impossible without these channels, abort the process
  287. gcs().send_text(MAV_SEVERITY_CRITICAL, "Deepstall: Unable to find the elevator channels");
  288. request_go_around();
  289. return false;
  290. }
  291. // calculate the progress on slewing the elevator
  292. float slew_progress = 1.0f;
  293. if (slew_speed > 0) {
  294. slew_progress = (AP_HAL::millis() - stall_entry_time) / (100.0f * slew_speed);
  295. }
  296. // mix the elevator to the correct value
  297. elevator->set_output_pwm(linear_interpolate(initial_elevator_pwm, elevator_pwm,
  298. slew_progress, 0.0f, 1.0f));
  299. // use the current airspeed to dictate the travel limits
  300. float airspeed;
  301. if (!landing.ahrs.airspeed_estimate(&airspeed)) {
  302. airspeed = 0; // safely forces control to the deepstall steering since we don't have an estimate
  303. }
  304. // only allow the deepstall steering controller to run below the handoff airspeed
  305. if (slew_progress >= 1.0f || airspeed <= handoff_airspeed) {
  306. // run the steering conntroller
  307. float pid = update_steering();
  308. float travel_limit = constrain_float((handoff_airspeed - airspeed) /
  309. (handoff_airspeed - handoff_lower_limit_airspeed) *
  310. 0.5f + 0.5f,
  311. 0.5f, 1.0f);
  312. float output = constrain_float(pid, -travel_limit, travel_limit);
  313. SRV_Channels::set_output_scaled(SRV_Channel::k_aileron, output*4500*aileron_scalar);
  314. SRV_Channels::set_output_scaled(SRV_Channel::k_rudder, output*4500);
  315. SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, 0); // this will normally be managed as part of landing,
  316. // but termination needs to set throttle control here
  317. }
  318. // hand off rudder control to deepstall controlled
  319. return true;
  320. }
  321. bool AP_Landing_Deepstall::request_go_around(void)
  322. {
  323. float current_altitude_d;
  324. landing.ahrs.get_relative_position_D_home(current_altitude_d);
  325. if (is_zero(min_abort_alt) || -current_altitude_d > min_abort_alt) {
  326. landing.flags.commanded_go_around = true;
  327. return true;
  328. } else {
  329. return false;
  330. }
  331. }
  332. bool AP_Landing_Deepstall::is_throttle_suppressed(void) const
  333. {
  334. return stage == DEEPSTALL_STAGE_LAND;
  335. }
  336. bool AP_Landing_Deepstall::is_flying_forward(void) const
  337. {
  338. return stage != DEEPSTALL_STAGE_LAND;
  339. }
  340. bool AP_Landing_Deepstall::is_on_approach(void) const
  341. {
  342. return stage == DEEPSTALL_STAGE_LAND;
  343. }
  344. bool AP_Landing_Deepstall::get_target_altitude_location(Location &location)
  345. {
  346. memcpy(&location, &landing_point, sizeof(Location));
  347. return true;
  348. }
  349. int32_t AP_Landing_Deepstall::get_target_airspeed_cm(void) const
  350. {
  351. if (stage == DEEPSTALL_STAGE_APPROACH ||
  352. stage == DEEPSTALL_STAGE_LAND) {
  353. return landing.pre_flare_airspeed * 100;
  354. } else {
  355. return landing.aparm.airspeed_cruise_cm;
  356. }
  357. }
  358. bool AP_Landing_Deepstall::send_deepstall_message(mavlink_channel_t chan) const
  359. {
  360. CHECK_PAYLOAD_SIZE2(DEEPSTALL);
  361. mavlink_msg_deepstall_send(
  362. chan,
  363. landing_point.lat,
  364. landing_point.lng,
  365. stage >= DEEPSTALL_STAGE_WAIT_FOR_BREAKOUT ? arc_exit.lat : 0.0f,
  366. stage >= DEEPSTALL_STAGE_WAIT_FOR_BREAKOUT ? arc_exit.lng : 0.0f,
  367. stage >= DEEPSTALL_STAGE_WAIT_FOR_BREAKOUT ? arc_entry.lat : 0.0f,
  368. stage >= DEEPSTALL_STAGE_WAIT_FOR_BREAKOUT ? arc_entry.lng : 0.0f,
  369. landing_point.alt * 0.01,
  370. stage >= DEEPSTALL_STAGE_WAIT_FOR_BREAKOUT ? predicted_travel_distance : 0.0f,
  371. stage == DEEPSTALL_STAGE_LAND ? crosstrack_error : 0.0f,
  372. stage);
  373. return true;
  374. }
  375. const AP_Logger::PID_Info& AP_Landing_Deepstall::get_pid_info(void) const
  376. {
  377. return ds_PID.get_pid_info();
  378. }
  379. void AP_Landing_Deepstall::Log(void) const {
  380. const AP_Logger::PID_Info& pid_info = ds_PID.get_pid_info();
  381. struct log_DSTL pkt = {
  382. LOG_PACKET_HEADER_INIT(LOG_DSTL_MSG),
  383. time_us : AP_HAL::micros64(),
  384. stage : (uint8_t)stage,
  385. target_heading : target_heading_deg,
  386. target_lat : landing_point.lat,
  387. target_lng : landing_point.lng,
  388. target_alt : landing_point.alt,
  389. crosstrack_error : (int16_t)(stage >= DEEPSTALL_STAGE_LAND ?
  390. constrain_float(crosstrack_error * 1e2f, (float)INT16_MIN, (float)INT16_MAX) : 0),
  391. travel_distance : (int16_t)(stage >= DEEPSTALL_STAGE_LAND ?
  392. constrain_float(predicted_travel_distance * 1e2f, (float)INT16_MIN, (float)INT16_MAX) : 0),
  393. l1_i : stage >= DEEPSTALL_STAGE_LAND ? L1_xtrack_i : 0.0f,
  394. loiter_sum_cd : stage >= DEEPSTALL_STAGE_ESTIMATE_WIND ? loiter_sum_cd : 0,
  395. desired : pid_info.target,
  396. P : pid_info.P,
  397. I : pid_info.I,
  398. D : pid_info.D,
  399. };
  400. AP::logger().WriteBlock(&pkt, sizeof(pkt));
  401. }
  402. // termination handling, expected to set the servo outputs
  403. bool AP_Landing_Deepstall::terminate(void) {
  404. // if we were not in a deepstall, mark us as being in one
  405. if(!landing.flags.in_progress || stage != DEEPSTALL_STAGE_LAND) {
  406. stall_entry_time = AP_HAL::millis();
  407. ds_PID.reset();
  408. L1_xtrack_i = 0.0f;
  409. landing.flags.in_progress = true;
  410. stage = DEEPSTALL_STAGE_LAND;
  411. if(landing.ahrs.get_position(landing_point)) {
  412. build_approach_path(true);
  413. } else {
  414. hold_level = true;
  415. }
  416. }
  417. // set the servo ouptuts, this can fail, so this is the important return value for the AFS
  418. return override_servos();
  419. }
  420. void AP_Landing_Deepstall::build_approach_path(bool use_current_heading)
  421. {
  422. float loiter_radius = landing.nav_controller->loiter_radius(landing.aparm.loiter_radius);
  423. Vector3f wind = landing.ahrs.wind_estimate();
  424. // TODO: Support a user defined approach heading
  425. target_heading_deg = use_current_heading ? landing.ahrs.yaw_sensor * 1e-2 : (degrees(atan2f(-wind.y, -wind.x)));
  426. memcpy(&extended_approach, &landing_point, sizeof(Location));
  427. memcpy(&arc_exit, &landing_point, sizeof(Location));
  428. //extend the approach point to 1km away so that there is always a navigational target
  429. extended_approach.offset_bearing(target_heading_deg, 1000.0);
  430. float expected_travel_distance = predict_travel_distance(wind, is_zero(approach_alt_offset) ? landing_point.alt * 0.01f : approach_alt_offset,
  431. false);
  432. float approach_extension_m = expected_travel_distance + approach_extension;
  433. float loiter_radius_m_abs = fabsf(loiter_radius);
  434. // an approach extensions must be at least half the loiter radius, or the aircraft has a
  435. // decent chance to be misaligned on final approach
  436. approach_extension_m = MAX(approach_extension_m, loiter_radius_m_abs * 0.5f);
  437. arc_exit.offset_bearing(target_heading_deg + 180, approach_extension_m);
  438. memcpy(&arc, &arc_exit, sizeof(Location));
  439. memcpy(&arc_entry, &arc_exit, sizeof(Location));
  440. float arc_heading_deg = target_heading_deg + (landing_point.loiter_ccw ? -90.0f : 90.0f);
  441. arc.offset_bearing(arc_heading_deg, loiter_radius_m_abs);
  442. arc_entry.offset_bearing(arc_heading_deg, loiter_radius_m_abs * 2);
  443. #ifdef DEBUG_PRINTS
  444. // TODO: Send this information via a MAVLink packet
  445. gcs().send_text(MAV_SEVERITY_INFO, "Arc: %3.8f %3.8f",
  446. (double)(arc.lat / 1e7),(double)( arc.lng / 1e7));
  447. gcs().send_text(MAV_SEVERITY_INFO, "Loiter en: %3.8f %3.8f",
  448. (double)(arc_entry.lat / 1e7), (double)(arc_entry.lng / 1e7));
  449. gcs().send_text(MAV_SEVERITY_INFO, "Loiter ex: %3.8f %3.8f",
  450. (double)(arc_exit.lat / 1e7), (double)(arc_exit.lng / 1e7));
  451. gcs().send_text(MAV_SEVERITY_INFO, "Extended: %3.8f %3.8f",
  452. (double)(extended_approach.lat / 1e7), (double)(extended_approach.lng / 1e7));
  453. gcs().send_text(MAV_SEVERITY_INFO, "Extended by: %f (%f)", (double)approach_extension_m,
  454. (double)expected_travel_distance);
  455. gcs().send_text(MAV_SEVERITY_INFO, "Target Heading: %3.1f", (double)target_heading_deg);
  456. #endif // DEBUG_PRINTS
  457. }
  458. float AP_Landing_Deepstall::predict_travel_distance(const Vector3f wind, const float height, const bool print)
  459. {
  460. bool reverse = false;
  461. float course = radians(target_heading_deg);
  462. // a forward speed of 0 will result in a divide by 0
  463. float forward_speed_ms = MAX(forward_speed, 0.1f);
  464. Vector2f wind_vec(wind.x, wind.y); // work with the 2D component of wind
  465. float wind_length = MAX(wind_vec.length(), 0.05f); // always assume a slight wind to avoid divide by 0
  466. Vector2f course_vec(cosf(course), sinf(course));
  467. float offset = course - atan2f(-wind.y, -wind.x);
  468. // estimator for how far the aircraft will travel while entering the stall
  469. float stall_distance = slope_a * wind_length * cosf(offset) + slope_b;
  470. float theta = acosf(constrain_float((wind_vec * course_vec) / wind_length, -1.0f, 1.0f));
  471. if ((course_vec % wind_vec) > 0) {
  472. reverse = true;
  473. theta *= -1;
  474. }
  475. float cross_component = sinf(theta) * wind_length;
  476. float estimated_crab_angle = asinf(constrain_float(cross_component / forward_speed_ms, -1.0f, 1.0f));
  477. if (reverse) {
  478. estimated_crab_angle *= -1;
  479. }
  480. float estimated_forward = cosf(estimated_crab_angle) * forward_speed_ms + cosf(theta) * wind_length;
  481. if (is_positive(down_speed)) {
  482. predicted_travel_distance = (estimated_forward * height / down_speed) + stall_distance;
  483. } else {
  484. // if we don't have a sane downward speed in a deepstall (IE not zero, and not
  485. // an ascent) then just provide the stall_distance as a reasonable approximation
  486. predicted_travel_distance = stall_distance;
  487. }
  488. if(print) {
  489. // allow printing the travel distances on the final entry as its used for tuning
  490. gcs().send_text(MAV_SEVERITY_INFO, "Deepstall: Entry: %0.1f (m) Travel: %0.1f (m)",
  491. (double)stall_distance, (double)predicted_travel_distance);
  492. }
  493. return predicted_travel_distance;
  494. }
  495. bool AP_Landing_Deepstall::verify_breakout(const Location &current_loc, const Location &target_loc,
  496. const float height_error) const
  497. {
  498. const Vector2f location_delta = current_loc.get_distance_NE(target_loc);
  499. const float heading_error = degrees(landing.ahrs.groundspeed_vector().angle(location_delta));
  500. // Check to see if the the plane is heading toward the land waypoint. We use 20 degrees (+/-10 deg)
  501. // of margin so that the altitude to be within 5 meters of desired
  502. if (heading_error <= 10.0 && fabsf(height_error) < DEEPSTALL_LOITER_ALT_TOLERANCE) {
  503. // Want to head in a straight line from _here_ to the next waypoint instead of center of loiter wp
  504. return true;
  505. }
  506. return false;
  507. }
  508. float AP_Landing_Deepstall::update_steering()
  509. {
  510. Location current_loc;
  511. if ((!landing.ahrs.get_position(current_loc) || !landing.ahrs.healthy()) && !hold_level) {
  512. // panic if no position source is available
  513. // continue the stall but target just holding the wings held level as deepstall should be a minimal
  514. // energy configuration on the aircraft, and if a position isn't available aborting would be worse
  515. gcs().send_text(MAV_SEVERITY_CRITICAL, "Deepstall: Invalid data from AHRS. Holding level");
  516. hold_level = true;
  517. }
  518. float desired_change = 0.0f;
  519. if (!hold_level) {
  520. uint32_t time = AP_HAL::millis();
  521. float dt = constrain_float(time - last_time, (uint32_t)10UL, (uint32_t)200UL) * 1e-3;
  522. last_time = time;
  523. Vector2f ab = arc_exit.get_distance_NE(extended_approach);
  524. ab.normalize();
  525. const Vector2f a_air = arc_exit.get_distance_NE(current_loc);
  526. crosstrack_error = a_air % ab;
  527. float sine_nu1 = constrain_float(crosstrack_error / MAX(L1_period, 0.1f), -0.7071f, 0.7107f);
  528. float nu1 = asinf(sine_nu1);
  529. if (L1_i > 0) {
  530. L1_xtrack_i += nu1 * L1_i / dt;
  531. L1_xtrack_i = constrain_float(L1_xtrack_i, -0.5f, 0.5f);
  532. nu1 += L1_xtrack_i;
  533. }
  534. desired_change = wrap_PI(radians(target_heading_deg) + nu1 - landing.ahrs.yaw) / time_constant;
  535. }
  536. float yaw_rate = landing.ahrs.get_gyro().z;
  537. float yaw_rate_limit_rps = radians(yaw_rate_limit);
  538. float error = wrap_PI(constrain_float(desired_change, -yaw_rate_limit_rps, yaw_rate_limit_rps) - yaw_rate);
  539. #ifdef DEBUG_PRINTS
  540. gcs().send_text(MAV_SEVERITY_INFO, "x: %f e: %f r: %f d: %f",
  541. (double)crosstrack_error,
  542. (double)error,
  543. (double)degrees(yaw_rate),
  544. (double)current_loc.get_distance(landing_point));
  545. #endif // DEBUG_PRINTS
  546. return ds_PID.get_pid(error);
  547. }