mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-20 07:38:28 -04:00
Sub: move handling Write_Event into AP_Logger
This commit is contained in:
parent
3521d98b52
commit
1690f78f4c
@ -88,23 +88,10 @@ void Sub::Log_Write_MotBatt()
|
|||||||
logger.WriteBlock(&pkt_mot, sizeof(pkt_mot));
|
logger.WriteBlock(&pkt_mot, sizeof(pkt_mot));
|
||||||
}
|
}
|
||||||
|
|
||||||
struct PACKED log_Event {
|
|
||||||
LOG_PACKET_HEADER;
|
|
||||||
uint64_t time_us;
|
|
||||||
uint8_t id;
|
|
||||||
};
|
|
||||||
|
|
||||||
// Wrote an event packet
|
// Wrote an event packet
|
||||||
void Sub::Log_Write_Event(uint8_t id)
|
void Sub::Log_Write_Event(Log_Event id)
|
||||||
{
|
{
|
||||||
if (should_log(MASK_LOG_ANY)) {
|
logger.Write_Event(id);
|
||||||
struct log_Event pkt = {
|
|
||||||
LOG_PACKET_HEADER_INIT(LOG_EVENT_MSG),
|
|
||||||
time_us : AP_HAL::micros64(),
|
|
||||||
id : id
|
|
||||||
};
|
|
||||||
logger.WriteCriticalBlock(&pkt, sizeof(pkt));
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
struct PACKED log_Data_Int16t {
|
struct PACKED log_Data_Int16t {
|
||||||
@ -326,7 +313,7 @@ void Sub::Log_Write_Control_Tuning() {}
|
|||||||
void Sub::Log_Write_Performance() {}
|
void Sub::Log_Write_Performance() {}
|
||||||
void Sub::Log_Write_Attitude(void) {}
|
void Sub::Log_Write_Attitude(void) {}
|
||||||
void Sub::Log_Write_MotBatt() {}
|
void Sub::Log_Write_MotBatt() {}
|
||||||
void Sub::Log_Write_Event(uint8_t id) {}
|
void Sub::Log_Write_Event(Log_Event id) {}
|
||||||
void Sub::Log_Write_Data(uint8_t id, int32_t value) {}
|
void Sub::Log_Write_Data(uint8_t id, int32_t value) {}
|
||||||
void Sub::Log_Write_Data(uint8_t id, uint32_t value) {}
|
void Sub::Log_Write_Data(uint8_t id, uint32_t value) {}
|
||||||
void Sub::Log_Write_Data(uint8_t id, int16_t value) {}
|
void Sub::Log_Write_Data(uint8_t id, int16_t value) {}
|
||||||
|
@ -486,7 +486,7 @@ private:
|
|||||||
void Log_Write_Performance();
|
void Log_Write_Performance();
|
||||||
void Log_Write_Attitude();
|
void Log_Write_Attitude();
|
||||||
void Log_Write_MotBatt();
|
void Log_Write_MotBatt();
|
||||||
void Log_Write_Event(uint8_t id);
|
void Log_Write_Event(Log_Event id);
|
||||||
void Log_Write_Data(uint8_t id, int32_t value);
|
void Log_Write_Data(uint8_t id, int32_t value);
|
||||||
void Log_Write_Data(uint8_t id, uint32_t value);
|
void Log_Write_Data(uint8_t id, uint32_t value);
|
||||||
void Log_Write_Data(uint8_t id, int16_t value);
|
void Log_Write_Data(uint8_t id, int16_t value);
|
||||||
|
@ -136,30 +136,6 @@ enum LoggingParameters {
|
|||||||
#define MASK_LOG_IMU_RAW (1UL<<19)
|
#define MASK_LOG_IMU_RAW (1UL<<19)
|
||||||
#define MASK_LOG_ANY 0xFFFF
|
#define MASK_LOG_ANY 0xFFFF
|
||||||
|
|
||||||
// DATA - event logging
|
|
||||||
#define DATA_AP_STATE 7
|
|
||||||
// 8 was DATA_SYSTEM_TIME_SET
|
|
||||||
#define DATA_ARMED 10
|
|
||||||
#define DATA_DISARMED 11
|
|
||||||
#define DATA_LOST_GPS 19
|
|
||||||
#define DATA_SET_HOME 25
|
|
||||||
#define DATA_SAVE_TRIM 38
|
|
||||||
#define DATA_SAVEWP_ADD_WP 39
|
|
||||||
#define DATA_FENCE_ENABLE 41
|
|
||||||
#define DATA_FENCE_DISABLE 42
|
|
||||||
#define DATA_ACRO_TRAINER_DISABLED 43
|
|
||||||
#define DATA_ACRO_TRAINER_LEVELING 44
|
|
||||||
#define DATA_ACRO_TRAINER_LIMITED 45
|
|
||||||
#define DATA_GRIPPER_GRAB 46
|
|
||||||
#define DATA_GRIPPER_RELEASE 47
|
|
||||||
#define DATA_EKF_ALT_RESET 60
|
|
||||||
#define DATA_SURFACE_CANCELLED_BY_PILOT 61
|
|
||||||
#define DATA_EKF_YAW_RESET 62
|
|
||||||
#define DATA_SURFACED 63
|
|
||||||
#define DATA_NOT_SURFACED 64
|
|
||||||
#define DATA_BOTTOMED 65
|
|
||||||
#define DATA_NOT_BOTTOMED 66
|
|
||||||
|
|
||||||
// Error message sub systems and error codes
|
// Error message sub systems and error codes
|
||||||
#define ERROR_SUBSYSTEM_MAIN 1
|
#define ERROR_SUBSYSTEM_MAIN 1
|
||||||
#define ERROR_SUBSYSTEM_INPUT 2
|
#define ERROR_SUBSYSTEM_INPUT 2
|
||||||
|
Loading…
Reference in New Issue
Block a user