Browse Source

Plane: fix quadplane qstabilize throttle input

mission-4.1.18
Randy Mackay 9 years ago
parent
commit
41b584ac9e
  1. 2
      ArduPlane/quadplane.cpp

2
ArduPlane/quadplane.cpp

@ -389,7 +389,7 @@ void QuadPlane::hold_stabilize(float throttle_in) @@ -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);
}

Loading…
Cancel
Save