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: move forward throttle output in VTOL modes to QuadPlane update #26028

Merged
merged 1 commit into from
Jan 30, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
9 changes: 9 additions & 0 deletions ArduPlane/quadplane.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1866,6 +1866,15 @@ void QuadPlane::update(void)

tiltrotor.update();

if (in_vtol_mode()) {
// if enabled output forward throttle else 0
float fwd_thr = 0;
if (allow_forward_throttle_in_vtol_mode()) {
fwd_thr = forward_throttle_pct();
}
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, fwd_thr);
}

#if HAL_LOGGING_ENABLED
// motors logging
if (motors->armed()) {
Expand Down
9 changes: 0 additions & 9 deletions ArduPlane/servos.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -605,15 +605,6 @@ void Plane::set_throttle(void)
guided_throttle_passthru) {
// manual pass through of throttle while in GUIDED
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, get_throttle_input(true));
#if HAL_QUADPLANE_ENABLED
} else if (quadplane.in_vtol_mode()) {
float fwd_thr = 0;
// if enabled ask quadplane code for forward throttle
if (quadplane.allow_forward_throttle_in_vtol_mode()) {
fwd_thr = quadplane.forward_throttle_pct();
}
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, fwd_thr);
#endif // HAL_QUADPLANE_ENABLED
}

if (control_mode->use_battery_compensation()) {
Expand Down
Loading