Rover: auto mode fails to enter if no mission

This prevent going into Auto without a mission and skipping the first mission waypoint because we aren't yet in Auto when in enter()
This commit is contained in:
khancyr 2017-07-11 11:58:47 +02:00 committed by Randy Mackay
parent 07f4603533
commit 809a9e5894
1 changed files with 6 additions and 0 deletions

View File

@ -3,6 +3,12 @@
bool ModeAuto::_enter()
{
// fail to enter auto if no mission commands
if (mission.num_commands() == 0) {
gcs().send_text(MAV_SEVERITY_NOTICE, "No Mission. Can't set AUTO.");
return false;
}
auto_triggered = false;
rover.restart_nav();
rover.loiter_start_time = 0;