|
|
@ -13,6 +13,11 @@ |
|
|
|
|
|
|
|
|
|
|
|
using namespace Linux; |
|
|
|
using namespace Linux; |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_RASPILOT |
|
|
|
|
|
|
|
#include "GPIO.h" |
|
|
|
|
|
|
|
#define RASPILOT_TONE_PIN RPI_GPIO_18 |
|
|
|
|
|
|
|
#endif |
|
|
|
|
|
|
|
|
|
|
|
extern const AP_HAL::HAL& hal; |
|
|
|
extern const AP_HAL::HAL& hal; |
|
|
|
static uint16_t notes[] = { 0, |
|
|
|
static uint16_t notes[] = { 0, |
|
|
|
NOTE_C4, NOTE_CS4, NOTE_D4, NOTE_DS4, NOTE_E4, NOTE_F4, NOTE_FS4, NOTE_G4, NOTE_GS4, NOTE_A4, NOTE_AS4, NOTE_B4, |
|
|
|
NOTE_C4, NOTE_CS4, NOTE_D4, NOTE_DS4, NOTE_E4, NOTE_F4, NOTE_FS4, NOTE_G4, NOTE_GS4, NOTE_A4, NOTE_AS4, NOTE_B4, |
|
|
@ -50,10 +55,16 @@ ToneAlarm::ToneAlarm() |
|
|
|
bool ToneAlarm::init() |
|
|
|
bool ToneAlarm::init() |
|
|
|
{ |
|
|
|
{ |
|
|
|
tune_num = 0; //play startup tune
|
|
|
|
tune_num = 0; //play startup tune
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_RASPILOT |
|
|
|
|
|
|
|
hal.gpio->pinMode(RASPILOT_TONE_PIN, HAL_GPIO_ALT, 5); |
|
|
|
|
|
|
|
#else |
|
|
|
if((period_fd == -1) || (duty_fd == -1) || (run_fd == -1)){ |
|
|
|
if((period_fd == -1) || (duty_fd == -1) || (run_fd == -1)){ |
|
|
|
hal.console->printf("ToneAlarm: Error!! please check if PWM overlays are loaded correctly"); |
|
|
|
hal.console->printf("ToneAlarm: Error!! please check if PWM overlays are loaded correctly"); |
|
|
|
return false; |
|
|
|
return false; |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
#endif |
|
|
|
|
|
|
|
|
|
|
|
return true; |
|
|
|
return true; |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
@ -69,7 +80,11 @@ bool ToneAlarm::is_tune_comp() |
|
|
|
|
|
|
|
|
|
|
|
void ToneAlarm::stop() |
|
|
|
void ToneAlarm::stop() |
|
|
|
{ |
|
|
|
{ |
|
|
|
|
|
|
|
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_RASPILOT |
|
|
|
|
|
|
|
hal.gpio->setPWMDuty(RASPILOT_TONE_PIN, 0); |
|
|
|
|
|
|
|
#else |
|
|
|
dprintf(run_fd,"0"); |
|
|
|
dprintf(run_fd,"0"); |
|
|
|
|
|
|
|
#endif |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
bool ToneAlarm::play() |
|
|
|
bool ToneAlarm::play() |
|
|
@ -80,10 +95,15 @@ bool ToneAlarm::play() |
|
|
|
return true; |
|
|
|
return true; |
|
|
|
} |
|
|
|
} |
|
|
|
if(cur_note != 0){ |
|
|
|
if(cur_note != 0){ |
|
|
|
|
|
|
|
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_RASPILOT |
|
|
|
|
|
|
|
hal.gpio->setPWMPeriod(RASPILOT_TONE_PIN, 1000000/cur_note); |
|
|
|
|
|
|
|
hal.gpio->setPWMDuty(RASPILOT_TONE_PIN, 50); |
|
|
|
|
|
|
|
#else |
|
|
|
dprintf(run_fd,"0"); |
|
|
|
dprintf(run_fd,"0"); |
|
|
|
dprintf(period_fd,"%u",1000000000/cur_note); |
|
|
|
dprintf(period_fd,"%u",1000000000/cur_note); |
|
|
|
dprintf(duty_fd,"%u",500000000/cur_note); |
|
|
|
dprintf(duty_fd,"%u",500000000/cur_note); |
|
|
|
dprintf(run_fd,"1"); |
|
|
|
dprintf(run_fd,"1"); |
|
|
|
|
|
|
|
#endif |
|
|
|
cur_note =0; |
|
|
|
cur_note =0; |
|
|
|
prev_time = cur_time; |
|
|
|
prev_time = cur_time; |
|
|
|
} |
|
|
|
} |
|
|
@ -189,7 +209,6 @@ bool ToneAlarm::set_note(){ |
|
|
|
cur_note = 0; |
|
|
|
cur_note = 0; |
|
|
|
return true; |
|
|
|
return true; |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
bool ToneAlarm::init_tune(){ |
|
|
|
bool ToneAlarm::init_tune(){ |
|
|
|