From 07b311f6a89a24190856bd11634202dac18796c5 Mon Sep 17 00:00:00 2001 From: Leonard Hall Date: Wed, 13 Jan 2016 16:09:42 +0900 Subject: [PATCH] Copter: brake sets desired spool state --- ArduCopter/control_brake.cpp | 9 +++++++-- 1 file changed, 7 insertions(+), 2 deletions(-) diff --git a/ArduCopter/control_brake.cpp b/ArduCopter/control_brake.cpp index a233dbb1c5..d60600574e 100644 --- a/ArduCopter/control_brake.cpp +++ b/ArduCopter/control_brake.cpp @@ -36,13 +36,15 @@ bool Copter::brake_init(bool ignore_checks) void Copter::brake_run() { // if not auto armed set throttle to zero and exit immediately - if(!ap.auto_armed) { + if (!motors.armed() || !ap.auto_armed || !motors.get_interlock()) { wp_nav.init_brake_target(BRAKE_MODE_DECEL_RATE); #if FRAME_CONFIG == HELI_FRAME // Helicopters always stabilize roll/pitch/yaw // call attitude controller attitude_control.input_euler_angle_roll_pitch_euler_rate_yaw_smooth(0, 0, 0, get_smoothing_gain()); attitude_control.set_throttle_out(0,false,g.throttle_filt); -#else // multicopters do not stabilize roll/pitch/yaw when disarmed +#else + motors.set_desired_spool_state(AP_MotorsMulticopter::DESIRED_SPIN_WHEN_ARMED); + // multicopters do not stabilize roll/pitch/yaw when disarmed attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt); #endif pos_control.relax_alt_hold_controllers(get_throttle_pre_takeoff(0)-throttle_average); @@ -59,6 +61,9 @@ void Copter::brake_run() init_disarm_motors(); } + // set motors to full range + motors.set_desired_spool_state(AP_MotorsMulticopter::DESIRED_THROTTLE_UNLIMITED); + // run brake controller wp_nav.update_brake(ekfGndSpdLimit, ekfNavVelGainScaler);