mirror of https://github.com/ArduPilot/ardupilot
Copter: reset mission when disarming
This commit is contained in:
parent
7d4c74c28e
commit
715e9c0474
|
@ -536,6 +536,9 @@ static void init_disarm_motors()
|
||||||
// we are not in the air
|
// we are not in the air
|
||||||
set_land_complete(true);
|
set_land_complete(true);
|
||||||
|
|
||||||
|
// reset the mission
|
||||||
|
mission.reset();
|
||||||
|
|
||||||
// setup fast AHRS gains to get right attitude
|
// setup fast AHRS gains to get right attitude
|
||||||
ahrs.set_fast_gains(true);
|
ahrs.set_fast_gains(true);
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue