Browse Source

AP_Scheduler: pass log-performance-bit at init time rather than update time

mission-4.1.18
Peter Barker 7 years ago committed by Andrew Tridgell
parent
commit
73c0905b5e
  1. 9
      libraries/AP_Scheduler/AP_Scheduler.cpp
  2. 7
      libraries/AP_Scheduler/AP_Scheduler.h

9
libraries/AP_Scheduler/AP_Scheduler.cpp

@ -74,7 +74,7 @@ AP_Scheduler::AP_Scheduler(scheduler_fastloop_fn_t fastloop_fn) : @@ -74,7 +74,7 @@ AP_Scheduler::AP_Scheduler(scheduler_fastloop_fn_t fastloop_fn) :
}
// initialise the scheduler
void AP_Scheduler::init(const AP_Scheduler::Task *tasks, uint8_t num_tasks)
void AP_Scheduler::init(const AP_Scheduler::Task *tasks, uint8_t num_tasks, uint32_t log_performance_bit)
{
_tasks = tasks;
_num_tasks = num_tasks;
@ -86,6 +86,8 @@ void AP_Scheduler::init(const AP_Scheduler::Task *tasks, uint8_t num_tasks) @@ -86,6 +86,8 @@ void AP_Scheduler::init(const AP_Scheduler::Task *tasks, uint8_t num_tasks)
perf_info.set_loop_rate(get_loop_rate_hz());
perf_info.reset();
loop_start = AP_HAL::micros();
_log_performance_bit = log_performance_bit;
}
// one tick has passed
@ -242,12 +244,13 @@ void AP_Scheduler::loop() @@ -242,12 +244,13 @@ void AP_Scheduler::loop()
perf_info.check_loop_time(AP_HAL::micros() - loop_start);
}
void AP_Scheduler::update_logging(const bool log_to_dataflash)
void AP_Scheduler::update_logging()
{
if (debug_flags()) {
perf_info.update_logging();
}
if (log_to_dataflash) {
if (_log_performance_bit != (uint32_t)-1 &&
DataFlash_Class::instance()->should_log(_log_performance_bit)) {
Log_Write_Performance();
}
perf_info.set_loop_rate(get_loop_rate_hz());

7
libraries/AP_Scheduler/AP_Scheduler.h

@ -72,14 +72,14 @@ public: @@ -72,14 +72,14 @@ public:
};
// initialise scheduler
void init(const Task *tasks, uint8_t num_tasks);
void init(const Task *tasks, uint8_t num_tasks, uint32_t log_performance_bit);
// called by vehicle's main loop - which should be the only thing
// that function does
void loop();
// call to update any logging the scheduler might do; call at 1Hz
void update_logging(bool log_to_dataflash);
void update_logging();
// write out PERF message to dataflash
void Log_Write_Performance();
@ -188,4 +188,7 @@ private: @@ -188,4 +188,7 @@ private:
// performance counters
AP_HAL::Util::perf_counter_t *_perf_counters;
// bitmask bit which indicates if we should log PERF message to dataflash
uint32_t _log_performance_bit;
};

Loading…
Cancel
Save