From f07ac41c654630fc385924813fd83edca88a9020 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 19 Jun 2024 14:00:08 +1000 Subject: [PATCH] AP_Notify: rename Notify buzzertype enumeration --- libraries/AP_Notify/AP_Notify.cpp | 4 ++-- libraries/AP_Notify/AP_Notify.h | 10 +++++----- libraries/AP_Notify/MMLPlayer.cpp | 2 +- 3 files changed, 8 insertions(+), 8 deletions(-) diff --git a/libraries/AP_Notify/AP_Notify.cpp b/libraries/AP_Notify/AP_Notify.cpp index 577916e733..4bbebe497f 100644 --- a/libraries/AP_Notify/AP_Notify.cpp +++ b/libraries/AP_Notify/AP_Notify.cpp @@ -132,9 +132,9 @@ AP_Notify *AP_Notify::_singleton; #ifndef BUZZER_ENABLE_DEFAULT #if HAL_CANMANAGER_ENABLED // Enable Buzzer messages over UAVCAN -#define BUZZER_ENABLE_DEFAULT (Notify_Buzz_Builtin | Notify_Buzz_UAVCAN) +#define BUZZER_ENABLE_DEFAULT (uint8_t(BuzzerType::BUILTIN) | uint8_t(BuzzerType::UAVCAN)) #else -#define BUZZER_ENABLE_DEFAULT Notify_Buzz_Builtin +#define BUZZER_ENABLE_DEFAULT uint8_t(BuzzerType::BUILTIN) #endif #endif diff --git a/libraries/AP_Notify/AP_Notify.h b/libraries/AP_Notify/AP_Notify.h index b71988bdf1..f9f5e1fd04 100644 --- a/libraries/AP_Notify/AP_Notify.h +++ b/libraries/AP_Notify/AP_Notify.h @@ -103,11 +103,11 @@ public: Notify_LED_MAX }; - enum Notify_Buzz_Type { - Notify_Buzz_None = 0, - Notify_Buzz_Builtin = (1 << 0), // Built in default Alarm Out - Notify_Buzz_DShot = (1 << 1), // DShot Alarm - Notify_Buzz_UAVCAN = (1 << 2), // UAVCAN Alarm + enum class BuzzerType : uint8_t { + NONE = 0, + BUILTIN = (1 << 0), // Built in default Alarm Out + DSHOT = (1 << 1), // DShot Alarm + UAVCAN = (1 << 2), // UAVCAN Alarm }; /// notify_flags_type - bitmask of notification flags diff --git a/libraries/AP_Notify/MMLPlayer.cpp b/libraries/AP_Notify/MMLPlayer.cpp index 962cceb21c..9e01c53882 100644 --- a/libraries/AP_Notify/MMLPlayer.cpp +++ b/libraries/AP_Notify/MMLPlayer.cpp @@ -72,7 +72,7 @@ void MMLPlayer::start_note(float duration, float frequency, float volume) for (uint8_t i = 0; i < can_num_drivers; i++) { AP_DroneCAN *uavcan = AP_DroneCAN::get_dronecan(i); if (uavcan != nullptr && - (AP::notify().get_buzzer_types() & AP_Notify::Notify_Buzz_UAVCAN)) { + (AP::notify().get_buzzer_types() & uint8_t(AP_Notify::BuzzerType::UAVCAN))) { msg.frequency = frequency; msg.duration = _note_duration_us*1.0e-6; uavcan->buzzer.broadcast(msg);