Copter: set RC_SPEED default to 16kHz for brushed

This commit is contained in:
Andrew Tridgell 2017-05-25 12:09:33 +10:00
parent 96627bc4e5
commit ba21c1e67d
1 changed files with 5 additions and 0 deletions

View File

@ -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