mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
Plane: fix quadplane qstabilize throttle input
This commit is contained in:
parent
52caed2573
commit
41b584ac9e
@ -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…
Reference in New Issue
Block a user