AP_Logger: move handling Write_Event into AP_Logger
This commit is contained in:
parent
bb76143095
commit
78e76b84b2
@ -1056,6 +1056,17 @@ bool AP_Logger::Write_ISBD(const uint16_t isb_seqno,
|
|||||||
return backends[0]->WriteBlock(&pkt, sizeof(pkt));
|
return backends[0]->WriteBlock(&pkt, sizeof(pkt));
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// Wrote an event packet
|
||||||
|
void AP_Logger::Write_Event(Log_Event id)
|
||||||
|
{
|
||||||
|
struct log_Event pkt = {
|
||||||
|
LOG_PACKET_HEADER_INIT(LOG_EVENT_MSG),
|
||||||
|
time_us : AP_HAL::micros64(),
|
||||||
|
id : id
|
||||||
|
};
|
||||||
|
WriteCriticalBlock(&pkt, sizeof(pkt));
|
||||||
|
}
|
||||||
|
|
||||||
AP_Logger &AP::logger()
|
AP_Logger &AP::logger()
|
||||||
{
|
{
|
||||||
return *AP_Logger::instance();
|
return *AP_Logger::instance();
|
||||||
|
@ -37,6 +37,69 @@ enum AP_Logger_Backend_Type {
|
|||||||
DATAFLASH_BACKEND_BLOCK = (1<<2),
|
DATAFLASH_BACKEND_BLOCK = (1<<2),
|
||||||
};
|
};
|
||||||
|
|
||||||
|
// do not do anything here apart from add stuff; maintaining older
|
||||||
|
// entries means log analysis is easier
|
||||||
|
enum Log_Event : uint8_t {
|
||||||
|
DATA_AP_STATE = 7,
|
||||||
|
// DATA_SYSTEM_TIME_SET = 8,
|
||||||
|
DATA_INIT_SIMPLE_BEARING = 9,
|
||||||
|
DATA_ARMED = 10,
|
||||||
|
DATA_DISARMED = 11,
|
||||||
|
DATA_AUTO_ARMED = 15,
|
||||||
|
DATA_LAND_COMPLETE_MAYBE = 17,
|
||||||
|
DATA_LAND_COMPLETE = 18,
|
||||||
|
DATA_NOT_LANDED = 28,
|
||||||
|
DATA_LOST_GPS = 19,
|
||||||
|
DATA_FLIP_START = 21,
|
||||||
|
DATA_FLIP_END = 22,
|
||||||
|
DATA_SET_HOME = 25,
|
||||||
|
DATA_SET_SIMPLE_ON = 26,
|
||||||
|
DATA_SET_SIMPLE_OFF = 27,
|
||||||
|
DATA_SET_SUPERSIMPLE_ON = 29,
|
||||||
|
DATA_AUTOTUNE_INITIALISED = 30,
|
||||||
|
DATA_AUTOTUNE_OFF = 31,
|
||||||
|
DATA_AUTOTUNE_RESTART = 32,
|
||||||
|
DATA_AUTOTUNE_SUCCESS = 33,
|
||||||
|
DATA_AUTOTUNE_FAILED = 34,
|
||||||
|
DATA_AUTOTUNE_REACHED_LIMIT = 35,
|
||||||
|
DATA_AUTOTUNE_PILOT_TESTING = 36,
|
||||||
|
DATA_AUTOTUNE_SAVEDGAINS = 37,
|
||||||
|
DATA_SAVE_TRIM = 38,
|
||||||
|
DATA_SAVEWP_ADD_WP = 39,
|
||||||
|
DATA_FENCE_ENABLE = 41,
|
||||||
|
DATA_FENCE_DISABLE = 42,
|
||||||
|
DATA_ACRO_TRAINER_DISABLED = 43,
|
||||||
|
DATA_ACRO_TRAINER_LEVELING = 44,
|
||||||
|
DATA_ACRO_TRAINER_LIMITED = 45,
|
||||||
|
DATA_GRIPPER_GRAB = 46,
|
||||||
|
DATA_GRIPPER_RELEASE = 47,
|
||||||
|
DATA_PARACHUTE_DISABLED = 49,
|
||||||
|
DATA_PARACHUTE_ENABLED = 50,
|
||||||
|
DATA_PARACHUTE_RELEASED = 51,
|
||||||
|
DATA_LANDING_GEAR_DEPLOYED = 52,
|
||||||
|
DATA_LANDING_GEAR_RETRACTED = 53,
|
||||||
|
DATA_MOTORS_EMERGENCY_STOPPED = 54,
|
||||||
|
DATA_MOTORS_EMERGENCY_STOP_CLEARED = 55,
|
||||||
|
DATA_MOTORS_INTERLOCK_DISABLED = 56,
|
||||||
|
DATA_MOTORS_INTERLOCK_ENABLED = 57,
|
||||||
|
DATA_ROTOR_RUNUP_COMPLETE = 58, // Heli only
|
||||||
|
DATA_ROTOR_SPEED_BELOW_CRITICAL = 59, // Heli only
|
||||||
|
DATA_EKF_ALT_RESET = 60,
|
||||||
|
DATA_LAND_CANCELLED_BY_PILOT = 61,
|
||||||
|
DATA_EKF_YAW_RESET = 62,
|
||||||
|
DATA_AVOIDANCE_ADSB_ENABLE = 63,
|
||||||
|
DATA_AVOIDANCE_ADSB_DISABLE = 64,
|
||||||
|
DATA_AVOIDANCE_PROXIMITY_ENABLE = 65,
|
||||||
|
DATA_AVOIDANCE_PROXIMITY_DISABLE = 66,
|
||||||
|
DATA_GPS_PRIMARY_CHANGED = 67,
|
||||||
|
DATA_WINCH_RELAXED = 68,
|
||||||
|
DATA_WINCH_LENGTH_CONTROL = 69,
|
||||||
|
DATA_WINCH_RATE_CONTROL = 70,
|
||||||
|
DATA_ZIGZAG_STORE_A = 71,
|
||||||
|
DATA_ZIGZAG_STORE_B = 72,
|
||||||
|
DATA_LAND_REPO_ACTIVE = 73,
|
||||||
|
};
|
||||||
|
|
||||||
// fwd declarations to avoid include errors
|
// fwd declarations to avoid include errors
|
||||||
class AC_AttitudeControl;
|
class AC_AttitudeControl;
|
||||||
class AC_PosControl;
|
class AC_PosControl;
|
||||||
@ -88,6 +151,7 @@ public:
|
|||||||
void StopLogging();
|
void StopLogging();
|
||||||
|
|
||||||
void Write_Parameter(const char *name, float value);
|
void Write_Parameter(const char *name, float value);
|
||||||
|
void Write_Event(Log_Event id);
|
||||||
void Write_GPS(uint8_t instance, uint64_t time_us=0);
|
void Write_GPS(uint8_t instance, uint64_t time_us=0);
|
||||||
void Write_RFND(const RangeFinder &rangefinder);
|
void Write_RFND(const RangeFinder &rangefinder);
|
||||||
void Write_IMU();
|
void Write_IMU();
|
||||||
|
@ -158,6 +158,11 @@ struct PACKED log_DSF {
|
|||||||
uint32_t buf_space_avg;
|
uint32_t buf_space_avg;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
struct PACKED log_Event {
|
||||||
|
LOG_PACKET_HEADER;
|
||||||
|
uint64_t time_us;
|
||||||
|
uint8_t id;
|
||||||
|
};
|
||||||
struct PACKED log_GPS {
|
struct PACKED log_GPS {
|
||||||
LOG_PACKET_HEADER;
|
LOG_PACKET_HEADER;
|
||||||
uint64_t time_us;
|
uint64_t time_us;
|
||||||
@ -1460,6 +1465,8 @@ Format characters in the format string for binary log messages
|
|||||||
"SBRH", "QQQQQQQQ", "TimeUS,msg_flag,1,2,3,4,5,6", "s--b----", "F--0----" }, \
|
"SBRH", "QQQQQQQQ", "TimeUS,msg_flag,1,2,3,4,5,6", "s--b----", "F--0----" }, \
|
||||||
{ LOG_MSG_SBPRAWM, sizeof(log_SbpRAWM), \
|
{ LOG_MSG_SBPRAWM, sizeof(log_SbpRAWM), \
|
||||||
"SBRM", "QQQQQQQQQQQQQQQ", "TimeUS,msg_flag,1,2,3,4,5,6,7,8,9,10,11,12,13", "s??????????????", "F??????????????" }, \
|
"SBRM", "QQQQQQQQQQQQQQQ", "TimeUS,msg_flag,1,2,3,4,5,6,7,8,9,10,11,12,13", "s??????????????", "F??????????????" }, \
|
||||||
|
{ LOG_EVENT_MSG, sizeof(log_Event), \
|
||||||
|
"EV", "QB", "TimeUS,Id", "s-", "F-" }, \
|
||||||
{ LOG_MSG_SBPEVENT, sizeof(log_SbpEvent), \
|
{ LOG_MSG_SBPEVENT, sizeof(log_SbpEvent), \
|
||||||
"SBRE", "QHIiBB", "TimeUS,GWk,GMS,ns_residual,level,quality", "s?????", "F?????" }
|
"SBRE", "QHIiBB", "TimeUS,GWk,GMS,ns_residual,level,quality", "s?????", "F?????" }
|
||||||
// #endif
|
// #endif
|
||||||
@ -1616,6 +1623,7 @@ enum LogMessages : uint8_t {
|
|||||||
LOG_ASP2_MSG,
|
LOG_ASP2_MSG,
|
||||||
LOG_PERFORMANCE_MSG,
|
LOG_PERFORMANCE_MSG,
|
||||||
LOG_OPTFLOW_MSG,
|
LOG_OPTFLOW_MSG,
|
||||||
|
LOG_EVENT_MSG,
|
||||||
_LOG_LAST_MSG_
|
_LOG_LAST_MSG_
|
||||||
};
|
};
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user