Browse Source

Copter: tell motors library when to use acro gyro gain

master
Andrew Tridgell 10 years ago
parent
commit
49ee4b7965
  1. 1
      ArduCopter/flight_mode.cpp
  2. 2
      ArduCopter/heli_control_acro.cpp

1
ArduCopter/flight_mode.cpp

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

2
ArduCopter/heli_control_acro.cpp

@ -13,6 +13,8 @@ bool Copter::heli_acro_init(bool ignore_checks) @@ -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;
}

Loading…
Cancel
Save