AP_Scheduler: fixed perf info to match previous behaviour

This commit is contained in:
Andrew Tridgell 2018-02-10 13:47:16 +11:00
parent b7c4dea9d3
commit f436901517
2 changed files with 6 additions and 5 deletions

View File

@ -235,14 +235,15 @@ void AP_Scheduler::loop()
const uint32_t time_available = (sample_time_us + loop_us) - AP_HAL::micros();
run(time_available > loop_us ? 0u : time_available);
// check loop time
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
// move result of AP_HAL::micros() forward:
hal.scheduler->delay_microseconds(1);
#endif
perf_info.check_loop_time(AP_HAL::micros() - loop_timer_start_us);
loop_timer_start_us = AP_HAL::micros();
// check loop time
perf_info.check_loop_time(sample_time_us - loop_timer_start_us);
loop_timer_start_us = sample_time_us;
}
void AP_Scheduler::update_logging()

View File

@ -121,12 +121,12 @@ float AP::PerfInfo::get_filtered_time() const
void AP::PerfInfo::update_logging()
{
gcs().send_text(MAV_SEVERITY_WARNING,
"PERF: %u/%u max=%lu min=%lu avg=%lu sd=%lu",
"PERF: %u/%u max=%lu min=%lu F=%u sd=%lu",
(unsigned)get_num_long_running(),
(unsigned)get_num_loops(),
(unsigned long)get_max_time(),
(unsigned long)get_min_time(),
(unsigned long)get_avg_time(),
(unsigned)(get_filtered_time()*1.0e6),
(unsigned long)get_stddev_time());
}