mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-03 12:14:10 -04:00
Plane: move logging of PM and PERF messages to AP_Scheduler
This commit is contained in:
parent
55c27dfc56
commit
8cae776448
@ -338,23 +338,7 @@ void Plane::one_second_loop()
|
||||
|
||||
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)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();
|
||||
}
|
||||
|
||||
scheduler.perf_info.reset();
|
||||
scheduler.update_logging(should_log(MASK_LOG_PM));
|
||||
}
|
||||
|
||||
void Plane::compass_save()
|
||||
|
@ -54,35 +54,6 @@ void Plane::Log_Write_Fast(void)
|
||||
}
|
||||
|
||||
|
||||
struct PACKED log_Performance {
|
||||
LOG_PACKET_HEADER;
|
||||
uint64_t time_us;
|
||||
uint16_t num_long;
|
||||
uint16_t main_loop_count;
|
||||
uint32_t g_dt_max;
|
||||
uint32_t g_dt_min;
|
||||
uint32_t log_dropped;
|
||||
uint32_t mem_avail;
|
||||
};
|
||||
|
||||
// Write a performance monitoring packet. Total length : 19 bytes
|
||||
void Plane::Log_Write_Performance()
|
||||
{
|
||||
uint32_t dropped = DataFlash.num_dropped();
|
||||
struct log_Performance pkt = {
|
||||
LOG_PACKET_HEADER_INIT(LOG_PERFORMANCE_MSG),
|
||||
time_us : AP_HAL::micros64(),
|
||||
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;
|
||||
DataFlash.WriteCriticalBlock(&pkt, sizeof(pkt));
|
||||
}
|
||||
|
||||
struct PACKED log_Startup {
|
||||
LOG_PACKET_HEADER;
|
||||
uint64_t time_us;
|
||||
@ -364,8 +335,6 @@ void Plane::Log_Write_Home_And_Origin()
|
||||
// units and "Format characters" for field type information
|
||||
const struct LogStructure Plane::log_structure[] = {
|
||||
LOG_COMMON_STRUCTURES,
|
||||
{ LOG_PERFORMANCE_MSG, sizeof(log_Performance),
|
||||
"PM", "QHHIIII", "TimeUS,NLon,NLoop,MaxT,MinT,LogDrop,Mem", "ss----b", "FC----0" },
|
||||
{ LOG_STARTUP_MSG, sizeof(log_Startup),
|
||||
"STRT", "QBH", "TimeUS,SType,CTot", "s--", "F--" },
|
||||
{ LOG_CTUN_MSG, sizeof(log_Control_Tuning),
|
||||
|
@ -121,7 +121,6 @@ typedef enum GeofenceEnableReason {
|
||||
enum log_messages {
|
||||
LOG_CTUN_MSG,
|
||||
LOG_NTUN_MSG,
|
||||
LOG_PERFORMANCE_MSG,
|
||||
LOG_STARTUP_MSG,
|
||||
TYPE_AIRSTART_MSG,
|
||||
TYPE_GROUNDSTART_MSG,
|
||||
|
Loading…
Reference in New Issue
Block a user