Copter: mission_start always restarts mission

This commit is contained in:
KiwiHC16 2015-08-28 11:40:19 +02:00 committed by Randy Mackay
parent 1b5e6849d9
commit 004c5b8416

View File

@ -1296,6 +1296,9 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
case MAV_CMD_MISSION_START:
if (copter.motors.armed() && copter.set_mode(AUTO)) {
copter.set_auto_armed(true);
if (copter.mission.state() != AP_Mission::MISSION_RUNNING) {
copter.mission.start_or_resume();
}
result = MAV_RESULT_ACCEPTED;
}
break;