mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 15:23:57 -04:00
Rover: move logging of PM messages to AP_Scheduler
This commit is contained in:
parent
980fbf6cfb
commit
55c27dfc56
@ -254,11 +254,7 @@ void Rover::update_aux(void)
|
||||
|
||||
void Rover::perf_update()
|
||||
{
|
||||
if (should_log(MASK_LOG_PM)) {
|
||||
Log_Write_Performance();
|
||||
}
|
||||
scheduler.update_logging();
|
||||
perf_info.reset();
|
||||
scheduler.update_logging(should_log(MASK_LOG_PM));
|
||||
}
|
||||
|
||||
/*
|
||||
|
@ -4,39 +4,6 @@
|
||||
|
||||
#if LOGGING_ENABLED == ENABLED
|
||||
|
||||
struct PACKED log_Performance {
|
||||
LOG_PACKET_HEADER;
|
||||
uint64_t time_us;
|
||||
uint16_t num_long_running;
|
||||
uint16_t num_loops;
|
||||
uint32_t max_time;
|
||||
int16_t gyro_drift_x;
|
||||
int16_t gyro_drift_y;
|
||||
int16_t gyro_drift_z;
|
||||
uint8_t i2c_lockup_count;
|
||||
uint16_t ins_error_count;
|
||||
uint32_t mem_avail;
|
||||
};
|
||||
|
||||
// Write a performance monitoring packet. Total length : 19 bytes
|
||||
void Rover::Log_Write_Performance()
|
||||
{
|
||||
struct log_Performance pkt = {
|
||||
LOG_PACKET_HEADER_INIT(LOG_PERFORMANCE_MSG),
|
||||
time_us : AP_HAL::micros64(),
|
||||
num_long_running : scheduler.perf_info.get_num_long_running(),
|
||||
num_loops : scheduler.perf_info.get_num_loops(),
|
||||
max_time : scheduler.perf_info.get_max_time(),
|
||||
gyro_drift_x : (int16_t)(ahrs.get_gyro_drift().x * 1000),
|
||||
gyro_drift_y : (int16_t)(ahrs.get_gyro_drift().y * 1000),
|
||||
gyro_drift_z : (int16_t)(ahrs.get_gyro_drift().z * 1000),
|
||||
i2c_lockup_count: 0,
|
||||
ins_error_count : ins.error_count(),
|
||||
hal.util->available_memory()
|
||||
};
|
||||
DataFlash.WriteBlock(&pkt, sizeof(pkt));
|
||||
}
|
||||
|
||||
struct PACKED log_Steering {
|
||||
LOG_PACKET_HEADER;
|
||||
uint64_t time_us;
|
||||
@ -342,8 +309,6 @@ void Rover::Log_Write_Proximity()
|
||||
// units and "Format characters" for field type information
|
||||
const LogStructure Rover::log_structure[] = {
|
||||
LOG_COMMON_STRUCTURES,
|
||||
{ LOG_PERFORMANCE_MSG, sizeof(log_Performance),
|
||||
"PM", "QIHIhhhBHI", "TimeUS,LTime,NLoop,MaxT,GDx,GDy,GDz,I2CErr,INSErr,Mem", "ss-------b", "FC-------0" },
|
||||
{ LOG_STARTUP_MSG, sizeof(log_Startup),
|
||||
"STRT", "QBH", "TimeUS,SType,CTot", "s--", "F--" },
|
||||
{ LOG_THR_MSG, sizeof(log_Throttle),
|
||||
|
@ -55,7 +55,6 @@ enum mode {
|
||||
// Logging parameters
|
||||
#define LOG_THR_MSG 0x01
|
||||
#define LOG_NTUN_MSG 0x02
|
||||
#define LOG_PERFORMANCE_MSG 0x03
|
||||
#define LOG_STARTUP_MSG 0x06
|
||||
#define LOG_RANGEFINDER_MSG 0x07
|
||||
#define LOG_ARM_DISARM_MSG 0x08
|
||||
|
Loading…
Reference in New Issue
Block a user