Browse Source

Copter: integrate heli_control_stabilize

master
Randy Mackay 11 years ago committed by Andrew Tridgell
parent
commit
922dff0514
  1. 6
      ArduCopter/ArduCopter.pde
  2. 6
      ArduCopter/system.pde

6
ArduCopter/ArduCopter.pde

@ -1452,7 +1452,11 @@ static void update_flight_mode() @@ -1452,7 +1452,11 @@ static void update_flight_mode()
break;
case STABILIZE:
stabilize_run();
#if FRAME_CONFIG == HELI_FRAME
heli_stabilize_run();
#else
stabilize_run();
#endif
break;
case ALT_HOLD:

6
ArduCopter/system.pde

@ -391,7 +391,11 @@ static bool set_mode(uint8_t mode) @@ -391,7 +391,11 @@ static bool set_mode(uint8_t mode)
break;
case STABILIZE:
success = stabilize_init(ignore_checks);
#if FRAME_CONFIG == HELI_FRAME
success = heli_stabilize_init(ignore_checks);
#else
success = stabilize_init(ignore_checks);
#endif
break;
case ALT_HOLD:

Loading…
Cancel
Save