Plane: fix quadplane qstabilize throttle input

This commit is contained in:
Randy Mackay 2016-03-26 12:27:00 +09:00
parent 52caed2573
commit 41b584ac9e

View File

@ -389,7 +389,7 @@ void QuadPlane::hold_stabilize(float throttle_in)
// quadplane stabilize mode
void QuadPlane::control_stabilize(void)
{
int16_t pilot_throttle_scaled = plane.channel_throttle->control_in * 10;
float pilot_throttle_scaled = plane.channel_throttle->control_in / 100.0f;
hold_stabilize(pilot_throttle_scaled);
}