mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-24 17:48:35 -04:00
Copter: poshold loses stray set-desired-spool-state
spool state is all handled higher up in the poshold state switch statement
This commit is contained in:
parent
29d05dfeac
commit
d626ea66f1
@ -443,9 +443,6 @@ void Copter::ModePosHold::run()
|
|||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
// set motors to full range
|
|
||||||
motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
|
|
||||||
|
|
||||||
//
|
//
|
||||||
// Shared roll & pitch states (POSHOLD_BRAKE_TO_LOITER and POSHOLD_LOITER)
|
// Shared roll & pitch states (POSHOLD_BRAKE_TO_LOITER and POSHOLD_LOITER)
|
||||||
//
|
//
|
||||||
|
Loading…
Reference in New Issue
Block a user