From 49ee4b79651881f82a880336d63ebfa3569a4e45 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 9 Aug 2015 21:03:11 +1000 Subject: [PATCH] Copter: tell motors library when to use acro gyro gain --- ArduCopter/flight_mode.cpp | 1 + ArduCopter/heli_control_acro.cpp | 2 ++ 2 files changed, 3 insertions(+) diff --git a/ArduCopter/flight_mode.cpp b/ArduCopter/flight_mode.cpp index 23db80937f..93ce240e15 100644 --- a/ArduCopter/flight_mode.cpp +++ b/ArduCopter/flight_mode.cpp @@ -241,6 +241,7 @@ void Copter::exit_mode(uint8_t old_control_mode, uint8_t new_control_mode) // firmly reset the flybar passthrough to false when exiting acro mode. if (old_control_mode == ACRO) { attitude_control.use_flybar_passthrough(false, false); + motors.set_acro_tail(false); } // reset RC Passthrough to motors diff --git a/ArduCopter/heli_control_acro.cpp b/ArduCopter/heli_control_acro.cpp index 6111c3e211..9649d4396f 100644 --- a/ArduCopter/heli_control_acro.cpp +++ b/ArduCopter/heli_control_acro.cpp @@ -13,6 +13,8 @@ bool Copter::heli_acro_init(bool ignore_checks) // if heli is equipped with a flybar, then tell the attitude controller to pass through controls directly to servos attitude_control.use_flybar_passthrough(motors.has_flybar(), motors.supports_yaw_passthrough()); + motors.set_acro_tail(true); + // always successfully enter acro return true; }