From f6a6b360a88da228b76db83caadf4c04b44d1a0b Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Tue, 2 Feb 2016 21:16:07 +0900 Subject: [PATCH] Copter: stabilize uses AP_Motors set_desired_spool_state --- ArduCopter/control_stabilize.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ArduCopter/control_stabilize.cpp b/ArduCopter/control_stabilize.cpp index 5df29263fa..d05a1bb272 100644 --- a/ArduCopter/control_stabilize.cpp +++ b/ArduCopter/control_stabilize.cpp @@ -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();