Skip to content

Commit

Permalink
Plane: use throttle in for transition max comparison
Browse files Browse the repository at this point in the history
  • Loading branch information
IamPete1 authored and tridge committed Aug 30, 2020
1 parent 74c4782 commit abee62a
Showing 1 changed file with 1 addition and 1 deletion.
2 changes: 1 addition & 1 deletion ArduPlane/quadplane.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1760,7 +1760,7 @@ void QuadPlane::update_transition(void)
plane.nav_pitch_cd,
0);
// set throttle at either hover throttle or current throttle, whichever is higher, through the transition
attitude_control->set_throttle_out(MAX(motors->get_throttle_hover(),motors->get_throttle()), true, 0);
attitude_control->set_throttle_out(MAX(motors->get_throttle_hover(),attitude_control->get_throttle_in()), true, 0);
break;
}

Expand Down

0 comments on commit abee62a

Please sign in to comment.