mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-05 15:33:57 -04:00
Sub: move logging of PM messages to AP_Scheduler
This commit is contained in:
parent
bfc373aeff
commit
980fbf6cfb
@ -94,12 +94,7 @@ void Sub::setup()
|
|||||||
|
|
||||||
void Sub::perf_update(void)
|
void Sub::perf_update(void)
|
||||||
{
|
{
|
||||||
if (should_log(MASK_LOG_PM)) {
|
scheduler.update_logging(should_log(MASK_LOG_PM));
|
||||||
Log_Write_Performance();
|
|
||||||
}
|
|
||||||
scheduler.update_logging();
|
|
||||||
scheduler.perf_info.reset();
|
|
||||||
pmTest1 = 0;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void Sub::loop()
|
void Sub::loop()
|
||||||
|
@ -872,7 +872,6 @@ void GCS_MAVLINK_Sub::handleMessage(mavlink_message_t* msg)
|
|||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
sub.failsafe.last_heartbeat_ms = AP_HAL::millis();
|
sub.failsafe.last_heartbeat_ms = AP_HAL::millis();
|
||||||
sub.pmTest1++;
|
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -131,37 +131,6 @@ void Sub::Log_Write_Control_Tuning()
|
|||||||
DataFlash.WriteBlock(&pkt, sizeof(pkt));
|
DataFlash.WriteBlock(&pkt, sizeof(pkt));
|
||||||
}
|
}
|
||||||
|
|
||||||
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 pm_test;
|
|
||||||
uint8_t i2c_lockup_count;
|
|
||||||
uint16_t ins_error_count;
|
|
||||||
uint32_t log_dropped;
|
|
||||||
uint32_t mem_avail;
|
|
||||||
};
|
|
||||||
|
|
||||||
// Write a performance monitoring packet
|
|
||||||
void Sub::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(),
|
|
||||||
pm_test : pmTest1,
|
|
||||||
i2c_lockup_count : 0,
|
|
||||||
ins_error_count : ins.error_count(),
|
|
||||||
log_dropped : DataFlash.num_dropped() - scheduler.perf_info.get_num_dropped(),
|
|
||||||
hal.util->available_memory()
|
|
||||||
};
|
|
||||||
DataFlash.WriteCriticalBlock(&pkt, sizeof(pkt));
|
|
||||||
}
|
|
||||||
|
|
||||||
// Write an attitude packet
|
// Write an attitude packet
|
||||||
void Sub::Log_Write_Attitude()
|
void Sub::Log_Write_Attitude()
|
||||||
{
|
{
|
||||||
@ -424,8 +393,6 @@ const struct LogStructure Sub::log_structure[] = {
|
|||||||
"NTUN", "Qffffffffff", "TimeUS,DPosX,DPosY,PosX,PosY,DVelX,DVelY,VelX,VelY,DAccX,DAccY", "smmmmnnnnoo", "FBBBBBBBBBB" },
|
"NTUN", "Qffffffffff", "TimeUS,DPosX,DPosY,PosX,PosY,DVelX,DVelY,VelX,VelY,DAccX,DAccY", "smmmmnnnnoo", "FBBBBBBBBBB" },
|
||||||
{ LOG_CONTROL_TUNING_MSG, sizeof(log_Control_Tuning),
|
{ LOG_CONTROL_TUNING_MSG, sizeof(log_Control_Tuning),
|
||||||
"CTUN", "Qfffffffccfhh", "TimeUS,ThI,ABst,ThO,ThH,DAlt,Alt,BAlt,DSAlt,SAlt,TAlt,DCRt,CRt", "s----mmmmmmnn", "F----00BBBBBB" },
|
"CTUN", "Qfffffffccfhh", "TimeUS,ThI,ABst,ThO,ThH,DAlt,Alt,BAlt,DSAlt,SAlt,TAlt,DCRt,CRt", "s----mmmmmmnn", "F----00BBBBBB" },
|
||||||
{ LOG_PERFORMANCE_MSG, sizeof(log_Performance),
|
|
||||||
"PM", "QHHIhBHII", "TimeUS,NLon,NLoop,MaxT,PMT,I2CErr,INSErr,LogDrop,Mem", "s-------b", "F-------0" },
|
|
||||||
{ LOG_MOTBATT_MSG, sizeof(log_MotBatt),
|
{ LOG_MOTBATT_MSG, sizeof(log_MotBatt),
|
||||||
"MOTB", "Qffff", "TimeUS,LiftMax,BatVolt,BatRes,ThLimit", "s-vw-", "F-00-" },
|
"MOTB", "Qffff", "TimeUS,LiftMax,BatVolt,BatRes,ThLimit", "s-vw-", "F-00-" },
|
||||||
{ LOG_EVENT_MSG, sizeof(log_Event),
|
{ LOG_EVENT_MSG, sizeof(log_Event),
|
||||||
|
@ -51,7 +51,6 @@ Sub::Sub(void)
|
|||||||
pos_control(ahrs_view, inertial_nav, motors, attitude_control),
|
pos_control(ahrs_view, inertial_nav, motors, attitude_control),
|
||||||
wp_nav(inertial_nav, ahrs_view, pos_control, attitude_control),
|
wp_nav(inertial_nav, ahrs_view, pos_control, attitude_control),
|
||||||
circle_nav(inertial_nav, ahrs_view, pos_control),
|
circle_nav(inertial_nav, ahrs_view, pos_control),
|
||||||
pmTest1(0),
|
|
||||||
in_mavlink_delay(false),
|
in_mavlink_delay(false),
|
||||||
param_loader(var_info),
|
param_loader(var_info),
|
||||||
last_pilot_yaw_input_ms(0)
|
last_pilot_yaw_input_ms(0)
|
||||||
|
@ -395,9 +395,6 @@ private:
|
|||||||
AC_WPNav wp_nav;
|
AC_WPNav wp_nav;
|
||||||
AC_Circle circle_nav;
|
AC_Circle circle_nav;
|
||||||
|
|
||||||
// Performance monitoring
|
|
||||||
int16_t pmTest1;
|
|
||||||
|
|
||||||
// Reference to the relay object
|
// Reference to the relay object
|
||||||
AP_Relay relay;
|
AP_Relay relay;
|
||||||
|
|
||||||
|
@ -112,7 +112,6 @@ enum RTLState {
|
|||||||
#define TYPE_GROUNDSTART_MSG 0x01
|
#define TYPE_GROUNDSTART_MSG 0x01
|
||||||
#define LOG_CONTROL_TUNING_MSG 0x04
|
#define LOG_CONTROL_TUNING_MSG 0x04
|
||||||
#define LOG_NAV_TUNING_MSG 0x05
|
#define LOG_NAV_TUNING_MSG 0x05
|
||||||
#define LOG_PERFORMANCE_MSG 0x06
|
|
||||||
#define LOG_OPTFLOW_MSG 0x0C
|
#define LOG_OPTFLOW_MSG 0x0C
|
||||||
#define LOG_EVENT_MSG 0x0D
|
#define LOG_EVENT_MSG 0x0D
|
||||||
#define LOG_ERROR_MSG 0x13
|
#define LOG_ERROR_MSG 0x13
|
||||||
|
Loading…
Reference in New Issue
Block a user