From 668561ff0e9d08dfa4e59df002f34a5c28ddfefe Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Tue, 2 Feb 2016 21:15:18 +0900 Subject: [PATCH] Copter: acro uses AP_Motors set_desired_spool_state --- ArduCopter/control_acro.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ArduCopter/control_acro.cpp b/ArduCopter/control_acro.cpp index 7f812350a1..d974d624b6 100644 --- a/ArduCopter/control_acro.cpp +++ b/ArduCopter/control_acro.cpp @@ -28,7 +28,7 @@ void Copter::acro_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) { @@ -37,7 +37,7 @@ void Copter::acro_run() return; } - motors.set_desired_spool_state(AP_MotorsMulticopter::DESIRED_THROTTLE_UNLIMITED); + motors.set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED); // convert the input to the desired body frame rate get_pilot_desired_angle_rates(channel_roll->control_in, channel_pitch->control_in, channel_yaw->control_in, target_roll, target_pitch, target_yaw);