mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 15:53:56 -04:00
Copter: flip uses AP_Motors set_desired_spool_state
This commit is contained in:
parent
f91874afad
commit
4deb6fd39d
@ -220,7 +220,7 @@ void Copter::flip_run()
|
|||||||
}
|
}
|
||||||
|
|
||||||
// set motors to full range
|
// set motors to full range
|
||||||
motors.set_desired_spool_state(AP_MotorsMulticopter::DESIRED_THROTTLE_UNLIMITED);
|
motors.set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
|
||||||
|
|
||||||
// output pilot's throttle without angle boost
|
// output pilot's throttle without angle boost
|
||||||
if (is_zero(throttle_out)) {
|
if (is_zero(throttle_out)) {
|
||||||
|
Loading…
Reference in New Issue
Block a user