From ebddc05ead8457f44b26f9f2e93e503f12dcb8a9 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 22 Jun 2015 15:50:12 +1000 Subject: [PATCH] Copter: enable tail pass thru in acro for EXTGYRO tails this allows acro mode to function as full passthru --- ArduCopter/flight_mode.cpp | 2 +- ArduCopter/heli_control_acro.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/ArduCopter/flight_mode.cpp b/ArduCopter/flight_mode.cpp index 7bd96f5b30..23db80937f 100644 --- a/ArduCopter/flight_mode.cpp +++ b/ArduCopter/flight_mode.cpp @@ -240,7 +240,7 @@ void Copter::exit_mode(uint8_t old_control_mode, uint8_t new_control_mode) #if FRAME_CONFIG == HELI_FRAME // firmly reset the flybar passthrough to false when exiting acro mode. if (old_control_mode == ACRO) { - attitude_control.use_flybar_passthrough(false); + attitude_control.use_flybar_passthrough(false, false); } // reset RC Passthrough to motors diff --git a/ArduCopter/heli_control_acro.cpp b/ArduCopter/heli_control_acro.cpp index 4f9277dd2f..c00dd053c4 100644 --- a/ArduCopter/heli_control_acro.cpp +++ b/ArduCopter/heli_control_acro.cpp @@ -11,7 +11,7 @@ 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()); + attitude_control.use_flybar_passthrough(motors.has_flybar(), motors.tail_type() == AP_MOTORS_HELI_TAILTYPE_SERVO_EXTGYRO); // always successfully enter acro return true;