AP_Scheduler: fixed merge issues

This commit is contained in:
Andrew Tridgell 2018-02-10 11:48:20 +11:00
parent ae958632ec
commit 620d6ab4b8
3 changed files with 30 additions and 7 deletions

View File

@ -128,6 +128,10 @@ public:
return _loop_period_s; return _loop_period_s;
} }
float get_filtered_loop_time(void) const {
return perf_info.get_filtered_time();
}
static const struct AP_Param::GroupInfo var_info[]; static const struct AP_Param::GroupInfo var_info[];
// current running task, or -1 if none. Used to debug stuck tasks // current running task, or -1 if none. Used to debug stuck tasks

View File

@ -44,11 +44,15 @@ void AP::PerfInfo::check_loop_time(uint32_t time_in_micros)
if( min_time == 0 || time_in_micros < min_time) { if( min_time == 0 || time_in_micros < min_time) {
min_time = time_in_micros; min_time = time_in_micros;
} }
if (time_in_micros > overtime_threshold_us) { if (time_in_micros > overtime_threshold_micros) {
long_running++; long_running++;
} }
sigma_time += time_in_micros; sigma_time += time_in_micros;
sigmasquared_time += time_in_micros * time_in_micros; sigmasquared_time += time_in_micros * time_in_micros;
// we keep a filtered loop time for use as G_Dt which is the
// predicted time for the next loop
filtered_loop_time = 0.99 * filtered_loop_time + 0.01 * time_in_micros * 1.0e-6;
} }
// get_num_loops: return number of loops used for recording performance // get_num_loops: return number of loops used for recording performance
@ -93,6 +97,12 @@ uint32_t AP::PerfInfo::get_stddev_time() const
return sqrt((sigmasquared_time - (sigma_time*sigma_time)/loop_count) / loop_count); return sqrt((sigmasquared_time - (sigma_time*sigma_time)/loop_count) / loop_count);
} }
// get_filtered_time - return low pass filtered loop time in seconds
float AP::PerfInfo::get_filtered_time() const
{
return filtered_loop_time;
}
void AP::PerfInfo::update_logging() void AP::PerfInfo::update_logging()
{ {
gcs().send_text(MAV_SEVERITY_WARNING, gcs().send_text(MAV_SEVERITY_WARNING,
@ -104,3 +114,14 @@ void AP::PerfInfo::update_logging()
(unsigned long)get_avg_time(), (unsigned long)get_avg_time(),
(unsigned long)get_stddev_time()); (unsigned long)get_stddev_time());
} }
void AP::PerfInfo::set_loop_rate(uint16_t rate_hz)
{
// allow a 20% overrun before we consider a loop "slow":
overtime_threshold_micros = 1000000/rate_hz * 1.2f;
if (loop_rate_hz != rate_hz) {
loop_rate_hz = rate_hz;
filtered_loop_time = 1.0 / rate_hz;
}
}

View File

@ -22,15 +22,13 @@ public:
uint32_t get_num_dropped() const; uint32_t get_num_dropped() const;
uint32_t get_avg_time() const; uint32_t get_avg_time() const;
uint32_t get_stddev_time() const; uint32_t get_stddev_time() const;
float get_filtered_time() const;
void set_loop_rate(uint16_t rate_hz) { void set_loop_rate(uint16_t rate_hz);
// allow a 20% overrun before we consider a loop "slow":
overtime_threshold_micros = 1000000/rate_hz * 1.2f;
}
void update_logging(); void update_logging();
private: private:
uint16_t loop_rate_hz;
uint16_t overtime_threshold_micros; uint16_t overtime_threshold_micros;
uint16_t loop_count; uint16_t loop_count;
uint32_t max_time; // in microseconds uint32_t max_time; // in microseconds
@ -39,7 +37,7 @@ private:
uint64_t sigmasquared_time; uint64_t sigmasquared_time;
uint16_t long_running; uint16_t long_running;
uint32_t log_dropped; uint32_t log_dropped;
uint32_t overtime_threshold_us; float filtered_loop_time;
bool ignore_loop; bool ignore_loop;
}; };