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

Do not allow users to set throttle-based notch in Heli #28843

Merged
merged 2 commits into from
Jan 21, 2025

Conversation

MattKear
Copy link
Contributor

@MattKear MattKear commented Dec 11, 2024

My attempt at fixing issue: #28841

Throttle is not "Throttle" in AP_MotorsHeli, it is actually collective position. Therefore, throttle-based tracking does not make any sense for Heli.

This is a subtly that most users will not appreciate, therefore we should help users to not make this mistake by throwing a config error if selected.

Have also changed the default notch mode for heli.

Tested in SITL only. This is how it presents to the user upon miss-configuration:

image

Copy link
Collaborator

@andyp1per andyp1per left a comment

Choose a reason for hiding this comment

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

LGTM, just would like to see the types called out explicitly

libraries/Filter/HarmonicNotchFilter.cpp Outdated Show resolved Hide resolved
@Hwurzburg Hwurzburg added the WikiNeeded needs wiki update label Dec 13, 2024
@MattKear MattKear force-pushed the pr_harm_ntch_heli_default branch from ea5a4ea to c0c5fe9 Compare January 17, 2025 15:36
Copy link
Contributor

@bnsgeyer bnsgeyer left a comment

Choose a reason for hiding this comment

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

@MattKear Thanks for this PR. LGTM

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.

LGTM

@tridge tridge merged commit 634cb02 into ArduPilot:master Jan 21, 2025
99 checks passed
// Throttle tracking does not make sense with heli because "throttle" is actually collective position in AP_MotorsHeli
for (auto &notch : harmonic_notches) {
if (notch.params.enabled() && notch.params.tracking_mode() == HarmonicNotchDynamicMode::UpdateThrottle) {
AP_BoardConfig::config_error("Throttle notch unavailable with heli");
Copy link
Contributor

Choose a reason for hiding this comment

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

Upon further though, I think it might have been better if this had been made an arming check. With a config_error the main loop won't run and the user will find the HUD doesn't update. Sadly this will only happen the next time that they reboot the board so they may not remember that they changed the harmonic notch method

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
Projects
None yet
Development

Successfully merging this pull request may close these issues.

8 participants