Plane: change default loop rate for quadplanes to 300Hz
This commit is contained in:
parent
1fe9582ac3
commit
06bcf0df4b
@ -1383,5 +1383,11 @@ void Plane::load_parameters(void)
|
||||
// Load all auto-loaded EEPROM variables
|
||||
AP_Param::load_all();
|
||||
AP_Param::convert_old_parameters(&conversion_table[0], ARRAY_SIZE(conversion_table));
|
||||
|
||||
if (quadplane.enable) {
|
||||
// quadplanes needs a higher loop rate
|
||||
AP_Param::set_default_by_name("SCHED_LOOP_RATE", 300);
|
||||
}
|
||||
|
||||
cliSerial->printf("load_all took %uus\n", (unsigned)(micros() - before));
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user