Copter: integrate heli_control_stabilize
This commit is contained in:
parent
41ab2547d7
commit
922dff0514
@ -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:
|
||||
|
@ -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…
Reference in New Issue
Block a user