Skip to content

Commit

Permalink
Plane: log the number of lost log messages
Browse files Browse the repository at this point in the history
  • Loading branch information
tridge committed Apr 21, 2016
1 parent c765979 commit cf7b612
Show file tree
Hide file tree
Showing 4 changed files with 15 additions and 8 deletions.
7 changes: 4 additions & 3 deletions ArduPlane/ArduPlane.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -340,11 +340,12 @@ void Plane::one_second_loop()
void Plane::log_perf_info()
{
if (scheduler.debug() != 0) {
gcs_send_text_fmt(MAV_SEVERITY_INFO, "PERF: %u/%u %lu %lu\n",
gcs_send_text_fmt(MAV_SEVERITY_INFO, "PERF: %u/%u Dt=%u/%u Log=%u\n",
(unsigned)perf.num_long,
(unsigned)perf.mainLoop_count,
(unsigned long)perf.G_Dt_max,
(unsigned long)perf.G_Dt_min);
(unsigned)perf.G_Dt_max,
(unsigned)perf.G_Dt_min,
(unsigned)(DataFlash.num_dropped() - perf.last_log_dropped));
}

if (should_log(MASK_LOG_PM)) {
Expand Down
12 changes: 7 additions & 5 deletions ArduPlane/Log.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -198,6 +198,7 @@ struct PACKED log_Performance {
uint16_t main_loop_count;
uint32_t g_dt_max;
uint32_t g_dt_min;
uint32_t log_dropped;
};

// Write a performance monitoring packet. Total length : 19 bytes
Expand All @@ -209,9 +210,10 @@ void Plane::Log_Write_Performance()
num_long : perf.num_long,
main_loop_count : perf.mainLoop_count,
g_dt_max : perf.G_Dt_max,
g_dt_min : perf.G_Dt_min
g_dt_min : perf.G_Dt_min,
log_dropped : DataFlash.num_dropped() - perf.last_log_dropped
};
DataFlash.WriteBlock(&pkt, sizeof(pkt));
DataFlash.WriteCriticalBlock(&pkt, sizeof(pkt));
}

struct PACKED log_Startup {
Expand All @@ -229,7 +231,7 @@ void Plane::Log_Write_Startup(uint8_t type)
startup_type : type,
command_total : mission.num_commands()
};
DataFlash.WriteBlock(&pkt, sizeof(pkt));
DataFlash.WriteCriticalBlock(&pkt, sizeof(pkt));
}

struct PACKED log_Control_Tuning {
Expand Down Expand Up @@ -424,7 +426,7 @@ void Plane::Log_Arm_Disarm() {
arm_state : arming.is_armed(),
arm_checks : arming.get_enabled_checks()
};
DataFlash.WriteBlock(&pkt, sizeof(pkt));
DataFlash.WriteCriticalBlock(&pkt, sizeof(pkt));
}

void Plane::Log_Write_GPS(uint8_t instance)
Expand Down Expand Up @@ -477,7 +479,7 @@ void Plane::Log_Write_Home_And_Origin()
const struct LogStructure Plane::log_structure[] = {
LOG_COMMON_STRUCTURES,
{ LOG_PERFORMANCE_MSG, sizeof(log_Performance),
"PM", "QHHII", "TimeUS,NLon,NLoop,MaxT,MinT" },
"PM", "QHHIII", "TimeUS,NLon,NLoop,MaxT,MinT,LogDrop" },
{ LOG_STARTUP_MSG, sizeof(log_Startup),
"STRT", "QBH", "TimeUS,SType,CTot" },
{ LOG_CTUN_MSG, sizeof(log_Control_Tuning),
Expand Down
3 changes: 3 additions & 0 deletions ArduPlane/Plane.h
Original file line number Diff line number Diff line change
Expand Up @@ -706,6 +706,9 @@ class Plane : public AP_HAL::HAL::Callbacks {

// number of long loops
uint16_t num_long;

// accumulated lost log messages
uint32_t last_log_dropped;
} perf;

// Camera/Antenna mount tracking and stabilisation stuff
Expand Down
1 change: 1 addition & 0 deletions ArduPlane/system.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -637,6 +637,7 @@ void Plane::resetPerfData(void)
perf.G_Dt_min = 0;
perf.num_long = 0;
perf.start_ms = millis();
perf.last_log_dropped = DataFlash.num_dropped();
}


Expand Down

0 comments on commit cf7b612

Please sign in to comment.