mirror of https://github.com/ArduPilot/ardupilot
AP_Notify: ensure ToneAlarm is not disabled when UAVCAN is available
This commit is contained in:
parent
ae80e2dd4d
commit
b7de9feb56
|
@ -94,12 +94,17 @@ AP_Notify *AP_Notify::_singleton;
|
|||
#endif // BUILD_DEFAULT_LED_TYPE
|
||||
|
||||
#ifndef BUZZER_ENABLE_DEFAULT
|
||||
#define BUZZER_ENABLE_DEFAULT 1
|
||||
#if HAL_ENABLE_LIBUAVCAN_DRIVERS
|
||||
// Enable Buzzer messages over UAVCAN
|
||||
#define BUZZER_ENABLE_DEFAULT (Notify_Buzz_Builtin | Notify_Buzz_UAVCAN)
|
||||
#else
|
||||
#define BUZZER_ENABLE_DEFAULT Notify_Buzz_Builtin
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#ifndef BUILD_DEFAULT_BUZZER_TYPE
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS && HAL_DSHOT_ALARM
|
||||
#define BUILD_DEFAULT_BUZZER_TYPE (BUZZER_ENABLE_DEFAULT | (HAL_DSHOT_ALARM << 1))
|
||||
#define BUILD_DEFAULT_BUZZER_TYPE (BUZZER_ENABLE_DEFAULT | Notify_Buzz_DShot)
|
||||
#else
|
||||
#define BUILD_DEFAULT_BUZZER_TYPE BUZZER_ENABLE_DEFAULT
|
||||
#endif
|
||||
|
@ -134,7 +139,7 @@ const AP_Param::GroupInfo AP_Notify::var_info[] = {
|
|||
// @Param: BUZZ_TYPES
|
||||
// @DisplayName: Buzzer Driver Types
|
||||
// @Description: Controls what types of Buzzer will be enabled
|
||||
// @Bitmask: 0:Built-in buzzer, 1:DShot
|
||||
// @Bitmask: 0:Built-in buzzer, 1:DShot, 2:UAVCAN
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("BUZZ_TYPES", 1, AP_Notify, _buzzer_type, BUILD_DEFAULT_BUZZER_TYPE),
|
||||
|
||||
|
|
|
@ -76,6 +76,13 @@ 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
|
||||
};
|
||||
|
||||
/// notify_flags_type - bitmask of notification flags
|
||||
struct notify_flags_and_values_type {
|
||||
bool initialising; // true if initialising and the vehicle should not be moved
|
||||
|
|
|
@ -70,7 +70,8 @@ void MMLPlayer::start_note(float duration, float frequency, float volume)
|
|||
|
||||
for (uint8_t i = 0; i < can_num_drivers; i++) {
|
||||
AP_UAVCAN *uavcan = AP_UAVCAN::get_uavcan(i);
|
||||
if (uavcan != nullptr) {
|
||||
if (uavcan != nullptr &&
|
||||
(AP::notify().get_buzzer_types() & AP_Notify::Notify_Buzz_UAVCAN)) {
|
||||
uavcan->set_buzzer_tone(frequency, _note_duration_us*1.0e-6);
|
||||
}
|
||||
}
|
||||
|
|
|
@ -105,9 +105,14 @@ bool AP_ToneAlarm::init()
|
|||
if (pNotify->buzzer_enabled() == false) {
|
||||
return false;
|
||||
}
|
||||
#if ((defined(HAL_PWM_ALARM) || HAL_DSHOT_ALARM) && CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS) || \
|
||||
CONFIG_HAL_BOARD == HAL_BOARD_LINUX || \
|
||||
CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
if (!hal.util->toneAlarm_init(pNotify->get_buzzer_types())) {
|
||||
return false;
|
||||
}
|
||||
#endif
|
||||
|
||||
|
||||
// set initial boot states. This prevents us issuing a arming
|
||||
// warning in plane and rover on every boot
|
||||
|
|
Loading…
Reference in New Issue