Browse Source

Copter: do an early-return if the time hasn't been reached

master
Arjun Vinod 6 years ago committed by Randy Mackay
parent
commit
8044d98382
  1. 6
      ArduCopter/mode_auto.cpp

6
ArduCopter/mode_auto.cpp

@ -1750,9 +1750,8 @@ bool Copter::ModeAuto::verify_nav_wp(const AP_Mission::Mission_Command& cmd) @@ -1750,9 +1750,8 @@ bool Copter::ModeAuto::verify_nav_wp(const AP_Mission::Mission_Command& cmd)
}
gcs().send_text(MAV_SEVERITY_INFO, "Reached command #%i",cmd.index);
return true;
} else {
return false;
}
return false;
}
// verify_circle - check if we have circled the point enough
@ -1805,9 +1804,8 @@ bool Copter::ModeAuto::verify_spline_wp(const AP_Mission::Mission_Command& cmd) @@ -1805,9 +1804,8 @@ bool Copter::ModeAuto::verify_spline_wp(const AP_Mission::Mission_Command& cmd)
if (((millis() - loiter_time) / 1000) >= loiter_time_max) {
gcs().send_text(MAV_SEVERITY_INFO, "Reached command #%i",cmd.index);
return true;
} else {
return false;
}
return false;
}
#if NAV_GUIDED == ENABLED

Loading…
Cancel
Save