mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
AP_Scheduler: allow for loop rates above 400Hz
with ChibiOS we can run copter at 1KHz with no scheduling misses. This small PR allows that to be configured.
This commit is contained in:
parent
e901243d8c
commit
44dd079cb9
@ -45,7 +45,7 @@ const AP_Param::GroupInfo AP_Scheduler::var_info[] = {
|
||||
|
||||
// @Param: LOOP_RATE
|
||||
// @DisplayName: Scheduling main loop rate
|
||||
// @Description: This controls the rate of the main control loop in Hz. This should only be changed by developers. This only takes effect on restart
|
||||
// @Description: This controls the rate of the main control loop in Hz. This should only be changed by developers. This only takes effect on restart. Values over 400 are considered highly experimental.
|
||||
// @Values: 50:50Hz,100:100Hz,200:200Hz,250:250Hz,300:300Hz,400:400Hz
|
||||
// @RebootRequired: True
|
||||
// @User: Advanced
|
||||
@ -60,11 +60,11 @@ AP_Scheduler::AP_Scheduler(void)
|
||||
_loop_rate_hz.set(SCHEDULER_DEFAULT_LOOP_RATE);
|
||||
AP_Param::setup_object_defaults(this, var_info);
|
||||
|
||||
// only allow 50 to 400 Hz
|
||||
// only allow 50 to 2000 Hz
|
||||
if (_loop_rate_hz < 50) {
|
||||
_loop_rate_hz.set(50);
|
||||
} else if (_loop_rate_hz > 400) {
|
||||
_loop_rate_hz.set(400);
|
||||
} else if (_loop_rate_hz > 2000) {
|
||||
_loop_rate_hz.set(2000);
|
||||
}
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user