mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
Plane: use mission.resume() not mission.start()
This commit is contained in:
parent
d4510d9b9b
commit
4992e2e2cf
@ -341,8 +341,12 @@ static void set_mode(enum FlightMode mode)
|
||||
|
||||
case AUTO:
|
||||
prev_WP.content.location = current_loc;
|
||||
// start the mission
|
||||
mission.start();
|
||||
// start the mission. Note that we use resume(), not start(),
|
||||
// as the correct behaviour for plane when entering auto is to
|
||||
// continue the mission. If the pilot wants to restart the
|
||||
// mission they need to either use RST_MISSION_CH or change
|
||||
// waypoint number to 0
|
||||
mission.resume();
|
||||
break;
|
||||
|
||||
case RTL:
|
||||
|
Loading…
Reference in New Issue
Block a user