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: ignore invalid pilot throttle #25633

Merged
merged 2 commits into from
Nov 29, 2023

Conversation

IamPete1
Copy link
Member

Extract from #25416 superseding #25631

This now always ignores pilot throttle if there is invalid RC. Currently on master you can get stuck at your last throttle in some cases with guided or suppressed passthrough and manual mode. This should be covered by the set_control_in call here:

channel_throttle->set_control_in(0);

However that does not fix all cases.

If we call get_throttle_input(true) to get the no deadzone value we call get_control_in_zero_dz:

/*
return control in from the radio throttle channel.
*/
float Plane::get_throttle_input(bool no_deadzone) const
{
float ret;
if (no_deadzone) {
ret = channel_throttle->get_control_in_zero_dz();
} else {
ret = channel_throttle->get_control_in();
}
if (reversed_throttle) {
// RC option for reverse throttle has been set
ret = -ret;
}
return ret;
}

However, get_control_in_zero_dz does not use control_in it uses radio_in so our set_control_in call is bypassed.

int16_t RC_Channel::get_control_in_zero_dz(void) const
{
if (type_in == ControlType::RANGE) {
return pwm_to_range_dz(0);
}
return pwm_to_angle_dz(0);
}

/*
convert a pulse width modulation value to a value in the configured
range, using the specified deadzone
*/
int16_t RC_Channel::pwm_to_range_dz(uint16_t _dead_zone) const
{
int16_t r_in = constrain_int16(radio_in, radio_min.get(), radio_max.get());
if (reversed) {
r_in = radio_max.get() - (r_in - radio_min.get());
}
int16_t radio_trim_low = radio_min + _dead_zone;
if (r_in > radio_trim_low) {
return (((int32_t)(high_in) * (int32_t)(r_in - radio_trim_low)) / (int32_t)(radio_max - radio_trim_low));
}
return 0;
}

The problem with get_adjusted_throttle_input is that is uses norm_input with again bypasses control_in

Recreation:

Turn off short fail-safe (FS_SHORT_ACTN 3)
Arm and go to full throttle in manual.
Have a RC fail-safe, (SIM_RC_FAIL 1)

Master:
Throttle remains at 100% until long action.

image

PR:

Throttle goes to 0 as soon as RC is lost, throttle is output again once in RTL.
image

The same issue also affects roll/pitch/yaw inputs in some modes....

@@ -547,9 +547,7 @@ void Plane::set_servos_controlled(void)
control_mode == &mode_fbwa ||
control_mode == &mode_autotune) {
// a manual throttle mode
if (!rc().has_valid_input()) {
Copy link
Member Author

@IamPete1 IamPete1 Nov 25, 2023

Choose a reason for hiding this comment

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

Now were handling it in the get_throttle_input and get_adjusted_throttle_input calls we don't need this check.

Copy link
Contributor

@tridge tridge left a comment

Choose a reason for hiding this comment

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

it would be good to test QSTAB, QACRO, QHOVER, QLOITER, make sure they don't lose height during the short rc failsafe period

@IamPete1
Copy link
Member Author

IamPete1 commented Nov 28, 2023

Added a commit to be sure that quadplane behaves the same, it is a re-implementation of the no deadzone case of get_throttle_input returning the set control in value rather than 0 in failsafe. These are exclusively used when comparing throttle to some threshold for things like throttle wait and suppression.

Also re-checked with SIM_RC_FAIL 2. Behavior is the same.

Tested Q modes to make sure we don't fall out of the sky.

Qstab and Qacro we get hover throttle.

image

Qhover and Qloiter a slow descent.

image

@IamPete1 IamPete1 force-pushed the plane_ignore_invalid_pilot_throttle branch from f7df379 to 35524b9 Compare November 28, 2023 18:25
float ret = plane.channel_throttle->get_control_in();
if (plane.reversed_throttle) {
// RC option for reverse throttle has been set
ret = -ret;
Copy link
Member Author

Choose a reason for hiding this comment

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

This is almost certainly wrong for Quadplanes, but it is the current behavior.

@IamPete1 IamPete1 force-pushed the plane_ignore_invalid_pilot_throttle branch from 35524b9 to 9b7f305 Compare November 28, 2023 18:29
@tridge tridge removed the DevCallEU label Nov 29, 2023
@tridge tridge merged commit 41f61da into ArduPilot:master Nov 29, 2023
57 checks passed
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.

None yet

3 participants