mirror of https://github.com/ArduPilot/ardupilot
Copter: stabilize uses AP_Motors set_desired_spool_state
This commit is contained in:
parent
d2642065dd
commit
f6a6b360a8
|
@ -29,7 +29,7 @@ void Copter::stabilize_run()
|
|||
|
||||
// if not armed set throttle to zero and exit immediately
|
||||
if (!motors.armed() || ap.throttle_zero || !motors.get_interlock()) {
|
||||
motors.set_desired_spool_state(AP_MotorsMulticopter::DESIRED_SPIN_WHEN_ARMED);
|
||||
motors.set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED);
|
||||
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
|
||||
// slow start if landed
|
||||
if (ap.land_complete) {
|
||||
|
@ -38,7 +38,7 @@ void Copter::stabilize_run()
|
|||
return;
|
||||
}
|
||||
|
||||
motors.set_desired_spool_state(AP_MotorsMulticopter::DESIRED_THROTTLE_UNLIMITED);
|
||||
motors.set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
|
||||
|
||||
// apply SIMPLE mode transform to pilot inputs
|
||||
update_simple_mode();
|
||||
|
|
Loading…
Reference in New Issue