|
|
@ -266,6 +266,7 @@ void PX4Util::free_type(void *ptr, size_t size, AP_HAL::Util::Memory_Type mem_ty |
|
|
|
|
|
|
|
|
|
|
|
extern "C" { |
|
|
|
extern "C" { |
|
|
|
int bl_update_main(int argc, char *argv[]); |
|
|
|
int bl_update_main(int argc, char *argv[]); |
|
|
|
|
|
|
|
int tone_alarm_main(int argc, char *argv[]); |
|
|
|
}; |
|
|
|
}; |
|
|
|
|
|
|
|
|
|
|
|
bool PX4Util::flash_bootloader() |
|
|
|
bool PX4Util::flash_bootloader() |
|
|
@ -279,18 +280,25 @@ bool PX4Util::flash_bootloader() |
|
|
|
return false; |
|
|
|
return false; |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
bool PX4Util::toneAlarm_init() { |
|
|
|
bool PX4Util::toneAlarm_init() |
|
|
|
|
|
|
|
{ |
|
|
|
|
|
|
|
if (!AP_BoardConfig::px4_start_driver(tone_alarm_main, "tone_alarm", "start")) { |
|
|
|
|
|
|
|
hal.console->printf("Failed to start tone_alarm\n"); |
|
|
|
|
|
|
|
return false; |
|
|
|
|
|
|
|
} |
|
|
|
_tonealarm_fd = open(TONEALARM0_DEVICE_PATH, O_WRONLY); |
|
|
|
_tonealarm_fd = open(TONEALARM0_DEVICE_PATH, O_WRONLY); |
|
|
|
if (_tonealarm_fd == -1) { |
|
|
|
if (_tonealarm_fd == -1) { |
|
|
|
hal.console->printf("ToneAlarm_PX4: Unable to open " TONEALARM0_DEVICE_PATH); |
|
|
|
hal.console->printf("ToneAlarm_PX4: Unable to open " TONEALARM0_DEVICE_PATH); |
|
|
|
return false; |
|
|
|
return false; |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
return true; |
|
|
|
return true; |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
void PX4Util::toneAlarm_set_buzzer_tone(float frequency, float volume, uint32_t duration_ms) { |
|
|
|
void PX4Util::toneAlarm_set_buzzer_tone(float frequency, float volume, uint32_t duration_ms) |
|
|
|
|
|
|
|
{ |
|
|
|
|
|
|
|
if (_tonealarm_fd == -1) { |
|
|
|
|
|
|
|
return; |
|
|
|
|
|
|
|
} |
|
|
|
if (is_zero(frequency) || is_zero(volume)) { |
|
|
|
if (is_zero(frequency) || is_zero(volume)) { |
|
|
|
write(_tonealarm_fd, "MFP", 4); |
|
|
|
write(_tonealarm_fd, "MFP", 4); |
|
|
|
} else { |
|
|
|
} else { |
|
|
|