Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Plane: most plane centi parameters to deg or m or m/s #26025

Merged
merged 86 commits into from Jan 23, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
86 commits
Select commit Hold shift + click to select a range
bf3e259
Plane: convert parameter TRIM_PITCH_CD to TRIM_PITCH_DEG
timtuxworth Dec 13, 2023
03ca7b9
AP_Param: added convert_centi_parameter()
timtuxworth Dec 13, 2023
63c5afd
AP_TECS: use new pitch_trim in degrees
timtuxworth Dec 14, 2023
644b11a
AP_Vehicle: use new pitch_trim in degrees in AP_FixedWing
timtuxworth Dec 14, 2023
f2de2b6
Tools: update Frame_params for TRIM_PITCH_DEG
timtuxworth Dec 14, 2023
1c86f2a
autotest: change default params from TRIM_PITCH_CD to TRIM_PITCH_DEG
timtuxworth Dec 14, 2023
e4c84da
SITL: convert TRIM_PITCH_CD to TRIM_PITCH_DEG
timtuxworth Dec 19, 2023
180d027
AP_Landing: change TRIM_ARSPD_CM to AIRSPEED_CRUISE
tridge Jan 18, 2024
d8b5a30
AP_Soaring: change TRIM_ARSPD_CM to AIRSPEED_CRUISE
tridge Jan 18, 2024
a198eb3
AP_TECS: change TRIM_ARSPD_CM to AIRSPEED_CRUISE
tridge Jan 18, 2024
10b61f0
AP_Vehicle: change TRIM_ARSPD_CM to AIRSPEED_CRUISE
tridge Jan 18, 2024
a68b832
ArduPlane: change TRIM_ARSPD_CM to AIRSPEED_CRUISE
tridge Jan 18, 2024
ebdc279
Tools: change TRIM_ARSPD_CM to AIRSPEED_CRUISE
tridge Jan 18, 2024
380f7a0
AP_HAL_ChibiOS: converted TRIM_ARSPD_CM to AIRSPEED_CRUISE
tridge Jan 18, 2024
a5de930
SITL: converted TRIM_ARSPD_CM to AIRSPEED_CRUISE
tridge Jan 18, 2024
0386750
AP_OSD: convert remaining uses of TRIM_ARSPD_CM to AIRSPEED_CRUISE
tridge Jan 18, 2024
ecdea3b
AP_Scripting: convert remaining uses of TRIM_ARSPD_CM to AIRSPEED_CRUISE
tridge Jan 18, 2024
3d80aac
AP_Soaring: convert remaining uses of TRIM_ARSPD_CM to AIRSPEED_CRUISE
tridge Jan 18, 2024
87294cb
AP_TECS: convert remaining uses of TRIM_ARSPD_CM to AIRSPEED_CRUISE
tridge Jan 18, 2024
1da1cc5
AP_Airspeed: convert ARSPD_FBW_MIN/MAX to AIRSPEED_MIN and AIRSPEED_MAX
tridge Jan 18, 2024
e2a8280
AP_HAL_ChibiOS: convert ARSPD_FBW_MIN/MAX to AIRSPEED_MIN and AIRSPEE…
tridge Jan 18, 2024
89864b8
AP_Landing: convert ARSPD_FBW_MIN/MAX to AIRSPEED_MIN and AIRSPEED_MAX
tridge Jan 18, 2024
89bd6ce
AP_OSD: convert ARSPD_FBW_MIN/MAX to AIRSPEED_MIN and AIRSPEED_MAX
tridge Jan 18, 2024
be8bbdd
AP_Scripting: convert ARSPD_FBW_MIN/MAX to AIRSPEED_MIN and AIRSPEED_MAX
tridge Jan 18, 2024
a070cc3
AP_TECS: convert ARSPD_FBW_MIN/MAX to AIRSPEED_MIN and AIRSPEED_MAX
tridge Jan 18, 2024
5eb448b
SITL: convert ARSPD_FBW_MIN/MAX to AIRSPEED_MIN and AIRSPEED_MAX
tridge Jan 18, 2024
9f46cdc
ArduPlane: convert ARSPD_FBW_MIN/MAX to AIRSPEED_MIN and AIRSPEED_MAX
tridge Jan 18, 2024
0262d25
Tools: convert ARSPD_FBW_MIN/MAX to AIRSPEED_MIN and AIRSPEED_MAX
tridge Jan 18, 2024
03d8a0a
AP_Landing: convert MIN_GNDSPEED_CM to MIN_GROUNDSPEED
tridge Jan 18, 2024
6c211f2
AP_Vehicle: convert MIN_GNDSPEED_CM to MIN_GROUNDSPEED
tridge Jan 18, 2024
c35d368
ArduPlane: convert MIN_GNDSPEED_CM to MIN_GROUNDSPEED
tridge Jan 18, 2024
6eccc1d
AP_HAL_ChibiOS: convert ALT_HOLD_RTL to RTL_ALTITUDE
tridge Jan 18, 2024
599535c
AP_OSD: convert ALT_HOLD_RTL to RTL_ALTITUDE
tridge Jan 18, 2024
7ddc90e
AP_Scripting: convert ALT_HOLD_RTL to RTL_ALTITUDE
tridge Jan 18, 2024
9dd58d3
SITL: convert ALT_HOLD_RTL and ALT_HOLD_FBWCM
tridge Jan 18, 2024
ed2cb2f
ArduPlane: convert ALT_HOLD_RTL and ALT_HOLD_FBWCM
tridge Jan 18, 2024
eaebeed
Tools: convert ALT_HOLD_RTL and ALT_HOLD_FBWCM
tridge Jan 18, 2024
8515679
Tools: fixed name of TRIM_PITCH_DEG
tridge Jan 18, 2024
8ce3118
Plans: rename ALT_CRUISE_MIN to CRUISE_ALT_FLOOR
tridge Jan 19, 2024
4bd2951
SITL: param rename for CRUISE_ALT_FLOOR
tridge Jan 19, 2024
0917244
Tools: param rename for CRUISE_ALT_FLOOR
tridge Jan 19, 2024
b70343f
APM_Control: convert LIM_PITCH_MIN/MAX -> PTCH_LIM_MIN/MAX_DEG
tridge Jan 19, 2024
9bebccd
AP_TECS: convert LIM_PITCH_MIN/MAX -> PTCH_LIM_MIN/MAX_DEG
tridge Jan 19, 2024
4f7893a
AP_Vehicle: convert LIM_PITCH_MIN/MAX -> PTCH_LIM_MIN/MAX_DEG
tridge Jan 19, 2024
d345cde
ArduPlane: convert LIM_PITCH_MIN/MAX -> PTCH_LIM_MIN/MAX_DEG
tridge Jan 19, 2024
8b8030b
AP_HAL_ChibiOS: convert param files for pitch limits
tridge Jan 19, 2024
45999e4
SITL: convert param files for pitch limits
tridge Jan 19, 2024
6861d22
Tools: convert param files for pitch limits
tridge Jan 19, 2024
b82ed52
APM_Control: change LIM_ROLL_CD to ROLL_LIMIT_DEG
tridge Jan 19, 2024
40695aa
AP_Vehicle: change LIM_ROLL_CD to ROLL_LIMIT_DEG
tridge Jan 19, 2024
f4a731b
ArduPlane: change LIM_ROLL_CD to ROLL_LIMIT_DEG
tridge Jan 19, 2024
d74f07b
AP_HAL_ChibiOS: convert param files LIM_ROLL_CD -> ROLL_LIMIT_DEG
tridge Jan 19, 2024
8eee607
SITL: convert param files LIM_ROLL_CD -> ROLL_LIMIT_DEG
tridge Jan 19, 2024
9107d66
Tools: convert param files LIM_ROLL_CD -> ROLL_LIMIT_DEG
tridge Jan 19, 2024
8750f04
AP_Landing: convert LAND_PITCH_CD to LAND_PITCH_DEG
tridge Jan 19, 2024
1f339b9
AP_TECS: convert LAND_PITCH_CD to LAND_PITCH_DEG
tridge Jan 19, 2024
0812e2e
ArduPlane: convert LAND_PITCH_CD to LAND_PITCH_DEG
tridge Jan 19, 2024
28f9739
SITL: convert param files for LAND_PITCH_DEG
tridge Jan 19, 2024
2ec9324
Tools: convert param files for LAND_PITCH_DEG
tridge Jan 19, 2024
930ead6
Plane: TRIM_PITCH_DEG to PTCH_TRIM_DEG
tridge Jan 19, 2024
61480cb
Tools: param file TRIM_PITCH_DEG to PTCH_TRIM_DEG
tridge Jan 19, 2024
fb2d0b6
Plane: Q_LAND_SPEED -> Q_LAND_FINAL_SPD
tridge Jan 19, 2024
1efe224
Tools: param conversion Q_LAND_SPEED -> Q_LAND_FINAL_SPD
tridge Jan 19, 2024
eda6e6f
Plane: Q_VELZ_MAX -> Q_PILOT_SPD_UP and Q_VELZ_MAX_DN -> Q_PILOT_SPD_DN
tridge Jan 19, 2024
f6ab60f
Tools: convert Q_VELZ_MAX to Q_PILOT_SPD_UP
tridge Jan 19, 2024
63b9bd0
Plane: Q_ACCEL_Z -> Q_PILOT_ACCEL_Z
tridge Jan 19, 2024
34846d8
AP_Vehicle: tidy TRIM_PITCH to PTCH_TRIM_DEG
tridge Jan 19, 2024
5b26613
SITL: tidy TRIM_PITCH to PTCH_TRIM_DEG
tridge Jan 19, 2024
a0f2b79
ArduPlane: tidy TRIM_PITCH to PTCH_TRIM_DEG
tridge Jan 19, 2024
6dc078a
autotest: fixed quadplane test
tridge Jan 19, 2024
cebc98e
AP_Scripting: fixed example script
tridge Jan 19, 2024
9975d6d
AP_TECS: fixed param names in comments
tridge Jan 19, 2024
5133148
Plane: tidy 2 comments
tridge Jan 19, 2024
420f20e
RC_Channel: tidy a comment for LAND_PITCH_DEG
tridge Jan 19, 2024
2ca477c
AP_Scripting: fixed parameter names
tridge Jan 19, 2024
23eb606
SITL: fixed parameter names
tridge Jan 19, 2024
7a17836
ArduPlane: fixed parameter names
tridge Jan 19, 2024
d2c5396
Tools: fixed parameter names
tridge Jan 19, 2024
f7a35f6
Tools: added convert_param_scale.py
tridge Jan 19, 2024
b8000f7
AP_HAL_ChibiOS: fixed name of pitch limit parameters
tridge Jan 19, 2024
c30b453
SITL: fixed name of pitch limit parameters
tridge Jan 19, 2024
1f3cb46
Tools: fixed name of pitch limit parameters
tridge Jan 19, 2024
a5c00bb
Tools: fixed incorrect param conversions
tridge Jan 19, 2024
ff164dd
Plane: make the 90x factor more obvios
tridge Jan 19, 2024
55d00f7
AP_Param: whitespace fix
tridge Jan 19, 2024
c431945
Plane: removed incorrect comment
tridge Jan 19, 2024
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
16 changes: 8 additions & 8 deletions ArduPlane/AP_Arming.cpp
Expand Up @@ -76,23 +76,23 @@ bool AP_Arming_Plane::pre_arm_checks(bool display_failure)
ret = false;
}

if (plane.aparm.roll_limit_cd < 300) {
check_failed(display_failure, "LIM_ROLL_CD too small (%u)", (unsigned)plane.aparm.roll_limit_cd);
if (plane.aparm.roll_limit < 3) {
check_failed(display_failure, "ROLL_LIMIT_DEG too small (%.1f)", plane.aparm.roll_limit.get());
ret = false;
}

if (plane.aparm.pitch_limit_max_cd < 300) {
check_failed(display_failure, "LIM_PITCH_MAX too small (%u)", (unsigned)plane.aparm.pitch_limit_max_cd);
if (plane.aparm.pitch_limit_max < 3) {
check_failed(display_failure, "PTCH_LIM_MAX_DEG too small (%.1f)", plane.aparm.pitch_limit_max.get());
ret = false;
}

if (plane.aparm.pitch_limit_min_cd > -300) {
check_failed(display_failure, "LIM_PITCH_MIN too large (%u)", (unsigned)plane.aparm.pitch_limit_min_cd);
if (plane.aparm.pitch_limit_min > -3) {
check_failed(display_failure, "PTCH_LIM_MIN_DEG too large (%.1f)", plane.aparm.pitch_limit_min.get());
ret = false;
}

if (plane.aparm.airspeed_min < MIN_AIRSPEED_MIN) {
check_failed(display_failure, "ARSPD_FBW_MIN too low (%i < %i)", plane.aparm.airspeed_min.get(), MIN_AIRSPEED_MIN);
check_failed(display_failure, "AIRSPEED_MIN too low (%i < %i)", plane.aparm.airspeed_min.get(), MIN_AIRSPEED_MIN);
ret = false;
}

Expand Down Expand Up @@ -454,7 +454,7 @@ bool AP_Arming_Plane::mission_checks(bool report)
prev_cmd.id == MAV_CMD_NAV_WAYPOINT) {
const float dist = cmd.content.location.get_distance(prev_cmd.content.location);
const float tecs_land_speed = plane.TECS_controller.get_land_airspeed();
const float landing_speed = is_positive(tecs_land_speed)?tecs_land_speed:plane.aparm.airspeed_cruise_cm*0.01;
const float landing_speed = is_positive(tecs_land_speed)?tecs_land_speed:plane.aparm.airspeed_cruise;
const float min_dist = 0.75 * plane.quadplane.stopping_distance(sq(landing_speed));
if (dist < min_dist) {
ret = false;
Expand Down
16 changes: 8 additions & 8 deletions ArduPlane/ArduPlane.cpp
Expand Up @@ -172,8 +172,8 @@ void Plane::ahrs_update()
#endif

// calculate a scaled roll limit based on current pitch
roll_limit_cd = aparm.roll_limit_cd;
pitch_limit_min_cd = aparm.pitch_limit_min_cd;
roll_limit_cd = aparm.roll_limit*100;
pitch_limit_min = aparm.pitch_limit_min;

bool rotate_limits = true;
#if HAL_QUADPLANE_ENABLED
Expand All @@ -183,7 +183,7 @@ void Plane::ahrs_update()
#endif
if (rotate_limits) {
roll_limit_cd *= ahrs.cos_pitch();
pitch_limit_min_cd *= fabsf(ahrs.cos_roll());
pitch_limit_min *= fabsf(ahrs.cos_roll());
}

// updated the summed gyro used for ground steering and
Expand Down Expand Up @@ -418,8 +418,8 @@ void Plane::airspeed_ratio_update(void)
return;
}
if (labs(ahrs.roll_sensor) > roll_limit_cd ||
ahrs.pitch_sensor > aparm.pitch_limit_max_cd ||
ahrs.pitch_sensor < pitch_limit_min_cd) {
ahrs.pitch_sensor > aparm.pitch_limit_max*100 ||
ahrs.pitch_sensor < pitch_limit_min*100) {
// don't calibrate when going beyond normal flight envelope
return;
}
Expand Down Expand Up @@ -917,7 +917,7 @@ bool Plane::is_taking_off() const
return control_mode->is_taking_off();
}

// correct AHRS pitch for TRIM_PITCH_CD in non-VTOL modes, and return VTOL view in VTOL
// correct AHRS pitch for PTCH_TRIM_DEG in non-VTOL modes, and return VTOL view in VTOL
void Plane::get_osd_roll_pitch_rad(float &roll, float &pitch) const
{
#if HAL_QUADPLANE_ENABLED
Expand All @@ -929,8 +929,8 @@ void Plane::get_osd_roll_pitch_rad(float &roll, float &pitch) const
#endif
pitch = ahrs.get_pitch();
roll = ahrs.get_roll();
if (!(flight_option_enabled(FlightOptions::OSD_REMOVE_TRIM_PITCH_CD))) { // correct for TRIM_PITCH_CD
pitch -= g.pitch_trim_cd * 0.01 * DEG_TO_RAD;
if (!(flight_option_enabled(FlightOptions::OSD_REMOVE_TRIM_PITCH))) { // correct for PTCH_TRIM_DEG
pitch -= g.pitch_trim * DEG_TO_RAD;
}
}

Expand Down
12 changes: 6 additions & 6 deletions ArduPlane/Attitude.cpp
Expand Up @@ -202,14 +202,14 @@ float Plane::stabilize_pitch_get_pitch_out()
return pitch_out;
}
#endif
// if LANDING_FLARE RCx_OPTION switch is set and in FW mode, manual throttle,throttle idle then set pitch to LAND_PITCH_CD if flight option FORCE_FLARE_ATTITUDE is set
// if LANDING_FLARE RCx_OPTION switch is set and in FW mode, manual throttle,throttle idle then set pitch to LAND_PITCH_DEG if flight option FORCE_FLARE_ATTITUDE is set
#if HAL_QUADPLANE_ENABLED
const bool quadplane_in_transition = quadplane.in_transition();
#else
const bool quadplane_in_transition = false;
#endif

int32_t demanded_pitch = nav_pitch_cd + g.pitch_trim_cd + SRV_Channels::get_output_scaled(SRV_Channel::k_throttle) * g.kff_throttle_to_pitch;
int32_t demanded_pitch = nav_pitch_cd + int32_t(g.pitch_trim * 100.0) + SRV_Channels::get_output_scaled(SRV_Channel::k_throttle) * g.kff_throttle_to_pitch;
bool disable_integrator = false;
if (control_mode == &mode_stabilize && channel_pitch->get_control_in() != 0) {
disable_integrator = true;
Expand Down Expand Up @@ -310,11 +310,11 @@ void Plane::stabilize_stick_mixing_fbw()
pitch_input = -pitch_input;
}
if (pitch_input > 0) {
nav_pitch_cd += pitch_input * aparm.pitch_limit_max_cd;
nav_pitch_cd += pitch_input * aparm.pitch_limit_max*100;
} else {
nav_pitch_cd += -(pitch_input * pitch_limit_min_cd);
nav_pitch_cd += -(pitch_input * pitch_limit_min*100);
}
nav_pitch_cd = constrain_int32(nav_pitch_cd, pitch_limit_min_cd, aparm.pitch_limit_max_cd.get());
nav_pitch_cd = constrain_int32(nav_pitch_cd, pitch_limit_min*100, aparm.pitch_limit_max.get()*100);
}


Expand Down Expand Up @@ -585,7 +585,7 @@ int16_t Plane::calc_nav_yaw_ground(void)
void Plane::calc_nav_pitch()
{
int32_t commanded_pitch = TECS_controller.get_pitch_demand();
nav_pitch_cd = constrain_int32(commanded_pitch, pitch_limit_min_cd, aparm.pitch_limit_max_cd.get());
nav_pitch_cd = constrain_int32(commanded_pitch, pitch_limit_min*100, aparm.pitch_limit_max.get()*100);
}


Expand Down
4 changes: 2 additions & 2 deletions ArduPlane/GCS_Mavlink.cpp
Expand Up @@ -133,8 +133,8 @@ void GCS_MAVLINK_Plane::send_attitude() const
float p = ahrs.get_pitch();
float y = ahrs.get_yaw();

if (!(plane.flight_option_enabled(FlightOptions::GCS_REMOVE_TRIM_PITCH_CD))) {
p -= radians(plane.g.pitch_trim_cd * 0.01f);
if (!(plane.flight_option_enabled(FlightOptions::GCS_REMOVE_TRIM_PITCH))) {
p -= radians(plane.g.pitch_trim);
}

#if HAL_QUADPLANE_ENABLED
Expand Down
109 changes: 60 additions & 49 deletions ArduPlane/Parameters.cpp
Expand Up @@ -267,28 +267,35 @@ const AP_Param::Info Plane::var_info[] = {

// @Param: STALL_PREVENTION
// @DisplayName: Enable stall prevention
// @Description: Enables roll limits at low airspeed in roll limiting flight modes. Roll limits based on aerodynamic load factor in turns and scale on ARSPD_FBW_MIN that must be set correctly. Without airspeed sensor, uses synthetic airspeed from wind speed estimate that may both be inaccurate.
// @Description: Enables roll limits at low airspeed in roll limiting flight modes. Roll limits based on aerodynamic load factor in turns and scale on AIRSPEED_MIN that must be set correctly. Without airspeed sensor, uses synthetic airspeed from wind speed estimate that may both be inaccurate.
// @Values: 0:Disabled,1:Enabled
// @User: Standard
ASCALAR(stall_prevention, "STALL_PREVENTION", 1),

// @Param: ARSPD_FBW_MIN
// @Param: AIRSPEED_CRUISE
tridge marked this conversation as resolved.
Show resolved Hide resolved
// @DisplayName: Target cruise airspeed
// @Description: Target cruise airspeed in m/s in automatic throttle modes. Value is as an indicated (calibrated/apparent) airspeed.
// @Units: m/s
// @User: Standard
ASCALAR(airspeed_cruise, "AIRSPEED_CRUISE", AIRSPEED_CRUISE),

// @Param: AIRSPEED_MIN
// @DisplayName: Minimum Airspeed
// @Description: Minimum airspeed demanded in automatic throttle modes. Should be set to 20% higher than level flight stall speed.
// @Units: m/s
// @Range: 5 100
// @Increment: 1
// @User: Standard
ASCALAR(airspeed_min, "ARSPD_FBW_MIN", AIRSPEED_FBW_MIN),
ASCALAR(airspeed_min, "AIRSPEED_MIN", AIRSPEED_FBW_MIN),

// @Param: ARSPD_FBW_MAX
// @Param: AIRSPEED_MAX
// @DisplayName: Maximum Airspeed
// @Description: Maximum airspeed demanded in automatic throttle modes. Should be set slightly less than level flight speed at THR_MAX and also at least 50% above ARSPD_FBW_MIN to allow for accurate TECS altitude control.
// @Description: Maximum airspeed demanded in automatic throttle modes. Should be set slightly less than level flight speed at THR_MAX and also at least 50% above AIRSPEED_MIN to allow for accurate TECS altitude control.
// @Units: m/s
// @Range: 5 100
// @Increment: 1
// @User: Standard
ASCALAR(airspeed_max, "ARSPD_FBW_MAX", AIRSPEED_FBW_MAX),
ASCALAR(airspeed_max, "AIRSPEED_MAX", AIRSPEED_FBW_MAX),

// @Param: FBWB_ELEV_REV
// @DisplayName: Fly By Wire elevator reverse
Expand Down Expand Up @@ -401,7 +408,7 @@ const AP_Param::Info Plane::var_info[] = {

// @Param: TRIM_THROTTLE
// @DisplayName: Throttle cruise percentage
// @Description: Target percentage of throttle to apply for flight in automatic throttle modes and throttle percentage that maintains TRIM_ARSPD_CM. Caution: low battery voltages at the end of flights may require higher throttle to maintain airspeed.
// @Description: Target percentage of throttle to apply for flight in automatic throttle modes and throttle percentage that maintains AIRSPEED_CRUISE. Caution: low battery voltages at the end of flights may require higher throttle to maintain airspeed.
// @Units: %
// @Range: 0 100
// @Increment: 1
Expand All @@ -410,7 +417,7 @@ const AP_Param::Info Plane::var_info[] = {

// @Param: THROTTLE_NUDGE
// @DisplayName: Throttle nudge enable
// @Description: When enabled, this uses the throttle input in auto-throttle modes to 'nudge' the throttle or airspeed to higher or lower values. When you have an airspeed sensor the nudge affects the target airspeed, so that throttle inputs above 50% will increase the target airspeed from TRIM_ARSPD_CM up to a maximum of ARSPD_FBW_MAX. When no airspeed sensor is enabled the throttle nudge will push up the target throttle for throttle inputs above 50%.
// @Description: When enabled, this uses the throttle input in auto-throttle modes to 'nudge' the throttle or airspeed to higher or lower values. When you have an airspeed sensor the nudge affects the target airspeed, so that throttle inputs above 50% will increase the target airspeed from AIRSPEED_CRUISE up to a maximum of AIRSPEED_MAX. When no airspeed sensor is enabled the throttle nudge will push up the target throttle for throttle inputs above 50%.
// @Values: 0:Disabled,1:Enabled
// @User: Standard
GSCALAR(throttle_nudge, "THROTTLE_NUDGE", 1),
Expand Down Expand Up @@ -505,32 +512,32 @@ const AP_Param::Info Plane::var_info[] = {
// @User: Advanced
GSCALAR(initial_mode, "INITIAL_MODE", Mode::Number::MANUAL),

// @Param: LIM_ROLL_CD
// @Param: ROLL_LIMIT_DEG
// @DisplayName: Maximum Bank Angle
// @Description: Maximum bank angle commanded in modes with stabilized limits. Increase this value for sharper turns, but decrease to prevent accelerated stalls.
// @Units: cdeg
// @Range: 0 9000
// @Increment: 10
// @Units: deg
// @Range: 0 90
// @Increment: 0.1
// @User: Standard
ASCALAR(roll_limit_cd, "LIM_ROLL_CD", HEAD_MAX_CENTIDEGREE),
ASCALAR(roll_limit, "ROLL_LIMIT_DEG", ROLL_LIMIT_DEG),

// @Param: LIM_PITCH_MAX
// @Param: PTCH_LIM_MAX_DEG
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

In copter we've used the short form, PIT when we didn't have enough room for Pitch.

// @DisplayName: Maximum Pitch Angle
// @Description: Maximum pitch up angle commanded in modes with stabilized limits.
// @Units: cdeg
// @Range: 0 9000
// @Units: deg
// @Range: 0 90
// @Increment: 10
// @User: Standard
ASCALAR(pitch_limit_max_cd, "LIM_PITCH_MAX", PITCH_MAX_CENTIDEGREE),
ASCALAR(pitch_limit_max, "PTCH_LIM_MAX_DEG", PITCH_MAX),

// @Param: LIM_PITCH_MIN
// @Param: PTCH_LIM_MIN_DEG
// @DisplayName: Minimum Pitch Angle
// @Description: Maximum pitch down angle commanded in modes with stabilized limits
// @Units: cdeg
// @Range: -9000 0
// @Range: -90 0
// @Increment: 10
// @User: Standard
ASCALAR(pitch_limit_min_cd, "LIM_PITCH_MIN", PITCH_MIN_CENTIDEGREE),
ASCALAR(pitch_limit_min, "PTCH_LIM_MIN_DEG", PITCH_MIN),

// @Param: ACRO_ROLL_RATE
// @DisplayName: ACRO mode roll rate
Expand Down Expand Up @@ -621,13 +628,6 @@ const AP_Param::Info Plane::var_info[] = {
// @User: Advanced
GSCALAR(log_bitmask, "LOG_BITMASK", DEFAULT_LOG_BITMASK),

// @Param: TRIM_ARSPD_CM
// @DisplayName: Target airspeed
// @Description: Target airspeed in cm/s in automatic throttle modes. Value is as an indicated (calibrated/apparent) airspeed.
// @Units: cm/s
// @User: Standard
ASCALAR(airspeed_cruise_cm, "TRIM_ARSPD_CM", AIRSPEED_CRUISE_CM),

// @Param: SCALING_SPEED
// @DisplayName: speed used for speed scaling calculations
// @Description: Airspeed in m/s to use when calculating surface speed scaling. Note that changing this value will affect all PID values
Expand All @@ -637,35 +637,34 @@ const AP_Param::Info Plane::var_info[] = {
// @User: Advanced
GSCALAR(scaling_speed, "SCALING_SPEED", SCALING_SPEED),

// @Param: MIN_GNDSPD_CM
// @Param: MIN_GROUNDSPEED
tridge marked this conversation as resolved.
Show resolved Hide resolved
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

MIn should not really be at the front if possible.

// @DisplayName: Minimum ground speed
// @Description: Minimum ground speed in cm/s when under airspeed control
// @Units: cm/s
// @Units: m/s
// @User: Advanced
ASCALAR(min_gndspeed_cm, "MIN_GNDSPD_CM", MIN_GNDSPEED_CM),
ASCALAR(min_groundspeed, "MIN_GROUNDSPEED", MIN_GROUNDSPEED),

// @Param: TRIM_PITCH_CD
// @Param: PTCH_TRIM_DEG
tridge marked this conversation as resolved.
Show resolved Hide resolved
tridge marked this conversation as resolved.
Show resolved Hide resolved
// @DisplayName: Pitch angle offset
// @Description: Offset applied to AHRS pitch used for in-flight pitch trimming. Correct ground leveling is better than changing this parameter.
// @Units: cdeg
// @Range: -4500 4500
// @Increment: 10
// @User: Advanced
GSCALAR(pitch_trim_cd, "TRIM_PITCH_CD", 0),
// @Description: Offset in degrees used for in-flight pitch trimming for level flight. Correct ground leveling is an alternative to changing this parameter.
// @Units: deg
// @Range: -45 45
// @User: Standard
GSCALAR(pitch_trim, "PTCH_TRIM_DEG", 0.0f),

// @Param: ALT_HOLD_RTL
// @Param: RTL_ALTITUDE
tridge marked this conversation as resolved.
Show resolved Hide resolved
// @DisplayName: RTL altitude
// @Description: Target altitude above home for RTL mode. Maintains current altitude if set to -1. Rally point altitudes are used if plane does not return to home.
// @Units: cm
// @Units: m
// @User: Standard
GSCALAR(RTL_altitude_cm, "ALT_HOLD_RTL", ALT_HOLD_HOME_CM),
GSCALAR(RTL_altitude, "RTL_ALTITUDE", ALT_HOLD_HOME),

// @Param: ALT_HOLD_FBWCM
// @DisplayName: Minimum altitude for FBWB mode
// @Description: This is the minimum altitude in centimeters (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: cm
// @Param: CRUISE_ALT_FLOOR
tridge marked this conversation as resolved.
Show resolved Hide resolved
// @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_cm, "ALT_HOLD_FBWCM", ALT_HOLD_FBW_CM),
GSCALAR(cruise_alt_floor, "CRUISE_ALT_FLOOR", CRUISE_ALT_FLOOR),
tridge marked this conversation as resolved.
Show resolved Hide resolved

// @Param: FLAP_1_PERCNT
// @DisplayName: Flap 1 percentage
Expand Down Expand Up @@ -1091,12 +1090,12 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
// @Bitmask: 1: Use centered throttle in Cruise or FBWB to indicate trim airspeed
// @Bitmask: 2: Disable attitude check for takeoff arming
// @Bitmask: 3: Force target airspeed to trim airspeed in Cruise or FBWB
// @Bitmask: 4: Climb to ALT_HOLD_RTL before turning for RTL
// @Bitmask: 4: Climb to RTL_ALTITUDE before turning for RTL
// @Bitmask: 5: Enable yaw damper in acro mode
// @Bitmask: 6: Supress speed scaling during auto takeoffs to be 1 or less to prevent oscillations without airspeed sensor.
// @Bitmask: 7: EnableDefaultAirspeed for takeoff
// @Bitmask: 8: Remove the TRIM_PITCH_CD on the GCS horizon
// @Bitmask: 9: Remove the TRIM_PITCH_CD on the OSD horizon
// @Bitmask: 8: Remove the PTCH_TRIM_DEG on the GCS horizon
// @Bitmask: 9: Remove the PTCH_TRIM_DEG on the OSD horizon
// @Bitmask: 10: Adjust mid-throttle to be TRIM_THROTTLE in non-auto throttle modes except MANUAL
// @Bitmask: 11: Disable suppression of fixed wing rate gains in ground mode
// @Bitmask: 12: Enable FBWB style loiter altitude control
Expand Down Expand Up @@ -1314,7 +1313,6 @@ static const AP_Param::ConversionInfo conversion_table[] = {

{ Parameters::k_param_land_slope_recalc_shallow_threshold,0,AP_PARAM_FLOAT, "LAND_SLOPE_RCALC" },
{ Parameters::k_param_land_slope_recalc_steep_threshold_to_abort,0,AP_PARAM_FLOAT, "LAND_ABORT_DEG" },
{ Parameters::k_param_land_pitch_cd, 0, AP_PARAM_INT16, "LAND_PITCH_CD" },
Copy link
Member

@IamPete1 IamPete1 Jan 23, 2024

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I wonder if we should just take the opportunity to remove all of these landing param conversions. With this change you get most converted but not all. Looks like there 8 years old. #5269

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

separate PR so I don't need to retest for the 4.5 beta

{ Parameters::k_param_land_flare_alt, 0, AP_PARAM_FLOAT, "LAND_FLARE_ALT" },
{ Parameters::k_param_land_flare_sec, 0, AP_PARAM_FLOAT, "LAND_FLARE_SEC" },
{ Parameters::k_param_land_pre_flare_sec, 0, AP_PARAM_FLOAT, "LAND_PF_SEC" },
Expand Down Expand Up @@ -1545,6 +1543,19 @@ void Plane::load_parameters(void)
#if AP_FENCE_ENABLED
AP_Param::convert_class(g.k_param_fence, &fence, fence.var_info, 0, 0, true);
#endif

// PARAMETER_CONVERSION - Added: Dec 2023
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
// PARAMETER_CONVERSION - Added: Dec 2023
// PARAMETER_CONVERSION - Added: Jan 2023 for Plane 4.5

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Jan 2024?

// Convert _CM (centimeter) parameters to meters and _CD (centidegrees) parameters to meters
g.pitch_trim.convert_centi_parameter(AP_PARAM_INT16);
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.cruise_alt_floor.convert_centi_parameter(AP_PARAM_INT16);
aparm.pitch_limit_max.convert_centi_parameter(AP_PARAM_INT16);
aparm.pitch_limit_min.convert_centi_parameter(AP_PARAM_INT16);
aparm.roll_limit.convert_centi_parameter(AP_PARAM_INT16);

landing.convert_parameters();

hal.console->printf("load_all took %uus\n", (unsigned)(micros() - before));
}