mirror of https://github.com/ArduPilot/ardupilot
AP_Scheduler: allow for arbitrary loop rates
it turns out 300Hz is pretty useful as it allows for triple EKF on pixhawk
This commit is contained in:
parent
bd272390bc
commit
c3829dfb64
|
@ -49,7 +49,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
|
||||
// @Values: 50:50Hz,100:100Hz,200:200Hz,400:400Hz
|
||||
// @Values: 50:50Hz,100:100Hz,200:200Hz,250:250Hz,300:300Hz,400:400Hz
|
||||
// @RebootRequired: True
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("LOOP_RATE", 1, AP_Scheduler, _loop_rate_hz, SCHEDULER_DEFAULT_LOOP_RATE),
|
||||
|
@ -64,15 +64,10 @@ AP_Scheduler::AP_Scheduler(void)
|
|||
_loop_rate_hz.set_default(SCHEDULER_DEFAULT_LOOP_RATE);
|
||||
AP_Param::setup_object_defaults(this, var_info);
|
||||
|
||||
// only allow specific values of main loop rate. This code is not
|
||||
// setup for arbitrary rates yet
|
||||
if (_loop_rate_hz <= 50) {
|
||||
// only allow 50 to 400 Hz
|
||||
if (_loop_rate_hz < 50) {
|
||||
_loop_rate_hz.set(50);
|
||||
} else if (_loop_rate_hz <= 100) {
|
||||
_loop_rate_hz.set(100);
|
||||
} else if (_loop_rate_hz <= 200) {
|
||||
_loop_rate_hz.set(200);
|
||||
} else {
|
||||
} else if (_loop_rate_hz > 400) {
|
||||
_loop_rate_hz.set(400);
|
||||
}
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue