Copter: enable tail pass thru in acro for EXTGYRO tails

this allows acro mode to function as full passthru
This commit is contained in:
Andrew Tridgell 2015-06-22 15:50:12 +10:00 committed by Randy Mackay
parent eeb97800ae
commit ebddc05ead
2 changed files with 2 additions and 2 deletions

View File

@ -240,7 +240,7 @@ void Copter::exit_mode(uint8_t old_control_mode, uint8_t new_control_mode)
#if FRAME_CONFIG == HELI_FRAME #if FRAME_CONFIG == HELI_FRAME
// firmly reset the flybar passthrough to false when exiting acro mode. // firmly reset the flybar passthrough to false when exiting acro mode.
if (old_control_mode == ACRO) { if (old_control_mode == ACRO) {
attitude_control.use_flybar_passthrough(false); attitude_control.use_flybar_passthrough(false, false);
} }
// reset RC Passthrough to motors // reset RC Passthrough to motors

View File

@ -11,7 +11,7 @@
bool Copter::heli_acro_init(bool ignore_checks) 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 // 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 // always successfully enter acro
return true; return true;