From c369139be0d04fd8ad9e780fb03718412efa9306 Mon Sep 17 00:00:00 2001 From: Michael du Breuil Date: Wed, 16 Oct 2019 20:48:00 -0700 Subject: [PATCH] AP_Logger: Support new ModeReason --- libraries/AP_Logger/AP_Logger.cpp | 2 +- libraries/AP_Logger/AP_Logger.h | 3 ++- libraries/AP_Logger/AP_Logger_Backend.h | 2 +- libraries/AP_Logger/LogFile.cpp | 5 +++-- 4 files changed, 7 insertions(+), 5 deletions(-) diff --git a/libraries/AP_Logger/AP_Logger.cpp b/libraries/AP_Logger/AP_Logger.cpp index 12cb0d2524..697db9dd00 100644 --- a/libraries/AP_Logger/AP_Logger.cpp +++ b/libraries/AP_Logger/AP_Logger.cpp @@ -705,7 +705,7 @@ void AP_Logger::Write_Message(const char *message) FOR_EACH_BACKEND(Write_Message(message)); } -void AP_Logger::Write_Mode(uint8_t mode, uint8_t reason) +void AP_Logger::Write_Mode(uint8_t mode, const ModeReason reason) { FOR_EACH_BACKEND(Write_Mode(mode, reason)); } diff --git a/libraries/AP_Logger/AP_Logger.h b/libraries/AP_Logger/AP_Logger.h index cd9a6dbb99..e6e514e9d5 100644 --- a/libraries/AP_Logger/AP_Logger.h +++ b/libraries/AP_Logger/AP_Logger.h @@ -18,6 +18,7 @@ #include #include #include +#include #include @@ -258,7 +259,7 @@ public: void Write_AttitudeView(AP_AHRS_View &ahrs, const Vector3f &targets); void Write_Current(); void Write_Compass(uint64_t time_us=0); - void Write_Mode(uint8_t mode, uint8_t reason); + void Write_Mode(uint8_t mode, const ModeReason reason); void Write_EntireMission(); void Write_Command(const mavlink_command_int_t &packet, MAV_RESULT result, bool was_command_long=false); diff --git a/libraries/AP_Logger/AP_Logger_Backend.h b/libraries/AP_Logger/AP_Logger_Backend.h index 1ea8d183f7..2e4b87bc47 100644 --- a/libraries/AP_Logger/AP_Logger_Backend.h +++ b/libraries/AP_Logger/AP_Logger_Backend.h @@ -93,7 +93,7 @@ public: bool Write_MessageF(const char *fmt, ...); bool Write_Mission_Cmd(const AP_Mission &mission, const AP_Mission::Mission_Command &cmd); - bool Write_Mode(uint8_t mode, uint8_t reason = 0); + bool Write_Mode(uint8_t mode, const ModeReason reason = ModeReason::UNKNOWN); bool Write_Parameter(const char *name, float value); bool Write_Parameter(const AP_Param *ap, const AP_Param::ParamToken &token, diff --git a/libraries/AP_Logger/LogFile.cpp b/libraries/AP_Logger/LogFile.cpp index b327a192c9..2ba523a549 100644 --- a/libraries/AP_Logger/LogFile.cpp +++ b/libraries/AP_Logger/LogFile.cpp @@ -760,14 +760,15 @@ void AP_Logger::Write_Compass(uint64_t time_us) } // Write a mode packet. -bool AP_Logger_Backend::Write_Mode(uint8_t mode, uint8_t reason) +bool AP_Logger_Backend::Write_Mode(uint8_t mode, const ModeReason reason) { + static_assert(sizeof(ModeReason) <= sizeof(uint8_t), "Logging expects the ModeReason to fit in 8 bits"); const struct log_Mode pkt{ LOG_PACKET_HEADER_INIT(LOG_MODE_MSG), time_us : AP_HAL::micros64(), mode : mode, mode_num : mode, - mode_reason : reason + mode_reason : static_cast(reason) }; return WriteCriticalBlock(&pkt, sizeof(pkt)); }