diff --git a/ArduCopter/mode_stabilize_heli.cpp b/ArduCopter/mode_stabilize_heli.cpp index 89678c4c10..2a7056cd1f 100644 --- a/ArduCopter/mode_stabilize_heli.cpp +++ b/ArduCopter/mode_stabilize_heli.cpp @@ -8,6 +8,9 @@ // stabilize_init - initialise stabilize controller bool ModeStabilize_Heli::init(bool ignore_checks) { + // be aware that when adding code to this function that it is *NOT + // RUN* at vehicle startup! + // set stab collective true to use stabilize scaled collective pitch range copter.input_manager.set_use_stab_col(true);