Skip to content

ArduSub/mode_acro: fix bug for dealing throttle from pilot#31469

Merged
Williangalvani merged 1 commit intoArduPilot:masterfrom
xianglunkai:pr_fix_sub_throttle_from_polit
Feb 5, 2026
Merged

ArduSub/mode_acro: fix bug for dealing throttle from pilot#31469
Williangalvani merged 1 commit intoArduPilot:masterfrom
xianglunkai:pr_fix_sub_throttle_from_polit

Conversation

@xianglunkai
Copy link
Contributor

fix mistake for getting throttle values from pilot


// output pilot's throttle without angle boost
attitude_control->set_throttle_out(channel_throttle->norm_input(), false, g.throttle_filt);
attitude_control->set_throttle_out((channel_throttle->norm_input() + 1.0f) / 2.0f, false, g.throttle_filt);
Copy link
Contributor

Choose a reason for hiding this comment

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

This isn't just reverse thrust being a thing on subs?

Copy link
Contributor Author

Choose a reason for hiding this comment

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

yes!

Copy link
Contributor

@Williangalvani Williangalvani left a comment

Choose a reason for hiding this comment

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

Thanks! it is hard to believe we had this bug for this long!

@Williangalvani Williangalvani merged commit 54e1593 into ArduPilot:master Feb 5, 2026
69 checks passed
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Labels

None yet

Projects

None yet

Development

Successfully merging this pull request may close these issues.

3 participants