From 2ddb3f6697b85a3b942b01f1bb91feebd0039cc7 Mon Sep 17 00:00:00 2001 From: Leonard Hall Date: Fri, 28 Dec 2018 20:12:28 +0900 Subject: [PATCH] Copter: desired-ground-idle replaces spin-when-armed --- ArduCopter/mode.cpp | 2 +- ArduCopter/mode_althold.cpp | 2 +- ArduCopter/mode_autotune.cpp | 2 +- ArduCopter/mode_flowhold.cpp | 2 +- ArduCopter/mode_land.cpp | 2 +- ArduCopter/mode_loiter.cpp | 2 +- ArduCopter/mode_poshold.cpp | 2 +- ArduCopter/mode_sport.cpp | 2 +- ArduCopter/mode_throw.cpp | 4 ++-- 9 files changed, 10 insertions(+), 10 deletions(-) diff --git a/ArduCopter/mode.cpp b/ArduCopter/mode.cpp index acb5df0adf..7bd209248e 100644 --- a/ArduCopter/mode.cpp +++ b/ArduCopter/mode.cpp @@ -383,7 +383,7 @@ void Copter::Mode::zero_throttle_and_relax_ac() attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(0.0f, 0.0f, 0.0f); attitude_control->set_throttle_out(0.0f, false, copter.g.throttle_filt); #else - motors->set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED); + motors->set_desired_spool_state(AP_Motors::DESIRED_GROUND_IDLE); // multicopters do not stabilize roll/pitch/yaw when disarmed attitude_control->set_throttle_out_unstabilized(0.0f, true, copter.g.throttle_filt); #endif diff --git a/ArduCopter/mode_althold.cpp b/ArduCopter/mode_althold.cpp index 08a2eeaa25..afec496fd4 100644 --- a/ArduCopter/mode_althold.cpp +++ b/ArduCopter/mode_althold.cpp @@ -111,7 +111,7 @@ void Copter::ModeAltHold::run() case AltHold_Landed: // set motors to spin-when-armed if throttle below deadzone, otherwise full range (but motors will only spin at min throttle) if (target_climb_rate < 0.0f) { - motors->set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED); + motors->set_desired_spool_state(AP_Motors::DESIRED_GROUND_IDLE); } else { motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED); } diff --git a/ArduCopter/mode_autotune.cpp b/ArduCopter/mode_autotune.cpp index 2953fd5559..307d0ddccd 100644 --- a/ArduCopter/mode_autotune.cpp +++ b/ArduCopter/mode_autotune.cpp @@ -54,7 +54,7 @@ void Copter::AutoTune::run() // set motors to spin-when-armed if throttle below deadzone, otherwise full range (but motors will only spin at min throttle) if (target_climb_rate < 0.0f) { - copter.motors->set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED); + copter.motors->set_desired_spool_state(AP_Motors::DESIRED_GROUND_IDLE); } else { copter.motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED); } diff --git a/ArduCopter/mode_flowhold.cpp b/ArduCopter/mode_flowhold.cpp index 6045110e17..977b669be2 100644 --- a/ArduCopter/mode_flowhold.cpp +++ b/ArduCopter/mode_flowhold.cpp @@ -336,7 +336,7 @@ void Copter::ModeFlowHold::run() case FlowHold_Landed: // set motors to spin-when-armed if throttle below deadzone, otherwise full range (but motors will only spin at min throttle) if (target_climb_rate < 0.0f) { - copter.motors->set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED); + copter.motors->set_desired_spool_state(AP_Motors::DESIRED_GROUND_IDLE); } else { copter.motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED); } diff --git a/ArduCopter/mode_land.cpp b/ArduCopter/mode_land.cpp index 4740bf297a..38f8e1d01a 100644 --- a/ArduCopter/mode_land.cpp +++ b/ArduCopter/mode_land.cpp @@ -113,7 +113,7 @@ void Copter::ModeLand::nogps_run() attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(target_roll, target_pitch, target_yaw_rate); attitude_control->set_throttle_out(0,false,g.throttle_filt); #else - motors->set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED); + motors->set_desired_spool_state(AP_Motors::DESIRED_GROUND_IDLE); // multicopters do not stabilize roll/pitch/yaw when disarmed attitude_control->set_throttle_out_unstabilized(0,true,g.throttle_filt); #endif diff --git a/ArduCopter/mode_loiter.cpp b/ArduCopter/mode_loiter.cpp index 6b1ca34ec9..b89c3ebc9b 100644 --- a/ArduCopter/mode_loiter.cpp +++ b/ArduCopter/mode_loiter.cpp @@ -182,7 +182,7 @@ void Copter::ModeLoiter::run() case Loiter_Landed: // set motors to spin-when-armed if throttle below deadzone, otherwise full range (but motors will only spin at min throttle) if (target_climb_rate < 0.0f) { - motors->set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED); + motors->set_desired_spool_state(AP_Motors::DESIRED_GROUND_IDLE); } else { motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED); } diff --git a/ArduCopter/mode_poshold.cpp b/ArduCopter/mode_poshold.cpp index a3fd32b927..b22d020cc6 100644 --- a/ArduCopter/mode_poshold.cpp +++ b/ArduCopter/mode_poshold.cpp @@ -186,7 +186,7 @@ void Copter::ModePosHold::run() if (ap.land_complete) { // set motors to spin-when-armed if throttle below deadzone, otherwise full range (but motors will only spin at min throttle) if (target_climb_rate < 0.0f) { - motors->set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED); + motors->set_desired_spool_state(AP_Motors::DESIRED_GROUND_IDLE); } else { motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED); } diff --git a/ArduCopter/mode_sport.cpp b/ArduCopter/mode_sport.cpp index 6c2e5e66c9..77b2ca1aeb 100644 --- a/ArduCopter/mode_sport.cpp +++ b/ArduCopter/mode_sport.cpp @@ -132,7 +132,7 @@ void Copter::ModeSport::run() case Sport_Landed: // set motors to spin-when-armed if throttle below deadzone, otherwise full range (but motors will only spin at min throttle) if (target_climb_rate < 0.0f) { - motors->set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED); + motors->set_desired_spool_state(AP_Motors::DESIRED_GROUND_IDLE); } else { motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED); } diff --git a/ArduCopter/mode_throw.cpp b/ArduCopter/mode_throw.cpp index 431e0741c8..66cfa24b07 100644 --- a/ArduCopter/mode_throw.cpp +++ b/ArduCopter/mode_throw.cpp @@ -110,7 +110,7 @@ void Copter::ModeThrow::run() // prevent motors from rotating before the throw is detected unless enabled by the user if (g.throw_motor_start == 1) { - motors->set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED); + motors->set_desired_spool_state(AP_Motors::DESIRED_GROUND_IDLE); } else { motors->set_desired_spool_state(AP_Motors::DESIRED_SHUT_DOWN); } @@ -123,7 +123,7 @@ void Copter::ModeThrow::run() // prevent motors from rotating before the throw is detected unless enabled by the user if (g.throw_motor_start == 1) { - motors->set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED); + motors->set_desired_spool_state(AP_Motors::DESIRED_GROUND_IDLE); } else { motors->set_desired_spool_state(AP_Motors::DESIRED_SHUT_DOWN); }