mirror of https://github.com/ArduPilot/ardupilot
AP_Notify: rename Notify buzzertype enumeration
This commit is contained in:
parent
6b490a4c47
commit
f07ac41c65
|
@ -132,9 +132,9 @@ AP_Notify *AP_Notify::_singleton;
|
||||||
#ifndef BUZZER_ENABLE_DEFAULT
|
#ifndef BUZZER_ENABLE_DEFAULT
|
||||||
#if HAL_CANMANAGER_ENABLED
|
#if HAL_CANMANAGER_ENABLED
|
||||||
// Enable Buzzer messages over UAVCAN
|
// 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
|
#else
|
||||||
#define BUZZER_ENABLE_DEFAULT Notify_Buzz_Builtin
|
#define BUZZER_ENABLE_DEFAULT uint8_t(BuzzerType::BUILTIN)
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
|
@ -103,11 +103,11 @@ public:
|
||||||
Notify_LED_MAX
|
Notify_LED_MAX
|
||||||
};
|
};
|
||||||
|
|
||||||
enum Notify_Buzz_Type {
|
enum class BuzzerType : uint8_t {
|
||||||
Notify_Buzz_None = 0,
|
NONE = 0,
|
||||||
Notify_Buzz_Builtin = (1 << 0), // Built in default Alarm Out
|
BUILTIN = (1 << 0), // Built in default Alarm Out
|
||||||
Notify_Buzz_DShot = (1 << 1), // DShot Alarm
|
DSHOT = (1 << 1), // DShot Alarm
|
||||||
Notify_Buzz_UAVCAN = (1 << 2), // UAVCAN Alarm
|
UAVCAN = (1 << 2), // UAVCAN Alarm
|
||||||
};
|
};
|
||||||
|
|
||||||
/// notify_flags_type - bitmask of notification flags
|
/// notify_flags_type - bitmask of notification flags
|
||||||
|
|
|
@ -72,7 +72,7 @@ void MMLPlayer::start_note(float duration, float frequency, float volume)
|
||||||
for (uint8_t i = 0; i < can_num_drivers; i++) {
|
for (uint8_t i = 0; i < can_num_drivers; i++) {
|
||||||
AP_DroneCAN *uavcan = AP_DroneCAN::get_dronecan(i);
|
AP_DroneCAN *uavcan = AP_DroneCAN::get_dronecan(i);
|
||||||
if (uavcan != nullptr &&
|
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.frequency = frequency;
|
||||||
msg.duration = _note_duration_us*1.0e-6;
|
msg.duration = _note_duration_us*1.0e-6;
|
||||||
uavcan->buzzer.broadcast(msg);
|
uavcan->buzzer.broadcast(msg);
|
||||||
|
|
Loading…
Reference in New Issue