From ba21c1e67d8c769607bcfc84e72918f1fa9e1289 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 25 May 2017 12:09:33 +1000 Subject: [PATCH] Copter: set RC_SPEED default to 16kHz for brushed --- ArduCopter/system.cpp | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/ArduCopter/system.cpp b/ArduCopter/system.cpp index 5551044fa9..ad75453b51 100644 --- a/ArduCopter/system.cpp +++ b/ArduCopter/system.cpp @@ -692,6 +692,11 @@ void Copter::allocate_motors(void) break; } + // brushed 16kHz defaults to 16kHz pulses + if (motors->get_pwm_type() >= AP_Motors::PWM_TYPE_BRUSHED) { + g.rc_speed.set_default(16000); + } + if (upgrading_frame_params) { // do frame specific upgrade. This is only done the first time we run the new firmware #if FRAME_CONFIG == HELI_FRAME