diff --git a/libraries/AP_Logger/AP_Logger.cpp b/libraries/AP_Logger/AP_Logger.cpp index 697db9dd00..35435eeb2c 100644 --- a/libraries/AP_Logger/AP_Logger.cpp +++ b/libraries/AP_Logger/AP_Logger.cpp @@ -1138,12 +1138,12 @@ bool AP_Logger::Write_ISBD(const uint16_t isb_seqno, } // Wrote an event packet -void AP_Logger::Write_Event(Log_Event id) +void AP_Logger::Write_Event(LogEvent id) { const struct log_Event pkt{ LOG_PACKET_HEADER_INIT(LOG_EVENT_MSG), time_us : AP_HAL::micros64(), - id : id + id : (uint8_t)id }; WriteCriticalBlock(&pkt, sizeof(pkt)); } diff --git a/libraries/AP_Logger/AP_Logger.h b/libraries/AP_Logger/AP_Logger.h index e6e514e9d5..2bdd3e14b5 100644 --- a/libraries/AP_Logger/AP_Logger.h +++ b/libraries/AP_Logger/AP_Logger.h @@ -30,72 +30,75 @@ class AP_AHRS_View; // 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, - DATA_STANDBY_ENABLE = 74, - DATA_STANDBY_DISABLE = 75, +enum class LogEvent : uint8_t { + ARMED = 10, + DISARMED = 11, + AUTO_ARMED = 15, + LAND_COMPLETE_MAYBE = 17, + LAND_COMPLETE = 18, + NOT_LANDED = 28, + LOST_GPS = 19, + FLIP_START = 21, + FLIP_END = 22, + SET_HOME = 25, + SET_SIMPLE_ON = 26, + SET_SIMPLE_OFF = 27, + SET_SUPERSIMPLE_ON = 29, + AUTOTUNE_INITIALISED = 30, + AUTOTUNE_OFF = 31, + AUTOTUNE_RESTART = 32, + AUTOTUNE_SUCCESS = 33, + AUTOTUNE_FAILED = 34, + AUTOTUNE_REACHED_LIMIT = 35, + AUTOTUNE_PILOT_TESTING = 36, + AUTOTUNE_SAVEDGAINS = 37, + SAVE_TRIM = 38, + SAVEWP_ADD_WP = 39, + FENCE_ENABLE = 41, + FENCE_DISABLE = 42, + ACRO_TRAINER_OFF = 43, + ACRO_TRAINER_LEVELING = 44, + ACRO_TRAINER_LIMITED = 45, + GRIPPER_GRAB = 46, + GRIPPER_RELEASE = 47, + PARACHUTE_DISABLED = 49, + PARACHUTE_ENABLED = 50, + PARACHUTE_RELEASED = 51, + LANDING_GEAR_DEPLOYED = 52, + LANDING_GEAR_RETRACTED = 53, + MOTORS_EMERGENCY_STOPPED = 54, + MOTORS_EMERGENCY_STOP_CLEARED = 55, + MOTORS_INTERLOCK_DISABLED = 56, + MOTORS_INTERLOCK_ENABLED = 57, + ROTOR_RUNUP_COMPLETE = 58, // Heli only + ROTOR_SPEED_BELOW_CRITICAL = 59, // Heli only + EKF_ALT_RESET = 60, + LAND_CANCELLED_BY_PILOT = 61, + EKF_YAW_RESET = 62, + AVOIDANCE_ADSB_ENABLE = 63, + AVOIDANCE_ADSB_DISABLE = 64, + AVOIDANCE_PROXIMITY_ENABLE = 65, + AVOIDANCE_PROXIMITY_DISABLE = 66, + GPS_PRIMARY_CHANGED = 67, + WINCH_RELAXED = 68, + WINCH_LENGTH_CONTROL = 69, + WINCH_RATE_CONTROL = 70, + ZIGZAG_STORE_A = 71, + ZIGZAG_STORE_B = 72, + LAND_REPO_ACTIVE = 73, + STANDBY_ENABLE = 74, + STANDBY_DISABLE = 75, - DATA_SURFACED = 163, - DATA_NOT_SURFACED = 164, - DATA_BOTTOMED = 165, - DATA_NOT_BOTTOMED = 166, + SURFACED = 163, + NOT_SURFACED = 164, + BOTTOMED = 165, + NOT_BOTTOMED = 166, +}; + +enum class LogDataID : uint8_t { + AP_STATE = 7, +// SYSTEM_TIME_SET = 8, + INIT_SIMPLE_BEARING = 9, }; enum class LogErrorSubsystem : uint8_t { @@ -221,7 +224,7 @@ public: void StopLogging(); void Write_Parameter(const char *name, float value); - void Write_Event(Log_Event id); + void Write_Event(LogEvent id); void Write_Error(LogErrorSubsystem sub_system, LogErrorCode error_code); void Write_GPS(uint8_t instance, uint64_t time_us=0);