From a18722a2fcd59c6b27034c7a6b9840e7abf02ea3 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Tue, 2 Feb 2016 21:31:44 +0900 Subject: [PATCH] AP_MotorsHeli: output_min uses new move_actuators in -1 to +1 range --- libraries/AP_Motors/AP_MotorsHeli.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_Motors/AP_MotorsHeli.cpp b/libraries/AP_Motors/AP_MotorsHeli.cpp index 38a0cb08dd..98c685be57 100644 --- a/libraries/AP_Motors/AP_MotorsHeli.cpp +++ b/libraries/AP_Motors/AP_MotorsHeli.cpp @@ -186,7 +186,7 @@ void AP_MotorsHeli::Init() void AP_MotorsHeli::output_min() { // move swash to mid - move_actuators(0,0,500,0); + move_actuators(0.0f,0.0f,0.5f,0.0f); update_motor_control(ROTOR_CONTROL_STOP);