-
Notifications
You must be signed in to change notification settings - Fork 14k
Remove MPC_USE_HTE
and always use hover thrust for altitude control
#24751
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
base: main
Are you sure you want to change the base?
Conversation
Note the separate module can still be not run but I have not seen a case where the hover thrust estimate is not useful for altitude control hence I don't expect anyone to have the parameter disabled or planning on not running the module. This parameter was used to experimentally introduce the hover thrust estimator. First it was just logging its status and you could opt in to use it: f9794e9 but soon after it became the default and you had to opt out of using it: a8063ac AFAIK we haven't seen problems requiring to disable it in the last 5 years and hence I suggest to remove the parameter to reduce the configuration space.
🔎 FLASH Analysispx4_fmu-v5x [Total VM Diff: -56 byte (-0 %)]
px4_fmu-v6x [Total VM Diff: -136 byte (-0.01 %)]
Updated: 2025-04-22T17:08:31 |
This pull request has been mentioned on Discussion Forum for PX4, Pixhawk, QGroundControl, MAVSDK, MAVLink. There might be relevant details there: |
I flight tested this yesterday and all seemed well. |
No flaws found |
@dakejahl Thanks for testing! I had a quick glance and it looks good from my perspective with this pull request in mind: |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Just a small comment. All good otherwise!
@@ -98,12 +97,12 @@ void MulticopterLandDetector::_update_topics() | |||
_flag_control_climb_rate_enabled = vehicle_control_mode.flag_control_climb_rate_enabled; | |||
} | |||
|
|||
if (_params.useHoverThrustEstimate) { | |||
if (_hover_thrust_estimate_sub.updated()) { | |||
hover_thrust_estimate_s hte; | |||
|
|||
if (_hover_thrust_estimate_sub.update(&hte)) { |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
if (_hover_thrust_estimate_sub.update(&hte)) { | |
if (_hover_thrust_estimate_sub.copy(&hte)) { |
Since you already have the updated
above.
Solved Problem
When we discussed #24710 in the dev call and agreed once again we need to reduce the configuration space, I realized I would never change this parameter to 0 or advise someone to do so. It was introduced beginning 2020 to experimentally introduce the hover thrust estimator but was soon after enabled by default and I have not seen anyone turn it off.
References:
Hover thrust estimator introduction: #13981
Addition of the parameter (and many improvements): #14182
Enabling use of the estimate the default: #14419
Solution
Note the separate
mc_hover_thrust_estimator
module can still be not run but I have not seen a case where the hover thrust estimate is not useful for altitude control hence I don't expect anyone to have the parameter disabled or planning on not running the module.Please review the cases where the hover thrust is not available or gets invalid. My intention is to keep on using the last valid estimate like for the stick rescaling in Stabilized mode. This is in my eyes better than jumping back to the hover thrust parameter. I left the safety logic to make landing detection checks more strict with invalid hover thrust.
Changelog Entry
Test coverage
I have not tested this pr. But can do so if we decide to go forward with it.