Plans: rename ALT_CRUISE_MIN to CRUISE_ALT_FLOOR

This commit is contained in:
Andrew Tridgell 2024-01-19 12:36:20 +11:00
parent e0cd06cc83
commit a3d622b37d
4 changed files with 10 additions and 10 deletions

View File

@ -659,12 +659,12 @@ const AP_Param::Info Plane::var_info[] = {
// @User: Standard
GSCALAR(RTL_altitude, "RTL_ALTITUDE", ALT_HOLD_HOME),
// @Param: ALT_CRUISE_MIN
// @Param: CRUISE_ALT_FLOOR
// @DisplayName: Minimum altitude for FBWB and CRUISE mode
// @Description: This is the minimum altitude in meters (above home) that FBWB and CRUISE modes will allow. If you attempt to descend below this altitude then the plane will level off. It will also force a climb to this altitude if below in these modes. A value of zero means no limit.
// @Units: m
// @User: Standard
GSCALAR(FBWB_min_altitude, "ALT_CRUISE_MIN", ALT_CRUISE_MIN),
GSCALAR(cruise_alt_floor, "CRUISE_ALT_FLOOR", CRUISE_ALT_FLOOR),
// @Param: FLAP_1_PERCNT
// @DisplayName: Flap 1 percentage
@ -1551,7 +1551,7 @@ void Plane::load_parameters(void)
aparm.airspeed_cruise.convert_centi_parameter(AP_PARAM_INT32);
aparm.min_groundspeed.convert_centi_parameter(AP_PARAM_INT32);
g.RTL_altitude.convert_centi_parameter(AP_PARAM_INT32);
g.FBWB_min_altitude.convert_centi_parameter(AP_PARAM_INT16);
g.cruise_alt_floor.convert_centi_parameter(AP_PARAM_INT16);
hal.console->printf("load_all took %uus\n", (unsigned)(micros() - before));
}

View File

@ -174,7 +174,7 @@ public:
//
k_param_airspeed_min = 120,
k_param_airspeed_max,
k_param_FBWB_min_altitude, // 0=disabled, minimum value for altitude in cm (for first time try 30 meters = 3000 cm)
k_param_cruise_alt_floor,
k_param_flybywire_elev_reverse,
k_param_alt_control_algorithm, // unused
k_param_flybywire_climb_rate,
@ -438,7 +438,7 @@ public:
AP_Int32 log_bitmask;
AP_Float RTL_altitude;
AP_Float pitch_trim;
AP_Float FBWB_min_altitude;
AP_Float cruise_alt_floor;
AP_Int8 flap_1_percent;
AP_Int8 flap_1_speed;

View File

@ -337,7 +337,7 @@ int32_t Plane::calc_altitude_error_cm(void)
}
/*
check for FBWB_min_altitude and fence min/max altitude
check for cruise_alt_floor and fence min/max altitude
*/
void Plane::check_fbwb_altitude(void)
{
@ -359,9 +359,9 @@ void Plane::check_fbwb_altitude(void)
}
#endif
if (g.FBWB_min_altitude > 0) {
if (g.cruise_alt_floor > 0) {
// FBWB min altitude exists
min_alt_cm = MAX(min_alt_cm, plane.g.FBWB_min_altitude*100.0);
min_alt_cm = MAX(min_alt_cm, plane.g.cruise_alt_floor*100.0);
should_check_min = true;
}

View File

@ -135,8 +135,8 @@
# define AIRSPEED_FBW_MAX 22
#endif
#ifndef ALT_CRUISE_MIN
# define ALT_CRUISE_MIN 0
#ifndef CRUISE_ALT_FLOOR
# define CRUISE_ALT_FLOOR 0
#endif