From dc3db0476b20a66b60d47f6c4be676b928363957 Mon Sep 17 00:00:00 2001 From: Buzz Date: Mon, 18 May 2020 16:57:29 +1000 Subject: [PATCH] AP_Landing: option to keep landing throttle at thr_min during flare and touchdown, not zero. --- libraries/AP_Landing/AP_Landing.cpp | 15 ++++++++++++++- libraries/AP_Landing/AP_Landing.h | 8 ++++++++ 2 files changed, 22 insertions(+), 1 deletion(-) diff --git a/libraries/AP_Landing/AP_Landing.cpp b/libraries/AP_Landing/AP_Landing.cpp index 5dc940cc09..007f3086c5 100644 --- a/libraries/AP_Landing/AP_Landing.cpp +++ b/libraries/AP_Landing/AP_Landing.cpp @@ -142,7 +142,14 @@ const AP_Param::GroupInfo AP_Landing::var_info[] = { // @Group: DS_ // @Path: AP_Landing_Deepstall.cpp AP_SUBGROUPINFO(deepstall, "DS_", 15, AP_Landing, AP_Landing_Deepstall), - + + // @Param: _OPTIONS + // @DisplayName: Landing options bitmask + // @Description: Bitmask of options to use with landing. + // @Bitmask: 0: honor min throttle during landing flare + // @User: Advanced + AP_GROUPINFO("OPTIONS", 16, AP_Landing, _options, 0), + AP_GROUPEND }; @@ -606,6 +613,12 @@ bool AP_Landing::is_throttle_suppressed(void) const } } +//defaults to false, but _options bit zero enables it. +bool AP_Landing::use_thr_min_during_flare(void) const +{ + return (OptionsMask::ON_LANDING_FLARE_USE_THR_MIN & _options) != 0; +} + /* * returns false when the vehicle might not be flying forward while landing */ diff --git a/libraries/AP_Landing/AP_Landing.h b/libraries/AP_Landing/AP_Landing.h index 672f00fc53..82d447bbef 100644 --- a/libraries/AP_Landing/AP_Landing.h +++ b/libraries/AP_Landing/AP_Landing.h @@ -57,6 +57,11 @@ public: // TODO: TYPE_HELICAL, }; + // we support upto 32 boolean bits for users wanting to change landing behaviour. + enum OptionsMask { + ON_LANDING_FLARE_USE_THR_MIN = (1<<0), // If set then set trottle to thr_min instead of zero on final flare + }; + void do_land(const AP_Mission::Mission_Command& cmd, const float relative_altitude); bool verify_abort_landing(const Location &prev_WP_loc, Location &next_WP_loc, const Location ¤t_loc, const int32_t auto_state_takeoff_altitude_rel_cm, bool &throttle_suppressed); @@ -72,6 +77,7 @@ public: bool is_ground_steering_allowed(void) const; bool is_throttle_suppressed(void) const; bool is_flying_forward(void) const; + bool use_thr_min_during_flare(void) const; //defaults to false, but _options bit zero enables it. void handle_flight_stage_change(const bool _in_landing_stage); int32_t constrain_roll(const int32_t desired_roll_cd, const int32_t level_roll_limit_cd); bool get_target_altitude_location(Location &location); @@ -115,6 +121,8 @@ private: bool in_progress:1; } flags; + AP_Int16 _options; // user-configurable bitmask options, via a parameter, for landing + // same as land_slope but sampled once before a rangefinder changes the slope. This should be the original mission planned slope float initial_slope;