diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index c3e3787be7..f340346ed4 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -1448,7 +1448,11 @@ static void update_flight_mode() { switch (control_mode) { case ACRO: - acro_run(); + #if FRAME_CONFIG == HELI_FRAME + heli_acro_run(); + #else + acro_run(); + #endif break; case STABILIZE: diff --git a/ArduCopter/system.pde b/ArduCopter/system.pde index 0ebcc56920..32b19583e0 100644 --- a/ArduCopter/system.pde +++ b/ArduCopter/system.pde @@ -387,7 +387,11 @@ static bool set_mode(uint8_t mode) switch(mode) { case ACRO: - success = acro_init(ignore_checks); + #if FRAME_CONFIG == HELI_FRAME + success = heli_acro_init(ignore_checks); + #else + success = acro_init(ignore_checks); + #endif break; case STABILIZE: