Skip to content

Copter: Trust get-pilot-desired methods check RC input for validity #30070

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

Merged
merged 1 commit into from
May 14, 2025

Conversation

peterbarker
Copy link
Contributor

@peterbarker peterbarker commented May 14, 2025

.... which they do, for the most part.

This PR removes special-case logic in Loiter and ZigZag which check for radio failsafe before updating the loiter controller with values returned from them (etc.).

Those methods already check that RC input is good (improvements coming there, however!). So rely on those methods returning sensible values when there's no RC present. Several other modes already make the assumption that these methods do sensible things (eg. ModeAltHold!).

Note that clear_pilot_desired_acceleration just sets (0, 0), and get_pilot_desired_lean_angles sets target-roll/target-pitch to zero if RC input is bad).

There is a second fix in here where checks were insufficient when looking at RC values. This is the update_simple_mode method matches. We not only have to check that a new frame has been received, but that the values are generally good ie. not coming in at bind-mode values. This is a minimal patch to allow for the first patch to go in - there's plenty else wrong in the radio codepath which will be fixed in a future PR (eg. incorporating bind-time values into the throttle filter, setting the throttle-zero flag). This is also a bugfix for several methods which already transform the pilot inputs. - this was moved to a different PR

@peterbarker peterbarker force-pushed the pr/trust-control-values branch 2 times, most recently from 1fb7352 to 5ddcb53 Compare May 14, 2025 05:29
this stops ArduCopter looking at the RC failsafe values before trusting return values from varios methods like get_pilot_target_climb_rate_cms

Several other modes already make the assumption that if there's no good pilot input that these methods return 0
@peterbarker peterbarker force-pushed the pr/trust-control-values branch from 5ddcb53 to f633774 Compare May 14, 2025 05:30
Copy link
Contributor

@rmackay9 rmackay9 left a comment

Choose a reason for hiding this comment

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

LGTM, thanks.

The only function change is in update_simple_mode() which doesn't directly check the failsafe.radio boolean but instead checks the ap.new_radio_frame. So this is a slight change in behaviour in that the RC roll and pitch values could be updated now when they weren't before. I think there could only be an issue if the failsafe cleared without ap.new_radio_frame becoming true. It's slightly hard to imagine how this could happen and how it could cause a problem

@peterbarker
Copy link
Contributor Author

LGTM, thanks.

The only function change is in update_simple_mode() which doesn't directly check the failsafe.radio boolean but instead checks the ap.new_radio_frame. So this is a slight change in behaviour in that the RC roll and pitch values could be updated now when they weren't before. I think there could only be an issue if the failsafe cleared without ap.new_radio_frame becoming true. It's slightly hard to imagine how this could happen and how it could cause a problem

Yes, quite right - but we're already calling that method in similar circumstances. And it should be fixed by #30071 :-)

@lthall lthall self-requested a review May 14, 2025 11:37
Copy link
Contributor

@lthall lthall left a comment

Choose a reason for hiding this comment

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

This is a good change.

@lthall lthall self-requested a review May 14, 2025 11:38
@peterbarker peterbarker merged commit 8aa3c36 into ArduPilot:master May 14, 2025
81 checks passed
@peterbarker peterbarker deleted the pr/trust-control-values branch May 16, 2025 01:33
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Projects
None yet
Development

Successfully merging this pull request may close these issues.

3 participants