diff --git a/ArduCopter/control_auto.pde b/ArduCopter/control_auto.pde index ad4c5449a3..0fef3df67c 100644 --- a/ArduCopter/control_auto.pde +++ b/ArduCopter/control_auto.pde @@ -20,7 +20,7 @@ // auto_init - initialise auto controller static bool auto_init(bool ignore_checks) { - if ((GPS_ok() && inertial_nav.position_ok() && mission.num_commands() > 0) || ignore_checks) { + if ((GPS_ok() && inertial_nav.position_ok() && mission.num_commands() > 1) || ignore_checks) { // stop ROI from carrying over from previous runs of the mission // To-Do: reset the yaw as part of auto_wp_start when the previous command was not a wp command to remove the need for this special ROI check if (auto_yaw_mode == AUTO_YAW_ROI) {