sound fine

This commit is contained in:
DashyFox 2024-10-03 02:37:05 +03:00
parent 0e845d9ebd
commit dd34d1bbb1
8 changed files with 326 additions and 158 deletions

View File

@ -14,6 +14,8 @@
#define SOUND_TIMER TIM4 #define SOUND_TIMER TIM4
#define SOUND_TIMER_RCC RCC_APB1ENR_TIM4EN #define SOUND_TIMER_RCC RCC_APB1ENR_TIM4EN
extern uint32_t bpm;
// Define the Note structure // Define the Note structure
typedef struct { typedef struct {
uint32_t frequency; // Frequency in Hz uint32_t frequency; // Frequency in Hz
@ -158,7 +160,13 @@ void sound_init(void);
void sound_set_bpm(uint32_t bpm); void sound_set_bpm(uint32_t bpm);
void sound_play_note(Note_t note, uint8_t channel); void sound_play_note(Note_t note, uint8_t channel);
void sound_play_melody(Note_t* melody, uint32_t size, uint8_t channel, uint32_t repeat_count); void sound_play_melody(Note_t* melody, uint32_t size, uint8_t channel, uint32_t repeat_count);
void sound_play_melody(Note_t* melody, uint32_t size, uint8_t channel, uint32_t repeat_count);
void sound_tick(void); void sound_tick(void);
uint16_t get_array_size(Note_t *array);
Note_t sound_create_note(MusicalNote_t note, NoteDuration_t duration, uint8_t duty_cycle); Note_t sound_create_note(MusicalNote_t note, NoteDuration_t duration, uint8_t duty_cycle);
#define CREATE_NOTE(note, dur, duty) \
((Note_t){ .frequency = note, .duration = dur, .duty_cycle = duty })
#endif /* INC_SOUND_H_ */ #endif /* INC_SOUND_H_ */

28
Core/Inc/SoundMelody.h Normal file
View File

@ -0,0 +1,28 @@
/*
* SoundMelody.h
*
* Created on: Oct 2, 2024
* Author: DashyFox
*/
#ifndef INC_SOUNDMELODY_H_
#define INC_SOUNDMELODY_H_
#include "Sound.h"
#define melody(melodyName) sound_play_melody(melodyName, sizeof(melodyName)/sizeof(Note_t), 3, 0)
extern Note_t melody_buttonClick[1];
extern Note_t melody_buttonClickHold[1];
extern Note_t melody_timerClick[1];
extern Note_t melody_start[12];
extern Note_t melody_NoBall[14];
extern Note_t melody_Error[3];
extern Note_t melody_Ball_1[3];
extern Note_t melody_Done[9];
extern Note_t melody_OK[3];
#endif /* INC_SOUNDMELODY_H_ */

View File

@ -9,6 +9,7 @@
#include "ShiftReg.h" #include "ShiftReg.h"
#include "RobotFunctions.h" #include "RobotFunctions.h"
#include "Indicator.h" #include "Indicator.h"
#include "SoundMelody.h"
#include "Print.h" #include "Print.h"
@ -135,6 +136,7 @@ void IR_Home_Process() {
case ShotMode: case ShotMode:
currentInfo.mode = DebugShot; currentInfo.mode = DebugShot;
currentInfo.state = RUN; currentInfo.state = RUN;
melody(melody_start);
shotApply(&currentInfo.shot); shotApply(&currentInfo.shot);
break; break;
default: default:

View File

@ -4,6 +4,7 @@
#include "ShiftReg.h" #include "ShiftReg.h"
#include "Print.h" #include "Print.h"
#include "Indicator.h" #include "Indicator.h"
#include "SoundMelody.h"
#define IR_Timeout 137 #define IR_Timeout 137
#define ResetInputProgerss_Timeout 2500 #define ResetInputProgerss_Timeout 2500
@ -62,13 +63,13 @@ void IR_CMD_Handler() {
dataHandled_flag = 0; dataHandled_flag = 0;
} }
if (inputInProgerss && (millis() - inputInProgerss_timer > ResetInputProgerss_Timeout)) { if (inputInProgerss && (millis() - inputInProgerss_timer > ResetInputProgerss_Timeout)) {
IR_CMD_Clear(); IR_CMD_Clear();
uint8_t blinkPeriod = 25; // uint8_t blinkPeriod = 25;
for (int i = 9; i <= 10; ++i) { // for (int i = 9; i <= 10; ++i) {
led_blink_num(i, blinkPeriod, 4); // led_blink_num(i, blinkPeriod, 4);
} // }
} }
// cmd handler // cmd handler
@ -81,6 +82,7 @@ void IR_CMD_Handler() {
dataHandled_flag = 1; dataHandled_flag = 1;
if (IR_Address == 0x01) { if (IR_Address == 0x01) {
onHoldRepeat = NullFunc; onHoldRepeat = NullFunc;
melody(melody_buttonClick);
InputHandler(); InputHandler();
inputInProgerss = 1; inputInProgerss = 1;
inputInProgerss_timer = millis(); inputInProgerss_timer = millis();
@ -88,13 +90,16 @@ void IR_CMD_Handler() {
lastRepeatTime = holdStartTime; // Инициализируем таймер повторного вызова lastRepeatTime = holdStartTime; // Инициализируем таймер повторного вызова
currentRepeatTime = InitialRepeatTime; // Сбрасываем интервал повторного вызова currentRepeatTime = InitialRepeatTime; // Сбрасываем интервал повторного вызова
uint8_t blinkPeriod = 75; // led
led_blink_num(19, blinkPeriod, 1); // uint8_t blinkPeriod = 75;
led_blink_num(18, blinkPeriod, 1); // led_blink_num(19, blinkPeriod, 1);
led_blink_num(17, blinkPeriod, 1); // led_blink_num(18, blinkPeriod, 1);
led_blink_num(2, blinkPeriod, 1); // led_blink_num(17, blinkPeriod, 1);
led_blink_num(1, blinkPeriod, 1); // led_blink_num(2, blinkPeriod, 1);
led_blink_num(0, blinkPeriod, 1); // led_blink_num(1, blinkPeriod, 1);
// led_blink_num(0, blinkPeriod, 1);
} }
memcpy(&old_data, &data, sizeof(IRData)); memcpy(&old_data, &data, sizeof(IRData));
} else { } else {
@ -102,10 +107,12 @@ void IR_CMD_Handler() {
if (millis() - holdStartTime > HoldTime) { // Если кнопка удерживается дольше HoldTime if (millis() - holdStartTime > HoldTime) { // Если кнопка удерживается дольше HoldTime
if (millis() - lastRepeatTime > currentRepeatTime) { // Если прошло достаточно времени для повторного вызова if (millis() - lastRepeatTime > currentRepeatTime) { // Если прошло достаточно времени для повторного вызова
lastRepeatTime = millis(); // Обновляем время последнего вызова lastRepeatTime = millis(); // Обновляем время последнего вызова
// uint8_t blinkPeriod = 10;
led_writeMirror(9, 1);
HAL_Delay(1); // led_writeMirror(9, 1);
led_writeMirror(9,0); // HAL_Delay(1);
// led_writeMirror(9,0);
melody(melody_buttonClickHold);
onHoldRepeat(); // Вызываем функцию при удержании onHoldRepeat(); // Вызываем функцию при удержании

View File

@ -12,7 +12,7 @@
#include "Print.h" #include "Print.h"
#include "SimpleTimer.h" #include "SimpleTimer.h"
#include "Indicator.h" #include "Indicator.h"
#include "Sound.h" #include "SoundMelody.h"
#define ballReact_value 10 // время реакции на вылет мяча #define ballReact_value 10 // время реакции на вылет мяча
@ -125,6 +125,8 @@ void RobotTick() {
currentInfo.mode = ShotMode; currentInfo.mode = ShotMode;
} }
robotStateStop(); robotStateStop();
melody(melody_NoBall);
led_clear(); led_clear();
for (int i = 7; i <= 12; ++i) { for (int i = 7; i <= 12; ++i) {
led_blink_num(i, 250, 0xFFFF - 1); led_blink_num(i, 250, 0xFFFF - 1);
@ -143,6 +145,7 @@ void RobotTick() {
if (elapsedTime > currentInfo.startDelay) { if (elapsedTime > currentInfo.startDelay) {
currentInfo.state = RUN; currentInfo.state = RUN;
// melody(melody_start);
shotApply(postDelayShot); shotApply(postDelayShot);
} else { } else {
@ -156,13 +159,16 @@ void RobotTick() {
if (ledProgress > 30) { if (ledProgress > 30) {
led_progressbar(9, 0, progress); led_progressbar(9, 0, progress);
led_progressbar(10, 19, progress); led_progressbar(10, 19, progress);
melody(melody_timerClick);
} else { } else {
led_progressbar(9, 0, 100); led_progressbar(9, 0, 100);
led_progressbar(10, 19, 100); led_progressbar(10, 19, 100);
melody(melody_start);
} }
print("delay: "); print("delay: ");
printNumber(progress); printNumber(progress);
print("\n"); print("\n");
} }
} }
} }
@ -177,9 +183,11 @@ uint8_t prepareShot(uint8_t number) {
currentInfo.mode = ShotMode; currentInfo.mode = ShotMode;
currentInfo.shot.shot = shot; currentInfo.shot.shot = shot;
currentInfo.shot.indexGlobal = number; currentInfo.shot.indexGlobal = number;
melody(melody_OK);
return 1; return 1;
} else { } else {
// TODO: sound_ERR(); ledFX_ERR(); // TODO: sound_ERR(); ledFX_ERR();
melody(melody_Error);
print("shot not exist\n\n"); print("shot not exist\n\n");
return 0; return 0;
} }
@ -193,9 +201,11 @@ uint8_t prepareProgramm(uint8_t number) {
currentInfo.mode = ProgramMode; currentInfo.mode = ProgramMode;
currentInfo.program.program = program; currentInfo.program.program = program;
currentInfo.program.indexGlobal = number; currentInfo.program.indexGlobal = number;
melody(melody_OK);
return 1; return 1;
} else { } else {
// TODO: sound_ERR(); ledFX_ERR(); // TODO: sound_ERR(); ledFX_ERR();
melody(melody_Error);
print("program not exist\n\n"); print("program not exist\n\n");
return 0; return 0;
} }
@ -210,9 +220,10 @@ uint8_t prepareMacro(uint8_t number) {
currentInfo.mode = MacroMode; currentInfo.mode = MacroMode;
currentInfo.macro.macro = macro; currentInfo.macro.macro = macro;
currentInfo.macro.indexGlobal = number; currentInfo.macro.indexGlobal = number;
melody(melody_OK);
return 1; return 1;
} else { } else {
melody(melody_Error);
print("Macro not exist "); print("Macro not exist ");
printNumber(number); printNumber(number);
print("\n"); print("\n");
@ -230,6 +241,8 @@ void BallEXT_Handler() {
return; return;
} }
melody(melody_Ball_1);
print("BallDetected "); print("BallDetected ");
uint16_t period = ballReact_timer - noBallTimer; uint16_t period = ballReact_timer - noBallTimer;
printNumber(period); printNumber(period);
@ -519,6 +532,11 @@ void stopShooting() {
if(currentInfo.mode == DebugShot){ if(currentInfo.mode == DebugShot){
currentInfo.mode = ShotMode; currentInfo.mode = ShotMode;
} }
if(currentInfo.state == RUN){
melody(melody_Done);
}
robotStateStop(); robotStateStop();
led_clear(); led_clear();

View File

@ -9,7 +9,7 @@
#include "stm32f103xb.h" #include "stm32f103xb.h"
#include "SimpleTimer.h" #include "SimpleTimer.h"
static uint32_t bpm = 120; // Default BPM uint32_t bpm = 120; // Default BPM
static uint32_t note_end_time_ch[4] = {0, 0, 0, 0}; // End times for each channel (1-4) static uint32_t note_end_time_ch[4] = {0, 0, 0, 0}; // End times for each channel (1-4)
static Melody_t melodies[4]; // Array of melodies for each channel static Melody_t melodies[4]; // Array of melodies for each channel
@ -19,32 +19,34 @@ static Melody_t melodies[4]; // Array of melodies for each channel
// Initialize the sound system // Initialize the sound system
void sound_init(void) { void sound_init(void) {
// Enable timer clock // Dont need, conflict with uart
RCC->APB1ENR |= SOUND_TIMER_RCC;
// Configure GPIO pins for timer output (assuming GPIOB pins for TIM4 CH3 and CH4) // // Enable timer clock
RCC->APB2ENR |= RCC_APB2ENR_IOPBEN; // RCC->APB1ENR |= SOUND_TIMER_RCC;
//
// Configure only channels 3 and 4 // // Configure GPIO pins for timer output (assuming GPIOB pins for TIM4 CH3 and CH4)
// Channel 3 // RCC->APB2ENR |= RCC_APB2ENR_IOPBEN;
GPIOB->CRH &= ~(0xF << (3 * 4)); // Clear configuration for PB10 (TIM4_CH3) //
GPIOB->CRH |= (0xB << (3 * 4)); // Set to alternate function push-pull // // Configure only channels 3 and 4
// // Channel 3
// Channel 4 // GPIOB->CRH &= ~(0xF << (3 * 4)); // Clear configuration for PB10 (TIM4_CH3)
GPIOB->CRH &= ~(0xF << (4 * 4)); // Clear configuration for PB11 (TIM4_CH4) // GPIOB->CRH |= (0xB << (3 * 4)); // Set to alternate function push-pull
GPIOB->CRH |= (0xB << (4 * 4)); // Set to alternate function push-pull //
// // Channel 4
// Initialize the timer for PWM output // GPIOB->CRH &= ~(0xF << (4 * 4)); // Clear configuration for PB11 (TIM4_CH4)
SOUND_TIMER->PSC = 0; // GPIOB->CRH |= (0xB << (4 * 4)); // Set to alternate function push-pull
SOUND_TIMER->ARR = 0xFFFF; //
// // Initialize the timer for PWM output
// Configure only channels 3 and 4 for PWM output // SOUND_TIMER->PSC = 0;
SOUND_TIMER->CCMR2 &= ~(TIM_CCMR2_OC3M | TIM_CCMR2_OC4M); // Clear channel 3 and 4 mode // SOUND_TIMER->ARR = 0xFFFF;
SOUND_TIMER->CCMR2 |= (6 << TIM_CCMR2_OC3M_Pos); // Set channel 3 to PWM mode 1 //
SOUND_TIMER->CCER |= (TIM_CCER_CC3E | TIM_CCER_CC4E); // Enable output for channels 3 and 4 // // Configure only channels 3 and 4 for PWM output
// SOUND_TIMER->CCMR2 &= ~(TIM_CCMR2_OC3M | TIM_CCMR2_OC4M); // Clear channel 3 and 4 mode
SOUND_TIMER->EGR = TIM_EGR_UG; // Update the timer // SOUND_TIMER->CCMR2 |= (6 << TIM_CCMR2_OC3M_Pos); // Set channel 3 to PWM mode 1
SOUND_TIMER->CR1 |= TIM_CR1_CEN; // Enable the timer // SOUND_TIMER->CCER |= (TIM_CCER_CC3E | TIM_CCER_CC4E); // Enable output for channels 3 and 4
//
// SOUND_TIMER->EGR = TIM_EGR_UG; // Update the timer
// SOUND_TIMER->CR1 |= TIM_CR1_CEN; // Enable the timer
} }
@ -62,10 +64,17 @@ void sound_play_note(Note_t note, uint8_t channel) {
uint32_t *ccer = &SOUND_TIMER->CCER; uint32_t *ccer = &SOUND_TIMER->CCER;
uint32_t enable_cc = TIM_CCER_CC1E << ((channel - 1) * 4); uint32_t enable_cc = TIM_CCER_CC1E << ((channel - 1) * 4);
uint32_t duration = (note.duration == T0) ? 0 : (60000 * 4 / (bpm * note.duration));
if (note.frequency == 0) { if (note.frequency == 0) {
*ccer &= ~enable_cc; *ccer &= ~enable_cc;
note_end_time_ch[channel - 1] = millis() + note.duration; note_end_time_ch[channel - 1] = millis() + duration;
} else { } else {
// Если текущая нота отличается от новой, отключите старую
if (*ccer & enable_cc) {
*ccer &= ~enable_cc; // Отключить старую ноту
}
uint32_t timer_clock = SystemCoreClock / 2; uint32_t timer_clock = SystemCoreClock / 2;
uint32_t prescaler = (timer_clock / (note.frequency * 65536)) + 1; uint32_t prescaler = (timer_clock / (note.frequency * 65536)) + 1;
uint32_t arr = (timer_clock / (prescaler * note.frequency)) - 1; uint32_t arr = (timer_clock / (prescaler * note.frequency)) - 1;
@ -82,22 +91,30 @@ void sound_play_note(Note_t note, uint8_t channel) {
SOUND_TIMER->EGR = TIM_EGR_UG; SOUND_TIMER->EGR = TIM_EGR_UG;
SOUND_TIMER->CR1 |= TIM_CR1_CEN; SOUND_TIMER->CR1 |= TIM_CR1_CEN;
note_end_time_ch[channel - 1] = (note.duration == 0) ? 0 : millis() + note.duration; note_end_time_ch[channel - 1] = (duration == 0) ? 0 : millis() + duration;
} }
} }
static void play_next_note(uint8_t channel);
// Play a melody on a specific channel with repeat count // Play a melody on a specific channel with repeat count
void sound_play_melody(Note_t* melody, uint32_t size, uint8_t channel, uint32_t repeat_count) { void sound_play_melody(Note_t* melody, uint32_t size, uint8_t channel, uint32_t repeat_count) {
if (channel < 1 || channel > 4 || melody == NULL || size == 0) return; if (channel < 1 || channel > 4 || melody == NULL || size == 0) return;
uint8_t ch_idx = channel - 1; uint8_t ch_idx = channel - 1;
// Если уже есть мелодия, которую нужно перебить
if (melodies[ch_idx].notes != NULL) {
// Остановите текущую мелодию
SOUND_TIMER->CCER &= ~(TIM_CCER_CC1E << (ch_idx * 4)); // Отключить выход
melodies[ch_idx].notes = NULL; // Удалить текущую мелодию
}
melodies[ch_idx].notes = melody; melodies[ch_idx].notes = melody;
melodies[ch_idx].size = size; melodies[ch_idx].size = size;
melodies[ch_idx].current_note = 0; melodies[ch_idx].current_note = 0;
melodies[ch_idx].repeat_count = repeat_count; melodies[ch_idx].repeat_count = repeat_count;
melodies[ch_idx].repeat_left = repeat_count; melodies[ch_idx].repeat_left = repeat_count;
play_next_note(channel);
sound_play_note(melody[0], channel); // Play the first note // sound_play_note(melody[0], channel); // Play the first note
} }
// Function to play the next note in the melody for a specific channel // Function to play the next note in the melody for a specific channel
@ -135,8 +152,9 @@ void sound_tick(void) {
} }
} }
// Create a note // Create a note
Note_t sound_create_note(MusicalNote_t note, NoteDuration_t duration, uint8_t duty_cycle) { Note_t sound_create_note(MusicalNote_t note, NoteDuration_t duration, uint8_t duty_cycle) {
uint32_t note_duration = (duration == T0) ? 0 : (60000 * 4 / (bpm * duration)); return (Note_t){ .frequency = note, .duration = duration, .duty_cycle = duty_cycle };
return (Note_t){ .frequency = note, .duration = note_duration, .duty_cycle = duty_cycle };
} }

View File

@ -33,7 +33,7 @@
#include "RobotFunctions.h" #include "RobotFunctions.h"
#include "ShiftReg.h" #include "ShiftReg.h"
#include "UART3_Handler.h" #include "UART3_Handler.h"
#include "Sound.h" #include "SoundMelody.h"
/* USER CODE END Includes */ /* USER CODE END Includes */
/* Private typedef -----------------------------------------------------------*/ /* Private typedef -----------------------------------------------------------*/
@ -209,112 +209,6 @@ int main(void)
} }
} }
sound_set_bpm(147);
Note_t melody[] = {
sound_create_note(C0, T16, 50),
sound_create_note(C0_sharp, T16, 50),
sound_create_note(D0, T16, 50),
sound_create_note(D0_sharp, T16, 50),
sound_create_note(E0, T16, 50),
sound_create_note(F0, T16, 50),
sound_create_note(F0_sharp, T16, 50),
sound_create_note(G0, T16, 50),
sound_create_note(G0_sharp, T16, 50),
sound_create_note(A0, T16, 50),
sound_create_note(A0_sharp, T16, 50),
sound_create_note(B0, T16, 50),
sound_create_note(C1, T16, 50),
sound_create_note(C1_sharp, T16, 50),
sound_create_note(D1, T16, 50),
sound_create_note(D1_sharp, T16, 50),
sound_create_note(E1, T16, 50),
sound_create_note(F1, T16, 50),
sound_create_note(F1_sharp, T16, 50),
sound_create_note(G1, T16, 50),
sound_create_note(G1_sharp, T16, 50),
sound_create_note(A1, T16, 50),
sound_create_note(A1_sharp, T16, 50),
sound_create_note(B1, T16, 50),
sound_create_note(C2, T16, 50),
sound_create_note(C2_sharp, T16, 50),
sound_create_note(D2, T16, 50),
sound_create_note(D2_sharp, T16, 50),
sound_create_note(E2, T16, 50),
sound_create_note(F2, T16, 50),
sound_create_note(F2_sharp, T16, 50),
sound_create_note(G2, T16, 50),
sound_create_note(G2_sharp, T16, 50),
sound_create_note(A2, T16, 50),
sound_create_note(A2_sharp, T16, 50),
sound_create_note(B2, T16, 50),
sound_create_note(C3, T16, 50),
sound_create_note(C3_sharp, T16, 50),
sound_create_note(D3, T16, 50),
sound_create_note(D3_sharp, T16, 50),
sound_create_note(E3, T16, 50),
sound_create_note(F3, T16, 50),
sound_create_note(F3_sharp, T16, 50),
sound_create_note(G3, T16, 50),
sound_create_note(G3_sharp, T16, 50),
sound_create_note(A3, T16, 50),
sound_create_note(A3_sharp, T16, 50),
sound_create_note(B3, T16, 50),
sound_create_note(C4, T16, 50),
sound_create_note(C4_sharp, T16, 50),
sound_create_note(D4, T16, 50),
sound_create_note(D4_sharp, T16, 50),
sound_create_note(E4, T16, 50),
sound_create_note(F4, T16, 50),
sound_create_note(F4_sharp, T16, 50),
sound_create_note(G4, T16, 50),
sound_create_note(G4_sharp, T16, 50),
sound_create_note(A4, T16, 50),
sound_create_note(A4_sharp, T16, 50),
sound_create_note(B4, T16, 50),
sound_create_note(C5, T16, 50),
sound_create_note(C5_sharp, T16, 50),
sound_create_note(D5, T16, 50),
sound_create_note(D5_sharp, T16, 50),
sound_create_note(E5, T16, 50),
sound_create_note(F5, T16, 50),
sound_create_note(F5_sharp, T16, 50),
sound_create_note(G5, T16, 50),
sound_create_note(G5_sharp, T16, 50),
sound_create_note(A5, T16, 50),
sound_create_note(A5_sharp, T16, 50),
sound_create_note(B5, T16, 50),
sound_create_note(C6, T16, 50),
sound_create_note(C6_sharp, T16, 50),
sound_create_note(D6, T16, 50),
sound_create_note(D6_sharp, T16, 50),
sound_create_note(E6, T16, 50),
sound_create_note(F6, T16, 50),
sound_create_note(F6_sharp, T16, 50),
sound_create_note(G6, T16, 50),
sound_create_note(G6_sharp, T16, 50),
sound_create_note(A6, T16, 50),
sound_create_note(A6_sharp, T16, 50),
sound_create_note(B6, T16, 50),
sound_create_note(C7, T16, 50),
sound_create_note(C7_sharp, T16, 50),
sound_create_note(D7, T16, 50),
sound_create_note(D7_sharp, T16, 50),
sound_create_note(E7, T16, 50),
sound_create_note(F7, T16, 50),
sound_create_note(F7_sharp, T16, 50),
sound_create_note(G7, T16, 50),
sound_create_note(G7_sharp, T16, 50),
sound_create_note(A7, T16, 50),
sound_create_note(A7_sharp, T16, 50),
sound_create_note(B7, T16, 50),
sound_create_note(C8, T16, 50),
sound_create_note(C8_sharp, T16, 50),
sound_create_note(D8, T16, 50)
};
sound_play_melody(melody, sizeof(melody)/sizeof(melody), 3, 1);
while (1) { while (1) {
IR_CMD_Handler(); IR_CMD_Handler();

193
Core/Src/soundMelody.c Normal file
View File

@ -0,0 +1,193 @@
/*
* soundMelody.c
*
* Created on: Oct 2, 2024
* Author: DashyFox
*/
#include "SoundMelody.h"
// Note_t melody_test[] = {
// sound_create_note(C0, T16, 50),
// sound_create_note(C0_sharp, T16, 50),
// sound_create_note(D0, T16, 50),
// sound_create_note(D0_sharp, T16, 50),
// sound_create_note(E0, T16, 50),
// sound_create_note(F0, T16, 50),
// sound_create_note(F0_sharp, T16, 50),
// sound_create_note(G0, T16, 50),
// sound_create_note(G0_sharp, T16, 50),
// sound_create_note(A0, T16, 50),
// sound_create_note(A0_sharp, T16, 50),
// sound_create_note(B0, T16, 50),
// sound_create_note(C1, T16, 50),
// sound_create_note(C1_sharp, T16, 50),
// sound_create_note(D1, T16, 50),
// sound_create_note(D1_sharp, T16, 50),
// sound_create_note(E1, T16, 50),
// sound_create_note(F1, T16, 50),
// sound_create_note(F1_sharp, T16, 50),
// sound_create_note(G1, T16, 50),
// sound_create_note(G1_sharp, T16, 50),
// sound_create_note(A1, T16, 50),
// sound_create_note(A1_sharp, T16, 50),
// sound_create_note(B1, T16, 50),
// sound_create_note(C2, T16, 50),
// sound_create_note(C2_sharp, T16, 50),
// sound_create_note(D2, T16, 50),
// sound_create_note(D2_sharp, T16, 50),
// sound_create_note(E2, T16, 50),
// sound_create_note(F2, T16, 50),
// sound_create_note(F2_sharp, T16, 50),
// sound_create_note(G2, T16, 50),
// sound_create_note(G2_sharp, T16, 50),
// sound_create_note(A2, T16, 50),
// sound_create_note(A2_sharp, T16, 50),
// sound_create_note(B2, T16, 50),
// sound_create_note(C3, T16, 50),
// sound_create_note(C3_sharp, T16, 50),
// sound_create_note(D3, T16, 50),
// sound_create_note(D3_sharp, T16, 50),
// sound_create_note(E3, T16, 50),
// sound_create_note(F3, T16, 50),
// sound_create_note(F3_sharp, T16, 50),
// sound_create_note(G3, T16, 50),
// sound_create_note(G3_sharp, T16, 50),
// sound_create_note(A3, T16, 50),
// sound_create_note(A3_sharp, T16, 50),
// sound_create_note(B3, T16, 50),
// sound_create_note(C4, T16, 50),
// sound_create_note(C4_sharp, T16, 50),
// sound_create_note(D4, T16, 50),
// sound_create_note(D4_sharp, T16, 50),
// sound_create_note(E4, T16, 50),
// sound_create_note(F4, T16, 50),
// sound_create_note(F4_sharp, T16, 50),
// sound_create_note(G4, T16, 50),
// sound_create_note(G4_sharp, T16, 50),
// sound_create_note(A4, T16, 50),
// sound_create_note(A4_sharp, T16, 50),
// sound_create_note(B4, T16, 50),
// sound_create_note(C5, T16, 50),
// sound_create_note(C5_sharp, T16, 50),
// sound_create_note(D5, T16, 50),
// sound_create_note(D5_sharp, T16, 50),
// sound_create_note(E5, T16, 50),
// sound_create_note(F5, T16, 50),
// sound_create_note(F5_sharp, T16, 50),
// sound_create_note(G5, T16, 50),
// sound_create_note(G5_sharp, T16, 50),
// sound_create_note(A5, T16, 50),
// sound_create_note(A5_sharp, T16, 50),
// sound_create_note(B5, T16, 50),
// sound_create_note(C6, T16, 50),
// sound_create_note(C6_sharp, T16, 50),
// sound_create_note(D6, T16, 50),
// sound_create_note(D6_sharp, T16, 50),
// sound_create_note(E6, T16, 50),
// sound_create_note(F6, T16, 50),
// sound_create_note(F6_sharp, T16, 50),
// sound_create_note(G6, T16, 50),
// sound_create_note(G6_sharp, T16, 50),
// sound_create_note(A6, T16, 50),
// sound_create_note(A6_sharp, T16, 50),
// sound_create_note(B6, T16, 50),
// sound_create_note(C7, T16, 50),
// sound_create_note(C7_sharp, T16, 50),
// sound_create_note(D7, T16, 50),
// sound_create_note(D7_sharp, T16, 50),
// sound_create_note(E7, T16, 50),
// sound_create_note(F7, T16, 50),
// sound_create_note(F7_sharp, T16, 50),
// sound_create_note(G7, T16, 50),
// sound_create_note(G7_sharp, T16, 50),
// sound_create_note(A7, T16, 50),
// sound_create_note(A7_sharp, T16, 50),
// sound_create_note(B7, T16, 50),
// sound_create_note(C8, T16, 50),
// sound_create_note(C8_sharp, T16, 50),
// sound_create_note(D8, T16, 50)
// };
Note_t melody_buttonClick[] = {
CREATE_NOTE(D6_sharp, 16, 50)
};
Note_t melody_buttonClickHold[] = {
CREATE_NOTE(A7_sharp, 64, 50)
};
Note_t melody_timerClick[] = {
CREATE_NOTE(E4, 64, 50)
};
Note_t melody_start[] = {
CREATE_NOTE(C4, 64, 50),
CREATE_NOTE(0, 64, 50),
CREATE_NOTE(E4, 64, 50),
CREATE_NOTE(0, 64, 50),
CREATE_NOTE(G4, 64, 50),
CREATE_NOTE(0, 32, 50),
CREATE_NOTE(E4, 64, 50),
CREATE_NOTE(0, 64, 50),
CREATE_NOTE(G4, 64, 50),
CREATE_NOTE(0, 64, 50),
CREATE_NOTE(C5, 64, 50),
CREATE_NOTE(0, 64, 50),
};
Note_t melody_NoBall[] = {
CREATE_NOTE(0, 4+1, 50),
CREATE_NOTE(G2, 32, 50),
CREATE_NOTE(A2, 32, 50),
CREATE_NOTE(B2, 32, 50),
CREATE_NOTE(C3, 8, 50),
CREATE_NOTE(B2, 8, 50),
CREATE_NOTE(A2_sharp, 8, 50),
CREATE_NOTE(A2, 16+4, 50),
CREATE_NOTE(G2_sharp, 32, 50),
CREATE_NOTE(A2, 4+3, 50),
CREATE_NOTE(0, 8, 50),
CREATE_NOTE(A1, 32, 50),
CREATE_NOTE(0, 32, 50),
CREATE_NOTE(A1, 32, 50)
};
Note_t melody_Error[] = {
CREATE_NOTE(A1, 32, 50),
CREATE_NOTE(0, 32, 50),
CREATE_NOTE(A1, 32, 50),
};
Note_t melody_Ball_1[] = {
CREATE_NOTE(C5, 16, 50),
CREATE_NOTE(G5, 16, 50),
};
Note_t melody_Done[] = {
CREATE_NOTE(C4, 16, 50),
CREATE_NOTE(D4, 16, 50),
CREATE_NOTE(E4, 16, 50),
CREATE_NOTE(G4, 16, 50),
CREATE_NOTE(C5, 16, 50),
CREATE_NOTE(0, 16, 50),
CREATE_NOTE(G4, 16, 50),
CREATE_NOTE(C5, 16, 50),
};
Note_t melody_OK[] = {
CREATE_NOTE(G6_sharp, 64, 50),
CREATE_NOTE(0, 64, 50),
CREATE_NOTE(C7_sharp, 64, 50),
};