diff --git a/ArduCopter/control_auto.pde b/ArduCopter/control_auto.pde index 7ea2d90d4b..10a902e4c3 100644 --- a/ArduCopter/control_auto.pde +++ b/ArduCopter/control_auto.pde @@ -518,7 +518,7 @@ static void set_auto_yaw_look_at_heading(float angle_deg, float turn_rate_dps, i static void set_auto_yaw_roi(const Location &roi_location) { // if location is zero lat, lon and altitude turn off ROI - if (auto_yaw_mode == AUTO_YAW_ROI && (roi_location.alt == 0 && roi_location.lat == 0 && roi_location.lng == 0)) { + if (roi_location.alt == 0 && roi_location.lat == 0 && roi_location.lng == 0) { // set auto yaw mode back to default assuming the active command is a waypoint command. A more sophisticated method is required to ensure we return to the proper yaw control for the active command set_auto_yaw_mode(get_default_auto_yaw_mode(false)); #if MOUNT == ENABLED