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

Conversation

tridge
Copy link
Contributor

@tridge tridge commented Jan 18, 2024

This builds on #25768 and converts:

  • TRIM_PITCH_CD -> PTCH_TRIM_DEG
  • TRIM_ARSPD_CM -> AIRSPEED_CRUISE
  • ARSPD_FBW_MIN -> AIRSPEED_MIN
  • ARSPD_FBW_MAX -> AIRSPEED_MAX
  • ALT_HOLD_RTL -> RTL_ALTITUDE
  • ALT_HOLD_FBWCM -> CRUISE_ALT_FLOOR ?
  • LIM_PITCH_MAX -> PTCH_LIM_MAX_DEG ?
  • LIM_PITCH_MIN -> PTCH_LIM_MIN_DEG ?
  • LIM_ROLL_CD -> ROLL_LIMIT_DEG ?
  • LAND_PITCH_CD -> LAND_PITCH_DEG ?
  • Q_LAND_SPEED -> Q_LAND_FINAL_SPD ? (matches Q_LAND_FINAL_ALT)
  • Q_VELZ_MAX -> Q_PILOT_SPD_UP ?
  • Q_VELZ_MAX_DN -> Q_PILOT_SPD_DN ?
  • Q_ACCEL_Z -> Q_PILOT_ACCEL_Z ?

This includes one real bug fix, in AP_Landing::type_slope_get_target_airspeed_cm() where cm and m was mixed up

@tridge
Copy link
Contributor Author

tridge commented Jan 18, 2024

ping @timtuxworth

@peterbarker
Copy link
Contributor

So we use AIRSPEED_CRUISE in cruise mode, presumably...

Why not AIRSPEED_TRIM? Being analogous with e.g. SERVO3_MIN/MAX/TRIM

@timtuxworth
Copy link
Contributor

timtuxworth commented Jan 18, 2024

So we use AIRSPEED_CRUISE in cruise mode, presumably...

Why not AIRSPEED_TRIM? Being analogous with e.g. SERVO3_MIN/MAX/TRIM

This is not just about cruise mode, it applies in all auto modes, e,g. if you flip to LOITER it will try to loiter at this speed, it's the default flying speed in AUTO if you don't set a specific speed. I think Pete's comment raises an issue though - it will definitely confuse people to have _CRUISE as the parameter name for a parameter that is NOT specifically about CRUISE mode.

I do like CRUISE - it is more understandable to new/casual users. I can sort of see Pete's point, but it really isn't the same concept, especially for plane users who might come from RC, 'trim' is about setting the surfaces' hands off location, this airspeed value is not that. The only other name I can think of that would make sense might be AIRSPEED_AUTO.

I'll make one last comment that I really think it should be ARSPD not AIRSPEED for consistency, but I won't mention it again.

@timtuxworth
Copy link
Contributor

Do you think Q_TRIM_PITCH should be converted to Q_TRIM_PITCH_DEG @tridge ? I think it would be a good idea for consistency.

I was looking at doing that in my PR, it's a very simple change.

@timtuxworth
Copy link
Contributor

This builds on #25768 and converts:

Does this mean my PR should be closed then?

Copy link
Contributor

@timtuxworth timtuxworth left a comment

Choose a reason for hiding this comment

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

Some suggestions, some fixes from my own incomplete work. (mostly leftover PITCH_TRIM needing _DEG in param files).

ArduPlane/Parameters.cpp Show resolved Hide resolved
ArduPlane/Parameters.cpp Show resolved Hide resolved
ArduPlane/Parameters.cpp Outdated Show resolved Hide resolved
ArduPlane/Parameters.h Outdated Show resolved Hide resolved
Tools/Frame_params/QuadPlanes/MFE_StriverMini.param Outdated Show resolved Hide resolved
Tools/autotest/default_params/plane-jsbsim.parm Outdated Show resolved Hide resolved
Tools/autotest/default_params/vee-gull 005.param Outdated Show resolved Hide resolved
Tools/autotest/models/plane.parm Outdated Show resolved Hide resolved
@IamPete1
Copy link
Member

I will re-state that I'm not a fan of adding _DEG all over the place. I also point out that this does not follow that pattern for speed params eg MIN_GNDSPD_CM -> MIN_GROUNDSPEED not MIN_GNDSPD_MTR. I count 5 angular conversions all getting _DEG, there are 8 speed/distance/accel conversions none of which get units in the name. Why are angular params special?

@timtuxworth
Copy link
Contributor

I will re-state that I'm not a fan of adding _DEG all over the place. I also point out that this does not follow that pattern for speed params eg MIN_GNDSPD_CM -> MIN_GROUNDSPEED not MIN_GNDSPD_MTR. I count 5 angular conversions all getting _DEG, there are 8 speed/distance/accel conversions none of which get units in the name. Why are angular params special?

What convinced me was finding some Q_ parameters (e.g. Q_ANGLE_MAX) that were in centi-degrees that did NOT have _CD at the end, so anyone using a converted parameter might easily use centidegrees when the refactored parameter should be degrees. So Q_ANGLE_MAX needs to become Q_ANGLE_MAX_DEG otherwise - planes will fall from the sky. So by extension if you are adding _DEG for one it should be added for all.

MIN_GROUNDSPEED (should be GROUNDSPEED_MIN) is a velocity not a distance, but I note that ALT_HOLD_RTL (was centimeters) is now RTL_ALTITUDE - and yes maybe it could be RTL_ALT_M for a similar reasons (I think "M" should be ok for meters, it's a standard).

veloclity and accelerations are harder. centidegrees/s and centidegrees/s/s (yes we have both) become what? "DEGS", "DS" and "DEGSS" and "DSS"? hardly user friendly. GROUNDSPEED_MIN could be GROUNDSPEED_MIN_MS - oh wait, is that milliseconds? :-D

In essence, I think the call is - _CD becomes _DEG because the risk is higher with this one, but otherwise - no units in the name, it's in the metadata - right? Do less harm.

@IamPete1
Copy link
Member

IamPete1 commented Jan 19, 2024

In essence, I think the call is - _CD becomes _DEG because the risk is higher with this one, but otherwise - no units in the name, it's in the metadata - right? Do less harm.

I'm not sure that is really true that the angle params are more "risky", there are plenty of scenarios where incorrect params make bad things happen. Don't forget the risk to the vehicle it's self not the only factor. The obvious example is setting your RTL alt 100 times too high will not cause your vehicle to crash (into the ground anyway).

The whole point of the rename is to make the parameters more consistent with units and naming. We only currently have one parameter with DEG in the name (LAND_ABORT_DEG). So the new pattern of adding DEG actually makes us less consistent not more. I accept that it might be a good idea to add DEG for a few releases to make the changes less painful for users, then we can come back and remove DEG in the future and then we get our consistency. But if were doing that for DEG params then surely we should do it for the speed/distance/accel params too. If users struggle with one they will struggle with the other.

Copy link
Contributor

@timtuxworth timtuxworth left a comment

Choose a reason for hiding this comment

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

Oh I had a pending review - sorry.

Tools/Frame_params/EFlight_Convergence.param Outdated Show resolved Hide resolved
Tools/Frame_params/Parrot_Disco/Parrot_Disco.param Outdated Show resolved Hide resolved
Tools/Frame_params/QuadPlanes/MFE_StriverMini.param Outdated Show resolved Hide resolved
ArduPlane/Parameters.h Outdated Show resolved Hide resolved
@tridge
Copy link
Contributor Author

tridge commented Jan 20, 2024

I count 5 angular conversions all getting _DEG, there are 8 speed/distance/accel conversions none of which get units in the name. Why are angular params special?

it is a per-parameter judgement, but it is partly because there is no obvious suffix for m/s that users will instantly recognise, whereas I think all users will understand XX_DEG as being degrees

@tridge
Copy link
Contributor Author

tridge commented Jan 20, 2024

Why not AIRSPEED_TRIM? Being analogous with e.g. SERVO3_MIN/MAX/TRIM

I discussed with @priseborough and he and I agreed it really has nothing to do with "trim". The "cruise" speed of an aircraft is standard parlance for what this variable represents, the original "trim" name was a mistake

@rmackay9
Copy link
Contributor

rmackay9 commented Jan 20, 2024

These two look suspicious because of the swapping of "Alt" and "Cruise"... also "min" and "floor" are very similar.

  • ALT_CRUISE_MIN
  • CRUISE_ALT_FLOOR

We should be careful that when MIN, MAX, TRIM etc are in the parameter name that they appear at the end except when the parameter name includes the Units. In this case it become Min/Max/Trim _ Units. I think this is all fine in this PR but I haven't checked everything carefully.


// @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.

@@ -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
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.

//
#ifndef MIN_GNDSPEED
# define MIN_GNDSPEED 0 // m/s (0 disables)
#ifndef MIN_GROUNDSPEED
Copy link
Contributor

Choose a reason for hiding this comment

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

If the definitions being changed, I'd also put the MIN at the end.

Copy link
Contributor

Choose a reason for hiding this comment

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

If the definitions being changed, I'd also put the MIN at the end.

Agree

@tridge
Copy link
Contributor Author

tridge commented Jan 20, 2024

Everyone please concentrate on actual errors in this PR. It is clear we're not going to get any two people to agree on every point, so what I want if for it to meet the main objectives

@@ -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?

Copy link
Member

@IamPete1 IamPete1 left a comment

Choose a reason for hiding this comment

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

Basically looks good, I left a few comments, but no bugs I can see.

@@ -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

@@ -359,9 +359,9 @@ void Plane::check_fbwb_altitude(void)
}
#endif

if (g.FBWB_min_altitude_cm != 0) {
Copy link
Member

Choose a reason for hiding this comment

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

This is a change in behavior. I guess setting a negative altitude is a bit of a edge case, especially if 0 is a magic disable.

break;
case AUTOTUNE_PITCH:
att_limit_deg = MIN(abs(aparm.pitch_limit_max_cd),abs(aparm.pitch_limit_min_cd))*0.01;
att_limit_deg = MIN(abs(aparm.pitch_limit_max*100),abs(aparm.pitch_limit_min*100))*0.01;
Copy link
Member

Choose a reason for hiding this comment

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

Suggested change
att_limit_deg = MIN(abs(aparm.pitch_limit_max*100),abs(aparm.pitch_limit_min*100))*0.01;
att_limit_deg = MIN(fabsf(aparm.pitch_limit_max), fabsf(aparm.pitch_limit_min));

@tridge tridge merged commit e602aa6 into ArduPilot:master Jan 23, 2024
93 checks passed
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
Plane WikiNeeded needs wiki update
Projects
None yet
Development

Successfully merging this pull request may close these issues.

None yet

8 participants