AP_Landing_Deepstall.h 4.3 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109
  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. #pragma once
  14. #include <AP_Param/AP_Param.h>
  15. #include <AP_Mission/AP_Mission.h>
  16. #include <AP_Common/AP_Common.h>
  17. #include <AP_SpdHgtControl/AP_SpdHgtControl.h>
  18. #include <AP_Navigation/AP_Navigation.h>
  19. #include <PID/PID.h>
  20. class AP_Landing;
  21. /// @class AP_Landing_Deepstall
  22. /// @brief Class managing Plane Deepstall landing methods
  23. class AP_Landing_Deepstall
  24. {
  25. private:
  26. friend class AP_Landing;
  27. // constructor
  28. AP_Landing_Deepstall(AP_Landing &_landing) :
  29. landing(_landing)
  30. {
  31. AP_Param::setup_object_defaults(this, var_info);
  32. }
  33. AP_Landing &landing;
  34. static const struct AP_Param::GroupInfo var_info[];
  35. AP_Float forward_speed;
  36. AP_Float slope_a;
  37. AP_Float slope_b;
  38. AP_Float approach_extension;
  39. AP_Float down_speed;
  40. AP_Float slew_speed;
  41. AP_Int16 elevator_pwm;
  42. AP_Float handoff_airspeed;
  43. AP_Float handoff_lower_limit_airspeed;
  44. AP_Float L1_period;
  45. AP_Float L1_i;
  46. AP_Float yaw_rate_limit;
  47. AP_Float time_constant;
  48. AP_Float min_abort_alt;
  49. AP_Float aileron_scalar;
  50. int32_t loiter_sum_cd; // used for tracking the progress on loitering
  51. DEEPSTALL_STAGE stage;
  52. Location landing_point;
  53. Location extended_approach;
  54. Location breakout_location;
  55. Location arc;
  56. Location arc_entry;
  57. Location arc_exit;
  58. float target_heading_deg; // target heading for the deepstall in degrees
  59. uint32_t stall_entry_time; // time when the aircrafted enter the stall (in millis)
  60. uint16_t initial_elevator_pwm; // PWM to start slewing the elevator up from
  61. uint32_t last_time; // last time the controller ran
  62. float L1_xtrack_i; // L1 integrator for navigation
  63. PID ds_PID;
  64. int32_t last_target_bearing; // used for tracking the progress on loitering
  65. float crosstrack_error; // current crosstrack error
  66. float predicted_travel_distance; // distance the aircraft is perdicted to travel during deepstall
  67. bool hold_level; // locks the target yaw rate of the aircraft to 0, serves to hold the aircraft level at all times
  68. float approach_alt_offset; // approach altitude offset
  69. //public AP_Landing interface
  70. void do_land(const AP_Mission::Mission_Command& cmd, const float relative_altitude);
  71. void verify_abort_landing(const Location &prev_WP_loc, Location &next_WP_loc, bool &throttle_suppressed);
  72. bool verify_land(const Location &prev_WP_loc, Location &next_WP_loc, const Location &current_loc,
  73. const float height, const float sink_rate, const float wp_proportion, const uint32_t last_flying_ms,
  74. const bool is_armed, const bool is_flying, const bool rangefinder_state_in_range);
  75. void setup_landing_glide_slope(const Location &prev_WP_loc, const Location &next_WP_loc,
  76. const Location &current_loc, int32_t &target_altitude_offset_cm);
  77. bool override_servos(void);
  78. bool request_go_around(void);
  79. bool get_target_altitude_location(Location &location);
  80. int32_t get_target_airspeed_cm(void) const;
  81. bool is_throttle_suppressed(void) const;
  82. bool is_flying_forward(void) const;
  83. bool is_on_approach(void) const;
  84. bool terminate(void);
  85. void Log(void) const;
  86. bool send_deepstall_message(mavlink_channel_t chan) const;
  87. const AP_Logger::PID_Info& get_pid_info(void) const;
  88. //private helpers
  89. void build_approach_path(bool use_current_heading);
  90. float predict_travel_distance(const Vector3f wind, const float height, const bool print);
  91. bool verify_breakout(const Location &current_loc, const Location &target_loc, const float height_error) const;
  92. float update_steering(void);
  93. #define DEEPSTALL_LOITER_ALT_TOLERANCE 5.0f
  94. };