Copter: tell PerfInfo the configured loop rate
This commit is contained in:
parent
ae9d4d514d
commit
bf6a2b8bb5
@ -190,7 +190,8 @@ void Copter::setup()
|
||||
scheduler.init(&scheduler_tasks[0], ARRAY_SIZE(scheduler_tasks));
|
||||
|
||||
// setup initial performance counters
|
||||
perf_info.reset(scheduler.get_loop_rate_hz());
|
||||
perf_info.set_loop_rate(scheduler.get_loop_rate_hz());
|
||||
perf_info.reset();
|
||||
fast_loopTimer = AP_HAL::micros();
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user