mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-26 09:43:57 -04:00
Plane: make ground test easier for tilt
This commit is contained in:
parent
76870f8e01
commit
b9debba509
@ -60,7 +60,7 @@ void QuadPlane::tiltrotor_continuous_update(void)
|
||||
// the maximum rate of throttle change
|
||||
float max_change;
|
||||
|
||||
if (!in_vtol_mode() && !assisted_flight) {
|
||||
if (!in_vtol_mode() && (!hal.util->get_soft_armed() || !assisted_flight)) {
|
||||
// we are in pure fixed wing mode. Move the tiltable motors all the way forward and run them as
|
||||
// a forward motor
|
||||
tiltrotor_slew(1);
|
||||
|
Loading…
Reference in New Issue
Block a user