diff --git a/libraries/AP_Landing/AP_Landing.cpp b/libraries/AP_Landing/AP_Landing.cpp index 6699089ad2..51ab12a63b 100644 --- a/libraries/AP_Landing/AP_Landing.cpp +++ b/libraries/AP_Landing/AP_Landing.cpp @@ -43,18 +43,18 @@ const AP_Param::GroupInfo AP_Landing::var_info[] = { // @User: Advanced AP_GROUPINFO("ABORT_DEG", 2, AP_Landing, slope_recalc_steep_threshold_to_abort, 0), - // @Param: PITCH_CD + // @Param: PITCH_DEG // @DisplayName: Landing Pitch // @Description: Used in autoland to give the minimum pitch in the final stage of landing (after the flare). This parameter can be used to ensure that the final landing attitude is appropriate for the type of undercarriage on the aircraft. Note that it is a minimum pitch only - the landing code will control pitch above this value to try to achieve the configured landing sink rate. - // @Units: cdeg - // @Range: -2000 2000 + // @Units: deg + // @Range: -20 20 // @Increment: 10 // @User: Advanced - AP_GROUPINFO("PITCH_CD", 3, AP_Landing, pitch_cd, 0), + AP_GROUPINFO("PITCH_DEG", 3, AP_Landing, pitch_deg, 0), // @Param: FLARE_ALT // @DisplayName: Landing flare altitude - // @Description: Altitude in autoland at which to lock heading and flare to the LAND_PITCH_CD pitch. Note that this option is secondary to LAND_FLARE_SEC. For a good landing it preferable that the flare is triggered by LAND_FLARE_SEC. + // @Description: Altitude in autoland at which to lock heading and flare to the LAND_PITCH_DEG pitch. Note that this option is secondary to LAND_FLARE_SEC. For a good landing it preferable that the flare is triggered by LAND_FLARE_SEC. // @Units: m // @Range: 0 30 // @Increment: 0.1 @@ -709,3 +709,12 @@ bool AP_Landing::terminate(void) { return false; } } + +/* + run parameter conversions + */ +void AP_Landing::convert_parameters(void) +{ + // added January 2024 + pitch_deg.convert_centi_parameter(AP_PARAM_INT16); +} diff --git a/libraries/AP_Landing/AP_Landing.h b/libraries/AP_Landing/AP_Landing.h index 3055bf2211..80349010bc 100644 --- a/libraries/AP_Landing/AP_Landing.h +++ b/libraries/AP_Landing/AP_Landing.h @@ -64,6 +64,8 @@ public: ON_LANDING_USE_ARSPD_MAX = (1<<1), // If set then allow landing throttle constraint to be increased from trim airspeed to max airspeed (AIRSPEED_MAX) }; + void convert_parameters(void); + 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); @@ -96,7 +98,7 @@ public: // accessor functions for the params and states static const struct AP_Param::GroupInfo var_info[]; - int16_t get_pitch_cd(void) const { return pitch_cd; } + int16_t get_pitch_cd(void) const { return pitch_deg*100; } float get_flare_sec(void) const { return flare_sec; } int8_t get_disarm_delay(void) const { return disarm_delay; } int8_t get_then_servos_neutral(void) const { return then_servos_neutral; } @@ -151,7 +153,7 @@ private: AP_Landing_Deepstall deepstall; #endif - AP_Int16 pitch_cd; + AP_Float pitch_deg; AP_Float flare_alt; AP_Float flare_sec; AP_Float pre_flare_airspeed;