mirror of https://github.com/ArduPilot/ardupilot
Copter: bug fix display of PerfMon log's num long loops
This commit is contained in:
parent
54e131cf1f
commit
9287e28307
|
@ -5,7 +5,11 @@
|
||||||
// we measure the main loop time
|
// we measure the main loop time
|
||||||
//
|
//
|
||||||
|
|
||||||
#define PERF_INFO_OVERTIME_THRESHOLD_MICROS 10500
|
#if MAIN_LOOP_RATE == 400
|
||||||
|
# define PERF_INFO_OVERTIME_THRESHOLD_MICROS 3000
|
||||||
|
#else
|
||||||
|
# define PERF_INFO_OVERTIME_THRESHOLD_MICROS 10500
|
||||||
|
#endif
|
||||||
|
|
||||||
uint16_t perf_info_loop_count;
|
uint16_t perf_info_loop_count;
|
||||||
uint32_t perf_info_max_time;
|
uint32_t perf_info_max_time;
|
||||||
|
@ -47,4 +51,4 @@ uint32_t perf_info_get_max_time()
|
||||||
uint16_t perf_info_get_num_long_running()
|
uint16_t perf_info_get_num_long_running()
|
||||||
{
|
{
|
||||||
return perf_info_long_running;
|
return perf_info_long_running;
|
||||||
}
|
}
|
||||||
|
|
Loading…
Reference in New Issue