Browse Source

Copter: enable tail pass thru in acro for EXTGYRO tails

this allows acro mode to function as full passthru
master
Andrew Tridgell 10 years ago committed by Randy Mackay
parent
commit
ebddc05ead
  1. 2
      ArduCopter/flight_mode.cpp
  2. 2
      ArduCopter/heli_control_acro.cpp

2
ArduCopter/flight_mode.cpp

@ -240,7 +240,7 @@ void Copter::exit_mode(uint8_t old_control_mode, uint8_t new_control_mode) @@ -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

2
ArduCopter/heli_control_acro.cpp

@ -11,7 +11,7 @@ @@ -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;

Loading…
Cancel
Save