Skip to content

Commit

Permalink
Copter: added logging of dropped log messages in PM message
Browse files Browse the repository at this point in the history
  • Loading branch information
tridge committed Apr 21, 2016
1 parent fd51c3c commit 5149a49
Show file tree
Hide file tree
Showing 3 changed files with 14 additions and 3 deletions.
1 change: 1 addition & 0 deletions ArduCopter/Copter.h
Original file line number Diff line number Diff line change
Expand Up @@ -915,6 +915,7 @@ class Copter : public AP_HAL::HAL::Callbacks {
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);
Expand Down
8 changes: 5 additions & 3 deletions ArduCopter/Log.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -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
Expand Down Expand Up @@ -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),
Expand Down
8 changes: 8 additions & 0 deletions ArduCopter/perf_info.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -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)
Expand Down Expand Up @@ -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;
}

0 comments on commit 5149a49

Please sign in to comment.