Copter: stabilize uses AP_Motors set_desired_spool_state

This commit is contained in:
Randy Mackay 2016-02-02 21:16:07 +09:00
parent d2642065dd
commit f6a6b360a8
1 changed files with 2 additions and 2 deletions

View File

@ -29,7 +29,7 @@ void Copter::stabilize_run()
// if not armed set throttle to zero and exit immediately // if not armed set throttle to zero and exit immediately
if (!motors.armed() || ap.throttle_zero || !motors.get_interlock()) { 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); attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
// slow start if landed // slow start if landed
if (ap.land_complete) { if (ap.land_complete) {
@ -38,7 +38,7 @@ void Copter::stabilize_run()
return; 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 // apply SIMPLE mode transform to pilot inputs
update_simple_mode(); update_simple_mode();