From f91874afad3d21d3eed80bfee0bcfc77d72a0159 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Tue, 2 Feb 2016 21:18:47 +0900 Subject: [PATCH] Copter: drift uses AP_Motors set_desired_spool_state --- ArduCopter/control_drift.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ArduCopter/control_drift.cpp b/ArduCopter/control_drift.cpp index c79ead3500..a48b666677 100644 --- a/ArduCopter/control_drift.cpp +++ b/ArduCopter/control_drift.cpp @@ -50,7 +50,7 @@ void Copter::drift_run() // if landed and throttle at zero, set throttle to zero and exit immediately if (!motors.armed() || !motors.get_interlock() || (ap.land_complete && ap.throttle_zero)) { - 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); return; } @@ -95,7 +95,7 @@ void Copter::drift_run() } // 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); // call attitude controller attitude_control.input_euler_angle_roll_pitch_euler_rate_yaw_smooth(target_roll, target_pitch, target_yaw_rate, get_smoothing_gain());