mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Scheduler: Use a range of values here because it is valid to do so.
Makes it easier for GUI applications to display this better and valudate the range
This commit is contained in:
parent
6a59d3adae
commit
12b761c534
@ -61,8 +61,9 @@ 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 over 400 are considered highly experimental.
|
||||
// @Values: 50:50Hz,100:100Hz,200:200Hz,250:250Hz,300:300Hz,400:400Hz
|
||||
// @Range: 50 400
|
||||
// @RebootRequired: True
|
||||
// @Units: Hz
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("LOOP_RATE", 1, AP_Scheduler, _loop_rate_hz, SCHEDULER_DEFAULT_LOOP_RATE),
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user