diff --git a/ArduCopter/mode_guided.cpp b/ArduCopter/mode_guided.cpp index 0eefda7d28..4d59044074 100644 --- a/ArduCopter/mode_guided.cpp +++ b/ArduCopter/mode_guided.cpp @@ -39,8 +39,6 @@ struct Guided_Limit { bool Copter::ModeGuided::init(bool ignore_checks) { if (copter.position_ok() || ignore_checks) { - // initialise yaw - auto_yaw.set_mode_to_default(false); // start in position control mode pos_control_start(); return true;