From 02540fdbf9a0382803aeb7be558ba60b8e6389f0 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 13 Nov 2017 18:22:07 +1100 Subject: [PATCH] Plane: use AP_Scheduler's loop() function --- ArduPlane/ArduPlane.cpp | 40 ++++++++++------------------------------ ArduPlane/Log.cpp | 10 +++++----- ArduPlane/Plane.h | 6 ------ 3 files changed, 15 insertions(+), 41 deletions(-) diff --git a/ArduPlane/ArduPlane.cpp b/ArduPlane/ArduPlane.cpp index 8e707a9cc7..76404b1e68 100644 --- a/ArduPlane/ArduPlane.cpp +++ b/ArduPlane/ArduPlane.cpp @@ -115,28 +115,8 @@ void Plane::setup() void Plane::loop() { - // wait for an INS sample - ins.wait_for_sample(); - - uint32_t timer = micros(); - - // check loop time - perf_info.check_loop_time(timer - perf.fast_loopTimer_us); - - G_Dt = (timer - perf.fast_loopTimer_us) * 1.0e-6f; - perf.fast_loopTimer_us = timer; - - // tell the scheduler one tick has passed - scheduler.tick(); - - // run all the tasks that are due to run. Note that we only - // have to call this once per loop, as the tasks are scheduled - // in multiples of the main loop tick. So if they don't run on - // the first call to the scheduler they won't run on a later - // call until scheduler.tick() is called again - const uint32_t loop_us = scheduler.get_loop_period_us(); - const uint32_t time_available = (timer + loop_us) - micros(); - scheduler.run(time_available); + scheduler.loop(); + G_Dt = scheduler.last_loop_time; } void Plane::update_soft_armed() @@ -361,20 +341,20 @@ void Plane::log_perf_info() if (scheduler.debug() != 0) { gcs().send_text(MAV_SEVERITY_INFO, "PERF: %u/%u max=%lu min=%lu avg=%lu sd=%lu Log=%u", - (unsigned)perf_info.get_num_long_running(), - (unsigned)perf_info.get_num_loops(), - (unsigned long)perf_info.get_max_time(), - (unsigned long)perf_info.get_min_time(), - (unsigned long)perf_info.get_avg_time(), - (unsigned long)perf_info.get_stddev_time(), - (unsigned)(DataFlash.num_dropped() - perf_info.get_num_dropped())); + (unsigned)scheduler.perf_info.get_num_long_running(), + (unsigned)scheduler.perf_info.get_num_loops(), + (unsigned long)scheduler.perf_info.get_max_time(), + (unsigned long)scheduler.perf_info.get_min_time(), + (unsigned long)scheduler.perf_info.get_avg_time(), + (unsigned long)scheduler.perf_info.get_stddev_time(), + (unsigned)(DataFlash.num_dropped() - scheduler.perf_info.get_num_dropped())); } if (should_log(MASK_LOG_PM)) { Log_Write_Performance(); } - perf_info.reset(); + scheduler.perf_info.reset(); } void Plane::compass_save() diff --git a/ArduPlane/Log.cpp b/ArduPlane/Log.cpp index 197287ead4..99beb1f49c 100644 --- a/ArduPlane/Log.cpp +++ b/ArduPlane/Log.cpp @@ -72,11 +72,11 @@ void Plane::Log_Write_Performance() struct log_Performance pkt = { LOG_PACKET_HEADER_INIT(LOG_PERFORMANCE_MSG), time_us : AP_HAL::micros64(), - num_long : perf_info.get_num_long_running(), - main_loop_count : perf_info.get_num_loops(), - g_dt_max : perf_info.get_max_time(), - g_dt_min : perf_info.get_min_time(), - log_dropped : DataFlash.num_dropped() - perf_info.get_num_dropped(), + num_long : scheduler.perf_info.get_num_long_running(), + main_loop_count : scheduler.perf_info.get_num_loops(), + g_dt_max : scheduler.perf_info.get_max_time(), + g_dt_min : scheduler.perf_info.get_min_time(), + log_dropped : DataFlash.num_dropped() - scheduler.perf_info.get_num_dropped(), hal.util->available_memory() }; last_log_dropped = dropped; diff --git a/ArduPlane/Plane.h b/ArduPlane/Plane.h index 25eacc862a..c3cbf45826 100644 --- a/ArduPlane/Plane.h +++ b/ArduPlane/Plane.h @@ -737,12 +737,6 @@ private: // loop performance monitoring: AP::PerfInfo perf_info; - struct { - // System Timers - // Time in microseconds of start of main control loop - uint32_t fast_loopTimer_us; - } perf; - struct { uint32_t last_trim_check; uint32_t last_trim_save;