mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-24 01:28:29 -04:00
Plane: guided takeoff success should return true
This commit is contained in:
parent
e03826890a
commit
85b7f1bbb4
@ -2402,5 +2402,5 @@ bool QuadPlane::do_user_takeoff(float takeoff_altitude)
|
|||||||
motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
|
motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
|
||||||
guided_start();
|
guided_start();
|
||||||
guided_takeoff = true;
|
guided_takeoff = true;
|
||||||
return false;
|
return true;
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user