mirror of https://github.com/ArduPilot/ardupilot
AP_Scheduler: removed perf counters
This commit is contained in:
parent
50e7c81f46
commit
f6ec48e0e2
|
@ -157,18 +157,6 @@ void AP_Scheduler::run(uint32_t time_available)
|
||||||
uint32_t run_started_usec = AP_HAL::micros();
|
uint32_t run_started_usec = AP_HAL::micros();
|
||||||
uint32_t now = run_started_usec;
|
uint32_t now = run_started_usec;
|
||||||
|
|
||||||
if (_debug > 1 && _perf_counters == nullptr) {
|
|
||||||
_perf_counters = new AP_HAL::Util::perf_counter_t[_num_tasks];
|
|
||||||
if (_perf_counters != nullptr) {
|
|
||||||
for (uint8_t i=0; i<_num_unshared_tasks; i++) {
|
|
||||||
_perf_counters[i] = hal.util->perf_alloc(AP_HAL::Util::PC_ELAPSED, _tasks[i].name);
|
|
||||||
}
|
|
||||||
for (uint8_t i=_num_unshared_tasks; i<_num_tasks; i++) {
|
|
||||||
_perf_counters[i] = hal.util->perf_alloc(AP_HAL::Util::PC_ELAPSED, _common_tasks[i].name);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
for (uint8_t i=0; i<_num_tasks; i++) {
|
for (uint8_t i=0; i<_num_tasks; i++) {
|
||||||
const AP_Scheduler::Task& task = (i < _num_unshared_tasks) ? _tasks[i] : _common_tasks[i - _num_unshared_tasks];
|
const AP_Scheduler::Task& task = (i < _num_unshared_tasks) ? _tasks[i] : _common_tasks[i - _num_unshared_tasks];
|
||||||
|
|
||||||
|
@ -204,16 +192,10 @@ void AP_Scheduler::run(uint32_t time_available)
|
||||||
// run it
|
// run it
|
||||||
_task_time_started = now;
|
_task_time_started = now;
|
||||||
hal.util->persistent_data.scheduler_task = i;
|
hal.util->persistent_data.scheduler_task = i;
|
||||||
if (_debug > 1 && _perf_counters && _perf_counters[i]) {
|
|
||||||
hal.util->perf_begin(_perf_counters[i]);
|
|
||||||
}
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||||
fill_nanf_stack();
|
fill_nanf_stack();
|
||||||
#endif
|
#endif
|
||||||
task.function();
|
task.function();
|
||||||
if (_debug > 1 && _perf_counters && _perf_counters[i]) {
|
|
||||||
hal.util->perf_end(_perf_counters[i]);
|
|
||||||
}
|
|
||||||
hal.util->persistent_data.scheduler_task = -1;
|
hal.util->persistent_data.scheduler_task = -1;
|
||||||
|
|
||||||
// record the tick counter when we ran. This drives
|
// record the tick counter when we ran. This drives
|
||||||
|
|
|
@ -222,9 +222,6 @@ private:
|
||||||
// time of last loop in seconds
|
// time of last loop in seconds
|
||||||
float _last_loop_time_s;
|
float _last_loop_time_s;
|
||||||
|
|
||||||
// performance counters
|
|
||||||
AP_HAL::Util::perf_counter_t *_perf_counters;
|
|
||||||
|
|
||||||
// bitmask bit which indicates if we should log PERF message
|
// bitmask bit which indicates if we should log PERF message
|
||||||
uint32_t _log_performance_bit;
|
uint32_t _log_performance_bit;
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue