mirror of https://github.com/ArduPilot/ardupilot
AP_Notify: directly send dronecan beep command from the driver
This commit is contained in:
parent
a1ba65a654
commit
5066d48718
|
@ -67,12 +67,15 @@ void MMLPlayer::start_note(float duration, float frequency, float volume)
|
|||
#if HAL_ENABLE_DRONECAN_DRIVERS
|
||||
// support CAN buzzers too
|
||||
uint8_t can_num_drivers = AP::can().get_num_drivers();
|
||||
uavcan_equipment_indication_BeepCommand msg;
|
||||
|
||||
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)) {
|
||||
uavcan->set_buzzer_tone(frequency, _note_duration_us*1.0e-6);
|
||||
msg.frequency = frequency;
|
||||
msg.duration = _note_duration_us*1.0e-6;
|
||||
uavcan->buzzer.broadcast(msg);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
|
Loading…
Reference in New Issue