mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
Copter: do an early-return if the time hasn't been reached
This commit is contained in:
parent
8644f4d76e
commit
8044d98382
@ -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);
|
gcs().send_text(MAV_SEVERITY_INFO, "Reached command #%i",cmd.index);
|
||||||
return true;
|
return true;
|
||||||
} else {
|
|
||||||
return false;
|
|
||||||
}
|
}
|
||||||
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
// verify_circle - check if we have circled the point enough
|
// 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)
|
|||||||
if (((millis() - loiter_time) / 1000) >= loiter_time_max) {
|
if (((millis() - loiter_time) / 1000) >= loiter_time_max) {
|
||||||
gcs().send_text(MAV_SEVERITY_INFO, "Reached command #%i",cmd.index);
|
gcs().send_text(MAV_SEVERITY_INFO, "Reached command #%i",cmd.index);
|
||||||
return true;
|
return true;
|
||||||
} else {
|
|
||||||
return false;
|
|
||||||
}
|
}
|
||||||
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
#if NAV_GUIDED == ENABLED
|
#if NAV_GUIDED == ENABLED
|
||||||
|
Loading…
Reference in New Issue
Block a user