From d37f70f767d95fd2a0a4290ed17a7086328ceb7e Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Tue, 2 Feb 2016 21:16:25 +0900 Subject: [PATCH] Copter: sport uses AP_Motors set_desired_spool_state --- ArduCopter/control_sport.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/ArduCopter/control_sport.cpp b/ArduCopter/control_sport.cpp index 489742ed1e..04ee900e29 100644 --- a/ArduCopter/control_sport.cpp +++ b/ArduCopter/control_sport.cpp @@ -34,7 +34,7 @@ void Copter::sport_run() // if not armed or throttle at zero, 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); pos_control.relax_alt_hold_controllers(get_throttle_pre_takeoff(channel_throttle->control_in)-throttle_average); return; @@ -93,16 +93,16 @@ void Copter::sport_run() // reset target lean angles and heading while landed if (ap.land_complete) { if (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); }else{ - motors.set_desired_spool_state(AP_MotorsMulticopter::DESIRED_THROTTLE_UNLIMITED); + motors.set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED); } // move throttle to between minimum and non-takeoff-throttle to keep us on the ground attitude_control.set_throttle_out(get_throttle_pre_takeoff(channel_throttle->control_in),false,g.throttle_filt); pos_control.relax_alt_hold_controllers(get_throttle_pre_takeoff(channel_throttle->control_in)-throttle_average); }else{ // 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_rate_roll_pitch_yaw(target_roll_rate, target_pitch_rate, target_yaw_rate);