From 068fc7feac94afdc6511f7f5cfcd58ed782b4bc6 Mon Sep 17 00:00:00 2001 From: Leonard Hall Date: Mon, 18 Jan 2016 14:36:56 +0900 Subject: [PATCH] Copter: flip uses 0 to 1 throttle and sets motor spool state --- ArduCopter/control_flip.cpp | 7 +++++-- 1 file changed, 5 insertions(+), 2 deletions(-) diff --git a/ArduCopter/control_flip.cpp b/ArduCopter/control_flip.cpp index c64fded8cc..295cb4404f 100644 --- a/ArduCopter/control_flip.cpp +++ b/ArduCopter/control_flip.cpp @@ -96,7 +96,7 @@ bool Copter::flip_init(bool ignore_checks) // should be called at 100hz or more void Copter::flip_run() { - int16_t throttle_out; + float throttle_out; float recovery_angle; // if pilot inputs roll > 40deg or timeout occurs abandon flip @@ -219,8 +219,11 @@ void Copter::flip_run() break; } + // set motors to full range + motors.set_desired_spool_state(AP_MotorsMulticopter::DESIRED_THROTTLE_UNLIMITED); + // output pilot's throttle without angle boost - if (throttle_out == 0) { + if (is_zero(throttle_out)) { attitude_control.set_throttle_out_unstabilized(0,false,g.throttle_filt); } else { attitude_control.set_throttle_out(throttle_out, false, g.throttle_filt);