From 5149a49daad31d045a3aa31b6a1f8775bf492ead Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 21 Apr 2016 16:42:25 +1000 Subject: [PATCH] Copter: added logging of dropped log messages in PM message --- ArduCopter/Copter.h | 1 + ArduCopter/Log.cpp | 8 +++++--- ArduCopter/perf_info.cpp | 8 ++++++++ 3 files changed, 14 insertions(+), 3 deletions(-) diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index a19395b6f2..cfaef9245c 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -915,6 +915,7 @@ private: uint32_t perf_info_get_max_time(); uint32_t perf_info_get_min_time(); uint16_t perf_info_get_num_long_running(); + uint32_t perf_info_get_num_dropped(); Vector3f pv_location_to_vector(const Location& loc); Vector3f pv_location_to_vector_with_default(const Location& loc, const Vector3f& default_posvec); float pv_alt_above_origin(float alt_above_home_cm); diff --git a/ArduCopter/Log.cpp b/ArduCopter/Log.cpp index b8d7fdaebb..06920824c3 100644 --- a/ArduCopter/Log.cpp +++ b/ArduCopter/Log.cpp @@ -339,6 +339,7 @@ struct PACKED log_Performance { int16_t pm_test; uint8_t i2c_lockup_count; uint16_t ins_error_count; + uint32_t log_dropped; }; // Write a performance monitoring packet @@ -352,9 +353,10 @@ void Copter::Log_Write_Performance() max_time : perf_info_get_max_time(), pm_test : pmTest1, i2c_lockup_count : hal.i2c->lockup_count(), - ins_error_count : ins.error_count() + ins_error_count : ins.error_count(), + log_dropped : DataFlash.num_dropped() - perf_info_get_num_dropped(), }; - DataFlash.WriteBlock(&pkt, sizeof(pkt)); + DataFlash.WriteCriticalBlock(&pkt, sizeof(pkt)); } // Write an attitude packet @@ -731,7 +733,7 @@ const struct LogStructure Copter::log_structure[] = { { LOG_CONTROL_TUNING_MSG, sizeof(log_Control_Tuning), "CTUN", "Qfffffecchh", "TimeUS,ThrIn,AngBst,ThrOut,DAlt,Alt,BarAlt,DSAlt,SAlt,DCRt,CRt" }, { LOG_PERFORMANCE_MSG, sizeof(log_Performance), - "PM", "QHHIhBH", "TimeUS,NLon,NLoop,MaxT,PMT,I2CErr,INSErr" }, + "PM", "QHHIhBHI", "TimeUS,NLon,NLoop,MaxT,PMT,I2CErr,INSErr,LogDrop" }, { LOG_MOTBATT_MSG, sizeof(log_MotBatt), "MOTB", "Qffff", "TimeUS,LiftMax,BatVolt,BatRes,ThLimit" }, { LOG_STARTUP_MSG, sizeof(log_Startup), diff --git a/ArduCopter/perf_info.cpp b/ArduCopter/perf_info.cpp index 7da62c69f3..e6d499c999 100644 --- a/ArduCopter/perf_info.cpp +++ b/ArduCopter/perf_info.cpp @@ -15,6 +15,7 @@ static uint16_t perf_info_loop_count; static uint32_t perf_info_max_time; static uint32_t perf_info_min_time; static uint16_t perf_info_long_running; +static uint32_t perf_info_log_dropped; static bool perf_ignore_loop = false; // perf_info_reset - reset all records of loop time to zero @@ -24,6 +25,7 @@ void Copter::perf_info_reset() perf_info_max_time = 0; perf_info_min_time = 0; perf_info_long_running = 0; + perf_info_log_dropped = DataFlash.num_dropped(); } // perf_ignore_loop - ignore this loop from performance measurements (used to reduce false positive when arming) @@ -77,3 +79,9 @@ uint16_t Copter::perf_info_get_num_long_running() { return perf_info_long_running; } + +// perf_info_get_num_dropped - get number of dropped log messages +uint32_t Copter::perf_info_get_num_dropped() +{ + return perf_info_log_dropped; +}