Compare commits
1 Commits
configmode
...
sound_tuni
Author | SHA1 | Date | |
---|---|---|---|
68816a06fa |
Binary file not shown.
Before Width: | Height: | Size: 603 KiB |
Binary file not shown.
Before Width: | Height: | Size: 262 KiB |
Binary file not shown.
BIN
docs/sound-driver-2.jpg
Normal file
BIN
docs/sound-driver-2.jpg
Normal file
Binary file not shown.
After Width: | Height: | Size: 48 KiB |
Binary file not shown.
Before Width: | Height: | Size: 183 KiB |
@ -7,11 +7,11 @@ MCU=msp430g2553
|
|||||||
CFLAGS=-Wall -mmcu=$(MCU) -std=gnu99 -I $(TOOLCHAIN_PREFIX)/include -O1 -g0
|
CFLAGS=-Wall -mmcu=$(MCU) -std=gnu99 -I $(TOOLCHAIN_PREFIX)/include -O1 -g0
|
||||||
|
|
||||||
# for debugging
|
# for debugging
|
||||||
#CFLAGS+= -g3 -ggdb -gdwarf-2
|
CFLAGS+= -g3 -ggdb -gdwarf-2
|
||||||
|
|
||||||
LDFLAGS=-mmcu=$(MCU) -L $(TOOLCHAIN_PREFIX)/include
|
LDFLAGS=-mmcu=$(MCU) -L $(TOOLCHAIN_PREFIX)/include
|
||||||
|
|
||||||
$(ARTIFACT).elf: main.o spi.o scheduler.o canvas.o shapes.o game.o buttons.o myrand.o display.o sound.o eeprom.o config.o
|
$(ARTIFACT).elf: main.o spi.o scheduler.o canvas.o shapes.o game.o buttons.o myrand.o display.o sound.o eeprom.o
|
||||||
$(CC) -o $@ $(LDFLAGS) $^
|
$(CC) -o $@ $(LDFLAGS) $^
|
||||||
$(OBJDUMP) -D $(ARTIFACT).elf > $(ARTIFACT).txt
|
$(OBJDUMP) -D $(ARTIFACT).elf > $(ARTIFACT).txt
|
||||||
|
|
||||||
|
@ -20,10 +20,6 @@ static uint8_t buttonsMoveLeftPressed() {
|
|||||||
return res;
|
return res;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool buttonsConfig1Pressed() {
|
|
||||||
return buttonsMoveLeftPressed();
|
|
||||||
}
|
|
||||||
|
|
||||||
static uint8_t buttonsMoveRightPressed() {
|
static uint8_t buttonsMoveRightPressed() {
|
||||||
static uint8_t last = 0;
|
static uint8_t last = 0;
|
||||||
uint8_t current = (P2IN & BIT0);
|
uint8_t current = (P2IN & BIT0);
|
||||||
@ -32,10 +28,6 @@ static uint8_t buttonsMoveRightPressed() {
|
|||||||
return res;
|
return res;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool buttonsConfig4Pressed() {
|
|
||||||
return buttonsMoveRightPressed();
|
|
||||||
}
|
|
||||||
|
|
||||||
static uint8_t buttonsRotateLeftPressed() {
|
static uint8_t buttonsRotateLeftPressed() {
|
||||||
static uint8_t last = 0;
|
static uint8_t last = 0;
|
||||||
uint8_t current = (P2IN & BIT3);
|
uint8_t current = (P2IN & BIT3);
|
||||||
@ -44,10 +36,6 @@ static uint8_t buttonsRotateLeftPressed() {
|
|||||||
return res;
|
return res;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool buttonsConfig2Pressed() {
|
|
||||||
return buttonsRotateLeftPressed();
|
|
||||||
}
|
|
||||||
|
|
||||||
static uint8_t buttonsRotateRightPressed() {
|
static uint8_t buttonsRotateRightPressed() {
|
||||||
static uint8_t last = 0;
|
static uint8_t last = 0;
|
||||||
uint8_t current = (P2IN & BIT1);
|
uint8_t current = (P2IN & BIT1);
|
||||||
@ -56,20 +44,10 @@ static uint8_t buttonsRotateRightPressed() {
|
|||||||
return res;
|
return res;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool buttonsConfig3Pressed() {
|
|
||||||
return buttonsRotateRightPressed();
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
static uint8_t buttonsMoveDownPressed() {
|
static uint8_t buttonsMoveDownPressed() {
|
||||||
return P2IN & BIT2;
|
return P2IN & BIT2;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool isConfigMode() {
|
|
||||||
return (P2IN & BIT2);
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
void buttonsExec(void *handle) {
|
void buttonsExec(void *handle) {
|
||||||
static uint32_t unmuteTimestamp;
|
static uint32_t unmuteTimestamp;
|
||||||
uint32_t currentTimestamp = getSeconds();
|
uint32_t currentTimestamp = getSeconds();
|
||||||
@ -126,9 +104,7 @@ void buttonsExec(void *handle) {
|
|||||||
|
|
||||||
void buttonsInit() {
|
void buttonsInit() {
|
||||||
P2DIR &= ~(BIT0|BIT1|BIT2|BIT3|BIT4);
|
P2DIR &= ~(BIT0|BIT1|BIT2|BIT3|BIT4);
|
||||||
}
|
|
||||||
|
|
||||||
void buttonsStart() {
|
|
||||||
schAdd(buttonsExec, NULL, 0, 25);
|
schAdd(buttonsExec, NULL, 0, 25);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -4,13 +4,7 @@
|
|||||||
#include <stdbool.h>
|
#include <stdbool.h>
|
||||||
|
|
||||||
void buttonsInit();
|
void buttonsInit();
|
||||||
void buttonsStart();
|
|
||||||
bool isGameActive();
|
bool isGameActive();
|
||||||
bool isConfigMode();
|
|
||||||
bool buttonsConfig1Pressed();
|
|
||||||
bool buttonsConfig2Pressed();
|
|
||||||
bool buttonsConfig3Pressed();
|
|
||||||
bool buttonsConfig4Pressed();
|
|
||||||
|
|
||||||
|
|
||||||
#endif // _BUTTONS_H_
|
#endif // _BUTTONS_H_
|
||||||
|
@ -5,8 +5,6 @@
|
|||||||
|
|
||||||
#include "canvas.h"
|
#include "canvas.h"
|
||||||
#include "spi.h"
|
#include "spi.h"
|
||||||
#include "eeprom.h"
|
|
||||||
#include "../rgb-driver/colors.h"
|
|
||||||
|
|
||||||
|
|
||||||
static uint8_t canvasStorage[CANVAS_WIDTH * CANVAS_HEIGHT];
|
static uint8_t canvasStorage[CANVAS_WIDTH * CANVAS_HEIGHT];
|
||||||
@ -24,8 +22,6 @@ const canvas_t miniCanvas = {
|
|||||||
};
|
};
|
||||||
|
|
||||||
void canvasShow() {
|
void canvasShow() {
|
||||||
uint8_t brightness_offset = _brightness_offset * eepromReadBrightness();
|
|
||||||
|
|
||||||
// wait for signal waiting for data
|
// wait for signal waiting for data
|
||||||
while (!(P1IN & BIT3));
|
while (!(P1IN & BIT3));
|
||||||
|
|
||||||
@ -35,14 +31,14 @@ void canvasShow() {
|
|||||||
if ((*((canvas.canvas)+i) & 0x80) != 0) {
|
if ((*((canvas.canvas)+i) & 0x80) != 0) {
|
||||||
*((canvas.canvas)+i) &= ~0x80;
|
*((canvas.canvas)+i) &= ~0x80;
|
||||||
spiSendOctet(i);
|
spiSendOctet(i);
|
||||||
spiSendOctet((*((canvas.canvas)+i) == 0) ? 0 : (*((canvas.canvas)+i) + brightness_offset));
|
spiSendOctet(*((canvas.canvas)+i));
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
for (uint8_t i = 0; i < (MINI_CANVAS_WIDTH*MINI_CANVAS_HEIGHT); i++) {
|
for (uint8_t i = 0; i < (MINI_CANVAS_WIDTH*MINI_CANVAS_HEIGHT); i++) {
|
||||||
if ((*((miniCanvas.canvas)+i) & 0x80) != 0) {
|
if ((*((miniCanvas.canvas)+i) & 0x80) != 0) {
|
||||||
*((miniCanvas.canvas)+i) &= ~0x80;
|
*((miniCanvas.canvas)+i) &= ~0x80;
|
||||||
spiSendOctet(i + (CANVAS_HEIGHT*CANVAS_WIDTH));
|
spiSendOctet(i + (CANVAS_HEIGHT*CANVAS_WIDTH));
|
||||||
spiSendOctet((*((miniCanvas.canvas)+i) == 0) ? 0 : (*((miniCanvas.canvas)+i) + brightness_offset));
|
spiSendOctet(*((miniCanvas.canvas)+i));
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
spiSendOctet(0xfe);
|
spiSendOctet(0xfe);
|
||||||
|
@ -1,91 +0,0 @@
|
|||||||
#include <stddef.h>
|
|
||||||
#include "config.h"
|
|
||||||
#include "canvas.h"
|
|
||||||
#include "../rgb-driver/colors.h"
|
|
||||||
#include "scheduler.h"
|
|
||||||
#include "buttons.h"
|
|
||||||
#include "eeprom.h"
|
|
||||||
#include "display.h"
|
|
||||||
#include "shapes.h"
|
|
||||||
|
|
||||||
|
|
||||||
static bool configChanged = false;
|
|
||||||
|
|
||||||
static void configHandleFlash() {
|
|
||||||
if (buttonsConfig2Pressed()) {
|
|
||||||
configChanged = true;
|
|
||||||
uint8_t color = eepromReadFlashColor() + 1;
|
|
||||||
if (color > _color_end) {
|
|
||||||
color = 0;
|
|
||||||
}
|
|
||||||
canvasFillRow(CANVAS_HEIGHT-1, color);
|
|
||||||
displaySetValue(color);
|
|
||||||
eepromSetFlashColor(color);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
static void configHandleResetHighScore() {
|
|
||||||
displaySetValue(eepromReadHighScore());
|
|
||||||
|
|
||||||
if (buttonsConfig2Pressed()) {
|
|
||||||
configChanged = true;
|
|
||||||
eepromSetHighScore(0);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
static void configHandleBrightness() {
|
|
||||||
displaySetValue(eepromReadBrightness());
|
|
||||||
|
|
||||||
if (buttonsConfig2Pressed()) {
|
|
||||||
configChanged = true;
|
|
||||||
uint8_t brightness = eepromReadBrightness() + 1;
|
|
||||||
if (brightness > _brightness_shifts) {
|
|
||||||
brightness = 0;
|
|
||||||
}
|
|
||||||
eepromSetBrightness(brightness);
|
|
||||||
|
|
||||||
stoneDrawConfigPattern();
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
void (*configHandler[])(void) = { configHandleFlash, configHandleResetHighScore, configHandleBrightness };
|
|
||||||
|
|
||||||
|
|
||||||
void configExec(void *handle) {
|
|
||||||
static uint8_t configState = 0;
|
|
||||||
static uint8_t lastConfigState = 255;
|
|
||||||
|
|
||||||
if (configState != lastConfigState) {
|
|
||||||
lastConfigState = configState;
|
|
||||||
|
|
||||||
miniCanvasClear();
|
|
||||||
canvasClear();
|
|
||||||
miniCanvasSetPixel(configState, 0, _red);
|
|
||||||
}
|
|
||||||
|
|
||||||
if (buttonsConfig1Pressed()) {
|
|
||||||
configState += 1;
|
|
||||||
if (configState >= sizeof(configHandler) / sizeof(configHandler[0])) {
|
|
||||||
configState = 0;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
configHandler[configState]();
|
|
||||||
|
|
||||||
if (configChanged) {
|
|
||||||
miniCanvasSetPixel(0, 2, _red);
|
|
||||||
if (buttonsConfig4Pressed()) {
|
|
||||||
eepromCommit();
|
|
||||||
configChanged = false;
|
|
||||||
}
|
|
||||||
} else {
|
|
||||||
miniCanvasSetPixel(0, 2, _green);
|
|
||||||
}
|
|
||||||
|
|
||||||
canvasShow();
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
void configInit() {
|
|
||||||
schAdd(configExec, NULL, 0, 25);
|
|
||||||
}
|
|
@ -1,8 +0,0 @@
|
|||||||
#ifndef _CONFIG_H_
|
|
||||||
#define _CONFIG_H_
|
|
||||||
|
|
||||||
|
|
||||||
void configInit();
|
|
||||||
|
|
||||||
|
|
||||||
#endif // _CONFIG_H_
|
|
@ -3,7 +3,7 @@
|
|||||||
#include "spi.h"
|
#include "spi.h"
|
||||||
|
|
||||||
|
|
||||||
#define MAGIC 0xb000
|
#define MAGIC 0xaffe
|
||||||
#define HIGHSCORE_ADDR 0x00
|
#define HIGHSCORE_ADDR 0x00
|
||||||
#define DUMMY 0x00
|
#define DUMMY 0x00
|
||||||
#define CMD_READ 0b00000011
|
#define CMD_READ 0b00000011
|
||||||
@ -12,16 +12,12 @@
|
|||||||
#define CMD_WREN 0b00000110
|
#define CMD_WREN 0b00000110
|
||||||
|
|
||||||
|
|
||||||
typedef struct {
|
|
||||||
uint16_t magic;
|
|
||||||
uint16_t highScore;
|
|
||||||
uint8_t flashColor;
|
|
||||||
uint8_t brightness;
|
|
||||||
} t_configBlock;
|
|
||||||
|
|
||||||
typedef union {
|
typedef union {
|
||||||
t_configBlock v;
|
uint8_t buffer[4];
|
||||||
uint8_t buffer[sizeof(t_configBlock)];
|
struct {
|
||||||
|
uint16_t magic;
|
||||||
|
uint16_t highScore;
|
||||||
|
} v;
|
||||||
} eepromBuf_t;
|
} eepromBuf_t;
|
||||||
|
|
||||||
eepromBuf_t buf;
|
eepromBuf_t buf;
|
||||||
@ -34,9 +30,10 @@ static void writeBuf() {
|
|||||||
spiSendBegin(e_SPI_EEPROM);
|
spiSendBegin(e_SPI_EEPROM);
|
||||||
spiSendOctet(CMD_WRITE);
|
spiSendOctet(CMD_WRITE);
|
||||||
spiSendOctet(HIGHSCORE_ADDR);
|
spiSendOctet(HIGHSCORE_ADDR);
|
||||||
for (uint8_t i = 0; i < sizeof(t_configBlock); i++) {
|
spiSendOctet(buf.buffer[0]);
|
||||||
spiSendOctet(buf.buffer[i]);
|
spiSendOctet(buf.buffer[1]);
|
||||||
}
|
spiSendOctet(buf.buffer[2]);
|
||||||
|
spiSendOctet(buf.buffer[3]);
|
||||||
spiSendEnd(e_SPI_EEPROM);
|
spiSendEnd(e_SPI_EEPROM);
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -46,10 +43,14 @@ static void readBuf() {
|
|||||||
spiReceiveOctet();
|
spiReceiveOctet();
|
||||||
spiSendOctet(HIGHSCORE_ADDR);
|
spiSendOctet(HIGHSCORE_ADDR);
|
||||||
spiReceiveOctet();
|
spiReceiveOctet();
|
||||||
for (uint8_t i = 0; i < sizeof(t_configBlock); i++) {
|
spiSendOctet(DUMMY);
|
||||||
spiSendOctet(DUMMY);
|
buf.buffer[0] = spiReceiveOctet();
|
||||||
buf.buffer[i] = spiReceiveOctet();
|
spiSendOctet(DUMMY);
|
||||||
}
|
buf.buffer[1] = spiReceiveOctet();
|
||||||
|
spiSendOctet(DUMMY);
|
||||||
|
buf.buffer[2] = spiReceiveOctet();
|
||||||
|
spiSendOctet(DUMMY);
|
||||||
|
buf.buffer[3] = spiReceiveOctet();
|
||||||
spiSendEnd(e_SPI_EEPROM);
|
spiSendEnd(e_SPI_EEPROM);
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -59,38 +60,16 @@ void eepromInit() {
|
|||||||
if (buf.v.magic != MAGIC) {
|
if (buf.v.magic != MAGIC) {
|
||||||
buf.v.magic = MAGIC;
|
buf.v.magic = MAGIC;
|
||||||
buf.v.highScore = 0;
|
buf.v.highScore = 0;
|
||||||
buf.v.flashColor = 0;
|
|
||||||
buf.v.brightness = 0;
|
|
||||||
writeBuf();
|
writeBuf();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void eepromCommit() {
|
|
||||||
writeBuf();
|
|
||||||
}
|
|
||||||
|
|
||||||
uint16_t eepromReadHighScore() {
|
uint16_t eepromReadHighScore() {
|
||||||
return buf.v.highScore;
|
return buf.v.highScore;
|
||||||
}
|
}
|
||||||
|
|
||||||
void eepromSetHighScore(uint16_t v) {
|
void eepromWriteHighScore(uint16_t v) {
|
||||||
buf.v.highScore = v;
|
buf.v.highScore = v;
|
||||||
writeBuf();
|
writeBuf();
|
||||||
}
|
}
|
||||||
|
|
||||||
uint8_t eepromReadFlashColor() {
|
|
||||||
return buf.v.flashColor;
|
|
||||||
}
|
|
||||||
|
|
||||||
void eepromSetFlashColor(uint8_t v) {
|
|
||||||
buf.v.flashColor = v;
|
|
||||||
}
|
|
||||||
|
|
||||||
uint8_t eepromReadBrightness() {
|
|
||||||
return buf.v.brightness;
|
|
||||||
}
|
|
||||||
|
|
||||||
void eepromSetBrightness(uint8_t v) {
|
|
||||||
buf.v.brightness = v;
|
|
||||||
}
|
|
||||||
|
|
||||||
|
@ -6,12 +6,7 @@
|
|||||||
|
|
||||||
void eepromInit();
|
void eepromInit();
|
||||||
uint16_t eepromReadHighScore();
|
uint16_t eepromReadHighScore();
|
||||||
void eepromSetHighScore(uint16_t v);
|
void eepromWriteHighScore(uint16_t v);
|
||||||
uint8_t eepromReadFlashColor();
|
|
||||||
void eepromSetFlashColor(uint8_t v);
|
|
||||||
uint8_t eepromReadBrightness();
|
|
||||||
void eepromSetBrightness(uint8_t v);
|
|
||||||
void eepromCommit();
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
121
game-ctrl/game.c
121
game-ctrl/game.c
@ -1,5 +1,3 @@
|
|||||||
// #define STATE_DEBUGGING
|
|
||||||
|
|
||||||
#include "stddef.h"
|
#include "stddef.h"
|
||||||
#include "stdint.h"
|
#include "stdint.h"
|
||||||
|
|
||||||
@ -14,36 +12,35 @@
|
|||||||
#include "buttons.h"
|
#include "buttons.h"
|
||||||
|
|
||||||
|
|
||||||
#define GAME_CYCLE_TIME 10
|
#define GAME_CYCLE_TIME 50
|
||||||
#define GAMEOVER_DELAY 10
|
#define GAMEOVER_DELAY 10
|
||||||
#define MAX_LEVEL 100
|
#define MAX_LEVEL 20
|
||||||
|
|
||||||
|
|
||||||
static uint16_t delayFactor(uint16_t level) {
|
static uint8_t delayFactor(uint8_t level) {
|
||||||
return MAX_LEVEL + 1 - level;
|
return MAX_LEVEL + 1 - level;
|
||||||
}
|
}
|
||||||
|
|
||||||
typedef enum {
|
typedef enum {
|
||||||
e_Start, e_NewStone, e_Down, e_DownDelay,
|
e_Phase_Game, e_Phase_GameOver
|
||||||
e_ClearRowInit, e_ClearRowNext, e_ClearRowCheck, e_ClearRowFlash, e_ClearRowFlashDelay, e_ClearRowWipe,
|
} phase_t;
|
||||||
|
|
||||||
|
typedef enum {
|
||||||
|
e_Start, e_NewStone, e_Down, e_DownDelay, e_ClearRows,
|
||||||
e_GameOver, e_GameOverFill, e_GameOverWipe, e_GameOverDelay
|
e_GameOver, e_GameOverFill, e_GameOverWipe, e_GameOverDelay
|
||||||
} state_t;
|
} state_t;
|
||||||
|
|
||||||
void gameExec(void *handle) {
|
void gameExec(void *handle) {
|
||||||
|
static phase_t phase;
|
||||||
static state_t state = e_Start;
|
static state_t state = e_Start;
|
||||||
static uint8_t gameOverDelay;
|
static uint8_t gameOverDelay;
|
||||||
static uint8_t rowIndex;
|
static uint8_t rowIndex;
|
||||||
static uint16_t proceedDelay;
|
static uint8_t proceedDelay;
|
||||||
static uint16_t level;
|
static uint8_t level;
|
||||||
static uint16_t filledLines;
|
static uint16_t filledLines;
|
||||||
static uint16_t score;
|
static uint16_t score;
|
||||||
static bool newHighScoreAchieved;
|
static bool newHighScoreAchieved;
|
||||||
|
|
||||||
static uint8_t clearCheckCnt;
|
|
||||||
|
|
||||||
#ifdef STATE_DEBUGGING
|
|
||||||
displaySetValue(state);
|
|
||||||
#endif
|
|
||||||
// --- engine begin -------------------------------------------------------
|
// --- engine begin -------------------------------------------------------
|
||||||
switch (state) {
|
switch (state) {
|
||||||
// --- phase: game --------------------------------------------------------
|
// --- phase: game --------------------------------------------------------
|
||||||
@ -54,6 +51,7 @@ void gameExec(void *handle) {
|
|||||||
filledLines = 0;
|
filledLines = 0;
|
||||||
score = 0;
|
score = 0;
|
||||||
newHighScoreAchieved = false;
|
newHighScoreAchieved = false;
|
||||||
|
phase = e_Phase_Game;
|
||||||
state = e_NewStone;
|
state = e_NewStone;
|
||||||
break;
|
break;
|
||||||
|
|
||||||
@ -70,78 +68,30 @@ void gameExec(void *handle) {
|
|||||||
case e_DownDelay:
|
case e_DownDelay:
|
||||||
proceedDelay--;
|
proceedDelay--;
|
||||||
if (proceedDelay == 0) {
|
if (proceedDelay == 0) {
|
||||||
state = e_Down;
|
rowIndex = 0;
|
||||||
|
state = e_ClearRows;
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
case e_ClearRows:
|
||||||
|
state = e_Down;
|
||||||
|
break;
|
||||||
|
|
||||||
case e_Down:
|
case e_Down:
|
||||||
if (! stoneMoveDown()) {
|
if (! stoneMoveDown()) {
|
||||||
soundCtrl(SOUND_LOCK);
|
soundCtrl(SOUND_LOCK);
|
||||||
stoneLock();
|
state = e_NewStone;
|
||||||
state = e_ClearRowInit;
|
|
||||||
} else {
|
} else {
|
||||||
proceedDelay = delayFactor(level);
|
proceedDelay = delayFactor(level);
|
||||||
state = e_DownDelay;
|
state = e_DownDelay;
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
|
||||||
// --- phase: clear rows --------------------------------------------------
|
|
||||||
case e_ClearRowInit:
|
|
||||||
clearCheckCnt = 0;
|
|
||||||
state = e_ClearRowCheck;
|
|
||||||
break;
|
|
||||||
|
|
||||||
case e_ClearRowNext:
|
|
||||||
if (clearCheckCnt >= CANVAS_HEIGHT) {
|
|
||||||
state = e_NewStone;
|
|
||||||
} else {
|
|
||||||
clearCheckCnt += 1;
|
|
||||||
state = e_ClearRowCheck;
|
|
||||||
}
|
|
||||||
break;
|
|
||||||
|
|
||||||
case e_ClearRowCheck:
|
|
||||||
if (canvasIsRowFilled(clearCheckCnt)) {
|
|
||||||
score += level;
|
|
||||||
if (score > eepromReadHighScore()) {
|
|
||||||
newHighScoreAchieved = true;
|
|
||||||
eepromSetHighScore(score);
|
|
||||||
eepromCommit();
|
|
||||||
}
|
|
||||||
state = e_ClearRowFlash;
|
|
||||||
} else {
|
|
||||||
state = e_ClearRowNext;
|
|
||||||
}
|
|
||||||
break;
|
|
||||||
|
|
||||||
case e_ClearRowFlash:
|
|
||||||
canvasFillRow(clearCheckCnt, eepromReadFlashColor());
|
|
||||||
state = e_ClearRowFlashDelay;
|
|
||||||
break;
|
|
||||||
|
|
||||||
case e_ClearRowFlashDelay:
|
|
||||||
state = e_ClearRowWipe;
|
|
||||||
break;
|
|
||||||
|
|
||||||
case e_ClearRowWipe:
|
|
||||||
canvasWipeRow(clearCheckCnt);
|
|
||||||
filledLines += 1;
|
|
||||||
|
|
||||||
if ((filledLines > 0) && ((filledLines % 10) == 0)) {
|
|
||||||
if (level < MAX_LEVEL) {
|
|
||||||
level += 1;
|
|
||||||
}
|
|
||||||
soundCtrl(SOUND_FANFARE);
|
|
||||||
} else {
|
|
||||||
soundCtrl(SOUND_PLING);
|
|
||||||
}
|
|
||||||
state = e_ClearRowNext;
|
|
||||||
break;
|
|
||||||
|
|
||||||
// --- phase: game over ---------------------------------------------------
|
// --- phase: game over ---------------------------------------------------
|
||||||
case e_GameOver:
|
case e_GameOver:
|
||||||
soundCtrl(SOUND_GAMEOVER);
|
soundCtrl(SOUND_GAMEOVER);
|
||||||
rowIndex = CANVAS_HEIGHT;
|
rowIndex = CANVAS_HEIGHT;
|
||||||
|
phase = e_Phase_GameOver;
|
||||||
state = e_GameOverFill;
|
state = e_GameOverFill;
|
||||||
break;
|
break;
|
||||||
|
|
||||||
@ -171,15 +121,42 @@ void gameExec(void *handle) {
|
|||||||
}
|
}
|
||||||
// --- engine end ---------------------------------------------------------
|
// --- engine end ---------------------------------------------------------
|
||||||
|
|
||||||
|
bool wipedLines = false;
|
||||||
canvasShow();
|
canvasShow();
|
||||||
|
if (phase == e_Phase_Game) {
|
||||||
|
for (uint8_t r = 0; r < CANVAS_HEIGHT; r++) {
|
||||||
|
if (canvasIsRowFilled(r)) {
|
||||||
|
score += level;
|
||||||
|
if (score > eepromReadHighScore()) {
|
||||||
|
newHighScoreAchieved = true;
|
||||||
|
eepromWriteHighScore(score);
|
||||||
|
}
|
||||||
|
displaySetValue(score);
|
||||||
|
canvasWipeRow(r);
|
||||||
|
canvasShow();
|
||||||
|
wipedLines = true;
|
||||||
|
filledLines += 1;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if (wipedLines) {
|
||||||
|
soundCtrl(SOUND_PLING);
|
||||||
|
}
|
||||||
|
|
||||||
|
if (wipedLines && (filledLines > 0) && ((filledLines % 10) == 0)) {
|
||||||
|
if (level < MAX_LEVEL) {
|
||||||
|
level += 1;
|
||||||
|
}
|
||||||
|
soundCtrl(SOUND_FANFARE);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
#ifndef STATE_DEBUGGING
|
|
||||||
if (isGameActive()) {
|
if (isGameActive()) {
|
||||||
displaySetValue(score);
|
displaySetValue(score);
|
||||||
} else {
|
} else {
|
||||||
displaySetValue(eepromReadHighScore());
|
displaySetValue(eepromReadHighScore());
|
||||||
}
|
}
|
||||||
#endif
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void gameInit() {
|
void gameInit() {
|
||||||
|
@ -13,7 +13,6 @@
|
|||||||
#include "spi.h"
|
#include "spi.h"
|
||||||
#include "display.h"
|
#include "display.h"
|
||||||
#include "eeprom.h"
|
#include "eeprom.h"
|
||||||
#include "config.h"
|
|
||||||
|
|
||||||
|
|
||||||
int main() {
|
int main() {
|
||||||
@ -34,15 +33,10 @@ int main() {
|
|||||||
displayInit();
|
displayInit();
|
||||||
myRandInit();
|
myRandInit();
|
||||||
canvasInit();
|
canvasInit();
|
||||||
buttonsInit();
|
|
||||||
|
|
||||||
if (isConfigMode()) {
|
shapesInit();
|
||||||
configInit();
|
gameInit();
|
||||||
} else {
|
buttonsInit();
|
||||||
shapesInit();
|
|
||||||
gameInit();
|
|
||||||
buttonsStart();
|
|
||||||
}
|
|
||||||
|
|
||||||
__enable_interrupt();
|
__enable_interrupt();
|
||||||
|
|
||||||
|
@ -1,7 +1,6 @@
|
|||||||
#include <stdint.h>
|
#include <stdint.h>
|
||||||
#include <stddef.h>
|
#include <stddef.h>
|
||||||
#include <stdlib.h>
|
#include <stdlib.h>
|
||||||
#include <stdbool.h>
|
|
||||||
|
|
||||||
#include "shapes.h"
|
#include "shapes.h"
|
||||||
#include "myrand.h"
|
#include "myrand.h"
|
||||||
@ -20,7 +19,6 @@ typedef struct {
|
|||||||
orientation_t orientation;
|
orientation_t orientation;
|
||||||
uint8_t x; // column
|
uint8_t x; // column
|
||||||
uint8_t y; // row
|
uint8_t y; // row
|
||||||
bool locked;
|
|
||||||
} stone_t;
|
} stone_t;
|
||||||
|
|
||||||
typedef struct {
|
typedef struct {
|
||||||
@ -365,11 +363,6 @@ void stoneCreate() {
|
|||||||
stone.orientation = e_0;
|
stone.orientation = e_0;
|
||||||
stone.x = 4;
|
stone.x = 4;
|
||||||
stone.y = 0;
|
stone.y = 0;
|
||||||
stone.locked = false;
|
|
||||||
}
|
|
||||||
|
|
||||||
void stoneLock() {
|
|
||||||
stone.locked = true;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
uint8_t stoneIsValid() {
|
uint8_t stoneIsValid() {
|
||||||
@ -383,12 +376,6 @@ static uint8_t move(direction_t direction) {
|
|||||||
if (motions[stone.shape].nullRotation && (direction == e_RotateLeft || direction == e_RotateRight)) {
|
if (motions[stone.shape].nullRotation && (direction == e_RotateLeft || direction == e_RotateRight)) {
|
||||||
return 1;
|
return 1;
|
||||||
}
|
}
|
||||||
|
|
||||||
// if the stone is already locked, do nothing
|
|
||||||
if (stone.locked) {
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
// check whether the pixels to move to are free
|
// check whether the pixels to move to are free
|
||||||
if (canvasIsPixelFree(stone.x + motions[stone.shape].motion[direction][stone.orientation].set[0].x,
|
if (canvasIsPixelFree(stone.x + motions[stone.shape].motion[direction][stone.orientation].set[0].x,
|
||||||
stone.y + motions[stone.shape].motion[direction][stone.orientation].set[0].y) &&
|
stone.y + motions[stone.shape].motion[direction][stone.orientation].set[0].y) &&
|
||||||
@ -483,31 +470,6 @@ uint8_t stoneDraw() {
|
|||||||
return res;
|
return res;
|
||||||
}
|
}
|
||||||
|
|
||||||
static void stoneJustDraw(uint8_t x, uint8_t y, shape_t shape) {
|
|
||||||
canvasSetPixel(x + motions[shape].draw[0].x,
|
|
||||||
y + motions[shape].draw[0].y,
|
|
||||||
motions[shape].color);
|
|
||||||
canvasSetPixel(x + motions[shape].draw[1].x,
|
|
||||||
y + motions[shape].draw[1].y,
|
|
||||||
motions[shape].color);
|
|
||||||
canvasSetPixel(x + motions[shape].draw[2].x,
|
|
||||||
y + motions[shape].draw[2].y,
|
|
||||||
motions[shape].color);
|
|
||||||
canvasSetPixel(x + motions[shape].draw[3].x,
|
|
||||||
y + motions[shape].draw[3].y,
|
|
||||||
motions[shape].color);
|
|
||||||
}
|
|
||||||
|
|
||||||
void stoneDrawConfigPattern() {
|
|
||||||
stoneJustDraw(1, 0, e_I);
|
|
||||||
stoneJustDraw(3, 4, e_O);
|
|
||||||
stoneJustDraw(4, 7, e_T);
|
|
||||||
stoneJustDraw(5, 10, e_Z);
|
|
||||||
stoneJustDraw(1, 12, e_S);
|
|
||||||
stoneJustDraw(5, 15, e_L);
|
|
||||||
stoneJustDraw(1, 17, e_J);
|
|
||||||
}
|
|
||||||
|
|
||||||
uint8_t stoneMoveDown() {
|
uint8_t stoneMoveDown() {
|
||||||
return move(e_MoveDown);
|
return move(e_MoveDown);
|
||||||
}
|
}
|
||||||
|
@ -5,7 +5,6 @@
|
|||||||
|
|
||||||
void shapesInit();
|
void shapesInit();
|
||||||
void stoneCreate();
|
void stoneCreate();
|
||||||
void stoneLock();
|
|
||||||
uint8_t stoneIsValid();
|
uint8_t stoneIsValid();
|
||||||
uint8_t stoneDraw();
|
uint8_t stoneDraw();
|
||||||
uint8_t stoneMoveDown();
|
uint8_t stoneMoveDown();
|
||||||
@ -14,6 +13,5 @@ uint8_t stoneMoveRight();
|
|||||||
uint8_t stoneRotateLeft();
|
uint8_t stoneRotateLeft();
|
||||||
uint8_t stoneRotateRight();
|
uint8_t stoneRotateRight();
|
||||||
|
|
||||||
void stoneDrawConfigPattern();
|
|
||||||
|
|
||||||
#endif // _SHAPES_H_
|
#endif // _SHAPES_H_
|
||||||
|
10
readme.md
10
readme.md
@ -2,14 +2,6 @@
|
|||||||
|
|
||||||

|

|
||||||
|
|
||||||
Update Amplifier (separate input circuitry per PSG, it appears, that a silent PSG has a DC level on its output which is summarized to the AC output of the working PSG, so two input circuits with individual couping capacitor):
|
|
||||||
|
|
||||||

|
|
||||||
|
|
||||||
Update of the power switch of the amplifier (at appears, that the small transistor couldn't deliver enough current):
|
|
||||||
|
|
||||||

|
|
||||||
|
|
||||||
This Tetris implementation consists of a hardware and a software (running on that hardware).
|
This Tetris implementation consists of a hardware and a software (running on that hardware).
|
||||||
|
|
||||||
The hardware utilizes four MSP430 microcontrollers for 1.) the game play, 2.) the play ground canvas, 3.) the score display and 4.) the sound effects.
|
The hardware utilizes four MSP430 microcontrollers for 1.) the game play, 2.) the play ground canvas, 3.) the score display and 4.) the sound effects.
|
||||||
@ -62,7 +54,7 @@ An amplifier following the proposal of the AY-3-8913 datasheet is implemented us
|
|||||||
The clock generator proposed by the AY-3-8913 does not work reliably, so an alternative design from "The Art of Electronics" has been used.
|
The clock generator proposed by the AY-3-8913 does not work reliably, so an alternative design from "The Art of Electronics" has been used.
|
||||||
|
|
||||||

|

|
||||||

|

|
||||||

|

|
||||||

|

|
||||||
|
|
||||||
|
@ -1,55 +1,38 @@
|
|||||||
#include "colors.h"
|
#include "colors.h"
|
||||||
|
|
||||||
|
#define DIMM_FACTOR 3
|
||||||
.section ".rodata","a"
|
.section ".rodata","a"
|
||||||
;; color definitions according to
|
;; color definitions according to
|
||||||
;; https://learn.sparkfun.com/tutorials/lilypad-protosnap-plus-activity-guide/3-custom-color-mixing
|
;; https://learn.sparkfun.com/tutorials/lilypad-protosnap-plus-activity-guide/3-custom-color-mixing
|
||||||
colors:
|
colors:
|
||||||
.global colors
|
.global colors
|
||||||
;; red, green, blue, padding
|
;; red, green, blue, padding
|
||||||
.byte 0x00, 0x00, 0x00, 0 ;; off
|
off:
|
||||||
|
.byte 0x00, 0x00, 0x00, 0
|
||||||
.byte 0x00>>5, 0x00>>5, 0xff>>5, 0 ;; blue
|
blue:
|
||||||
.byte 0x00>>5, 0xff>>5, 0x00>>5, 0 ;; green
|
.byte 0x00>>DIMM_FACTOR, 0x00>>DIMM_FACTOR, 0xff>>DIMM_FACTOR, 0
|
||||||
.byte 0xff>>5, 0x80>>5, 0x00>>5, 0 ;; orange
|
green:
|
||||||
.byte 0x80>>5, 0x00>>5, 0xff>>5, 0 ;; violet
|
.byte 0x00>>DIMM_FACTOR, 0xff>>DIMM_FACTOR, 0x00>>DIMM_FACTOR, 0
|
||||||
.byte 0x00>>5, 0xff>>5, 0xff>>5, 0 ;; cyan
|
orange:
|
||||||
.byte 0xff>>5, 0xff>>5, 0x00>>5, 0 ;; yellow
|
.byte 0xff>>DIMM_FACTOR, 0x80>>DIMM_FACTOR, 0x00>>DIMM_FACTOR, 0
|
||||||
.byte 0xff>>5, 0x00>>5, 0x00>>5, 0 ;; red
|
rose:
|
||||||
.byte 0xff>>5, 0xff>>5, 0xff>>5, 0 ;; white
|
.byte 0xff>>DIMM_FACTOR, 0x00>>DIMM_FACTOR, 0x80>>DIMM_FACTOR, 0
|
||||||
|
magenta:
|
||||||
.byte 0x00>>4, 0x00>>4, 0xff>>4, 0 ;; blue
|
.byte 0xff>>DIMM_FACTOR, 0x00>>DIMM_FACTOR, 0xff>>DIMM_FACTOR, 0
|
||||||
.byte 0x00>>4, 0xff>>4, 0x00>>4, 0 ;; green
|
violet:
|
||||||
.byte 0xff>>4, 0x80>>4, 0x00>>4, 0 ;; orange
|
.byte 0x80>>DIMM_FACTOR, 0x00>>DIMM_FACTOR, 0xff>>DIMM_FACTOR, 0
|
||||||
.byte 0x80>>4, 0x00>>4, 0xff>>4, 0 ;; violet
|
azure:
|
||||||
.byte 0x00>>4, 0xff>>4, 0xff>>4, 0 ;; cyan
|
.byte 0x00>>DIMM_FACTOR, 0x80>>DIMM_FACTOR, 0xff>>DIMM_FACTOR, 0
|
||||||
.byte 0xff>>4, 0xff>>4, 0x00>>4, 0 ;; yellow
|
cyan:
|
||||||
.byte 0xff>>4, 0x00>>4, 0x00>>4, 0 ;; red
|
.byte 0x00>>DIMM_FACTOR, 0xff>>DIMM_FACTOR, 0xff>>DIMM_FACTOR, 0
|
||||||
.byte 0xff>>4, 0xff>>4, 0xff>>4, 0 ;; white
|
springgreen:
|
||||||
|
.byte 0x00>>DIMM_FACTOR, 0xff>>DIMM_FACTOR, 0x80>>DIMM_FACTOR, 0
|
||||||
.byte 0x00>>3, 0x00>>3, 0xff>>3, 0 ;; blue
|
chartreuse:
|
||||||
.byte 0x00>>3, 0xff>>3, 0x00>>3, 0 ;; green
|
.byte 0x80>>DIMM_FACTOR, 0xff>>DIMM_FACTOR, 0x00>>DIMM_FACTOR, 0
|
||||||
.byte 0xff>>3, 0x80>>3, 0x00>>3, 0 ;; orange
|
yellow:
|
||||||
.byte 0x80>>3, 0x00>>3, 0xff>>3, 0 ;; violet
|
.byte 0xff>>DIMM_FACTOR, 0xff>>DIMM_FACTOR, 0x00>>DIMM_FACTOR, 0
|
||||||
.byte 0x00>>3, 0xff>>3, 0xff>>3, 0 ;; cyan
|
white:
|
||||||
.byte 0xff>>3, 0xff>>3, 0x00>>3, 0 ;; yellow
|
.byte 0xff>>DIMM_FACTOR, 0xff>>DIMM_FACTOR, 0xff>>DIMM_FACTOR, 0
|
||||||
.byte 0xff>>3, 0x00>>3, 0x00>>3, 0 ;; red
|
red:
|
||||||
.byte 0xff>>3, 0xff>>3, 0xff>>3, 0 ;; white
|
.byte 0xff>>DIMM_FACTOR, 0x00>>DIMM_FACTOR, 0x00>>DIMM_FACTOR, 0
|
||||||
|
|
||||||
.byte 0x00>>2, 0x00>>2, 0xff>>2, 0 ;; blue
|
|
||||||
.byte 0x00>>2, 0xff>>2, 0x00>>2, 0 ;; green
|
|
||||||
.byte 0xff>>2, 0x80>>2, 0x00>>2, 0 ;; orange
|
|
||||||
.byte 0x80>>2, 0x00>>2, 0xff>>2, 0 ;; violet
|
|
||||||
.byte 0x00>>2, 0xff>>2, 0xff>>2, 0 ;; cyan
|
|
||||||
.byte 0xff>>2, 0xff>>2, 0x00>>2, 0 ;; yellow
|
|
||||||
.byte 0xff>>2, 0x00>>2, 0x00>>2, 0 ;; red
|
|
||||||
.byte 0xff>>2, 0xff>>2, 0xff>>2, 0 ;; white
|
|
||||||
|
|
||||||
.byte 0x00>>1, 0x00>>1, 0xff>>1, 0 ;; blue
|
|
||||||
.byte 0x00>>1, 0xff>>1, 0x00>>1, 0 ;; green
|
|
||||||
.byte 0xff>>1, 0x80>>1, 0x00>>1, 0 ;; orange
|
|
||||||
.byte 0x80>>1, 0x00>>1, 0xff>>1, 0 ;; violet
|
|
||||||
.byte 0x00>>1, 0xff>>1, 0xff>>1, 0 ;; cyan
|
|
||||||
.byte 0xff>>1, 0xff>>1, 0x00>>1, 0 ;; yellow
|
|
||||||
.byte 0xff>>1, 0x00>>1, 0x00>>1, 0 ;; red
|
|
||||||
.byte 0xff>>1, 0xff>>1, 0xff>>1, 0 ;; white
|
|
||||||
|
|
||||||
|
@ -2,20 +2,21 @@
|
|||||||
#define _COLORS_H_
|
#define _COLORS_H_
|
||||||
|
|
||||||
|
|
||||||
#define _off 0
|
#define _off 0x00
|
||||||
|
#define _blue 0x01
|
||||||
|
#define _green 0x02
|
||||||
|
#define _orange 0x03
|
||||||
|
#define _rose 0x04
|
||||||
|
#define _magenta 0x05
|
||||||
|
#define _violet 0x06
|
||||||
|
#define _azure 0x07
|
||||||
|
#define _cyan 0x08
|
||||||
|
#define _springgreen 0x09
|
||||||
|
#define _chartreuse 0x0a
|
||||||
|
#define _yellow 0x0b
|
||||||
|
#define _white 0x0c
|
||||||
|
#define _red 0x0d
|
||||||
|
|
||||||
#define _blue 1
|
|
||||||
#define _green 2
|
|
||||||
#define _orange 3
|
|
||||||
#define _violet 4
|
|
||||||
#define _cyan 5
|
|
||||||
#define _yellow 6
|
|
||||||
#define _red 7
|
|
||||||
#define _white 8
|
|
||||||
|
|
||||||
#define _brightness_offset 8
|
|
||||||
#define _brightness_shifts 5
|
|
||||||
#define _color_end (_brightness_offset * _brightness_shifts)
|
|
||||||
|
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
@ -4,13 +4,15 @@ OBJDUMP=$(TOOLCHAIN_PREFIX)/bin/msp430-elf-objdump
|
|||||||
|
|
||||||
ARTIFACT=firmware
|
ARTIFACT=firmware
|
||||||
MCU=msp430g2553
|
MCU=msp430g2553
|
||||||
|
COMMONFLAGS=-Wall -mmcu=$(MCU) -I $(TOOLCHAIN_PREFIX)/include -g0 -fdata-sections -ffunction-sections
|
||||||
|
|
||||||
DEBUGFLAGS=
|
DEBUGFLAGS=
|
||||||
# DEBUGFLAGS+= -g3 -ggdb -gdwarf-2
|
# DEBUGFLAGS+= -g3 -ggdb -gdwarf-2
|
||||||
COMMONFLAGS=-Wall -mmcu=$(MCU) -I $(TOOLCHAIN_PREFIX)/include -O0 -g0 $(DEBUGFLAGS)
|
|
||||||
CFLAGS=$(COMMONFLAGS) -std=gnu99
|
|
||||||
ASFLAGS=$(COMMONFLAGS) -D__ASSEMBLER__
|
|
||||||
|
|
||||||
LDFLAGS=-mmcu=$(MCU) -L $(TOOLCHAIN_PREFIX)/include
|
CFLAGS=$(COMMONFLAGS) -std=gnu99 -O0 $(DEBUGFLAGS)
|
||||||
|
ASFLAGS=$(COMMONFLAGS) -D__ASSEMBLER__ -Os $(DEBUGFLAGS)
|
||||||
|
|
||||||
|
LDFLAGS=-mmcu=$(MCU) -L $(TOOLCHAIN_PREFIX)/include -Wl,-Map,firmware.map
|
||||||
|
|
||||||
$(ARTIFACT).elf: main.o scheduler.o spi.o spi_init.o sequencer.o melody_tetris.o melody_tusch1.o psg.o mute.o melody_pling.o
|
$(ARTIFACT).elf: main.o scheduler.o spi.o spi_init.o sequencer.o melody_tetris.o melody_tusch1.o psg.o mute.o melody_pling.o
|
||||||
$(CC) -o $@ $(LDFLAGS) $^
|
$(CC) -o $@ $(LDFLAGS) $^
|
||||||
|
@ -6,8 +6,6 @@
|
|||||||
#include "psg.h"
|
#include "psg.h"
|
||||||
#include "scheduler.h"
|
#include "scheduler.h"
|
||||||
#include "sequencer.h"
|
#include "sequencer.h"
|
||||||
#include "melody_tetris.h"
|
|
||||||
#include "melody_tusch1.h"
|
|
||||||
#include "mute.h"
|
#include "mute.h"
|
||||||
|
|
||||||
int main() {
|
int main() {
|
||||||
@ -31,7 +29,6 @@ int main() {
|
|||||||
|
|
||||||
__enable_interrupt();
|
__enable_interrupt();
|
||||||
|
|
||||||
|
|
||||||
while (1) {
|
while (1) {
|
||||||
schExec();
|
schExec();
|
||||||
}
|
}
|
||||||
|
@ -5,11 +5,8 @@
|
|||||||
#include "scheduler.h"
|
#include "scheduler.h"
|
||||||
|
|
||||||
const t_tone plingVoice1[] = {
|
const t_tone plingVoice1[] = {
|
||||||
{ .octave = e_O_5, .note = e_C, .length = e_L_1_16, .legato = false, .staccato = false },
|
{ .octave = e_O_5, .note = e_C, .length = e_L_1_4, .legato = false, .staccato = true },
|
||||||
{ .octave = e_O_5, .note = e_Cis, .length = e_L_1_16, .legato = false, .staccato = false },
|
{ .octave = e_O_5, .note = e_G, .length = e_L_1_4, .legato = false, .staccato = true },
|
||||||
{ .octave = e_O_5, .note = e_D, .length = e_L_1_16, .legato = false, .staccato = false },
|
|
||||||
{ .octave = e_O_5, .note = e_Dis, .length = e_L_1_16, .legato = false, .staccato = false },
|
|
||||||
{ .octave = e_O_5, .note = e_E, .length = e_L_1_8, .legato = false, .staccato = false },
|
|
||||||
|
|
||||||
{ .octave = e_O_Null, .note = e_Null, .length = e_L_SyncMark,.legato = false, .staccato = false },
|
{ .octave = e_O_Null, .note = e_Null, .length = e_L_SyncMark,.legato = false, .staccato = false },
|
||||||
{ .octave = e_O_Null, .note = e_Null, .length = e_L_StopMark,.legato = false, .staccato = false },
|
{ .octave = e_O_Null, .note = e_Null, .length = e_L_StopMark,.legato = false, .staccato = false },
|
||||||
@ -19,9 +16,10 @@ const t_tone plingVoice1[] = {
|
|||||||
|
|
||||||
t_melodies pling = {
|
t_melodies pling = {
|
||||||
.melodies = { { .amplitude = 12, .tones = plingVoice1 } },
|
.melodies = { { .amplitude = 12, .tones = plingVoice1 } },
|
||||||
|
.chip = 1,
|
||||||
.numOfMelodies = 1,
|
.numOfMelodies = 1,
|
||||||
.pace = 200,
|
.pace = 200,
|
||||||
.chip = 1
|
.slotMask = 0x02
|
||||||
};
|
};
|
||||||
|
|
||||||
void playPling() {
|
void playPling() {
|
||||||
|
@ -922,21 +922,21 @@ const t_tone voice3[] = {
|
|||||||
{ .octave = e_O_Null, .note = e_Null, .length = e_L_EndMark, .legato = false, .staccato = false },
|
{ .octave = e_O_Null, .note = e_Null, .length = e_L_EndMark, .legato = false, .staccato = false },
|
||||||
};
|
};
|
||||||
|
|
||||||
#define INITIAL_PACE 160
|
|
||||||
t_melodies tetrisTheme = {
|
t_melodies tetrisTheme = {
|
||||||
.melodies = { { .amplitude = 8, .tones = voice1 }, { .amplitude = 8, .tones = voice2 }, { .amplitude = 8, .tones = voice3 } },
|
.melodies = { { .amplitude = 8, .tones = voice1 }, { .amplitude = 8, .tones = voice2 }, { .amplitude = 8, .tones = voice3 } },
|
||||||
|
.chip = 0,
|
||||||
.numOfMelodies = 3,
|
.numOfMelodies = 3,
|
||||||
.pace = INITIAL_PACE,
|
.pace = 160,
|
||||||
.chip = 0
|
.slotMask = 0x01
|
||||||
};
|
};
|
||||||
|
|
||||||
void playMelodyTetris() {
|
void playMelodyTetris() {
|
||||||
tetrisTheme.pace = INITIAL_PACE; // reset to start value each time
|
tetrisTheme.pace = 160; // reset to start value each time
|
||||||
sequencerPlayMelodies(&tetrisTheme);
|
sequencerPlayMelodies(&tetrisTheme);
|
||||||
}
|
}
|
||||||
|
|
||||||
void playMelodyTetrisFaster() {
|
void playMelodyTetrisFaster() {
|
||||||
tetrisTheme.pace += 15;
|
tetrisTheme.pace += 10;
|
||||||
sequencerChangePace(&tetrisTheme);
|
sequencerChangePace(&tetrisTheme);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -73,14 +73,14 @@ const t_tone tusch1voice3[] = {
|
|||||||
|
|
||||||
t_melodies tusch1 = {
|
t_melodies tusch1 = {
|
||||||
.melodies = { { .amplitude = 12, .tones = tusch1voice1 }, { .amplitude = 12, .tones = tusch1voice2 }, { .amplitude = 12, .tones = tusch1voice3 } },
|
.melodies = { { .amplitude = 12, .tones = tusch1voice1 }, { .amplitude = 12, .tones = tusch1voice2 }, { .amplitude = 12, .tones = tusch1voice3 } },
|
||||||
|
.chip = 1,
|
||||||
.numOfMelodies = 3,
|
.numOfMelodies = 3,
|
||||||
.pace = 200,
|
.pace = 200,
|
||||||
.chip = 1
|
.slotMask = 0x02
|
||||||
};
|
};
|
||||||
|
|
||||||
void playTusch1() {
|
void playTusch1() {
|
||||||
sequencerPlayMelodies(&tusch1);
|
sequencerPlayMelodies(&tusch1);
|
||||||
// playMelodyTetrisFaster();
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
@ -8,15 +8,15 @@ void muteInit() {
|
|||||||
P1DIR |= BIT6;
|
P1DIR |= BIT6;
|
||||||
|
|
||||||
// initially, mute
|
// initially, mute
|
||||||
P1OUT &= ~BIT6;
|
|
||||||
}
|
|
||||||
|
|
||||||
void mute() {
|
|
||||||
P1OUT &= ~BIT6;
|
|
||||||
}
|
|
||||||
|
|
||||||
void unMute() {
|
|
||||||
P1OUT |= BIT6;
|
P1OUT |= BIT6;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void mute() {
|
||||||
|
P1OUT |= BIT6;
|
||||||
|
}
|
||||||
|
|
||||||
|
void unMute() {
|
||||||
|
P1OUT &= ~BIT6;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
@ -81,6 +81,19 @@ inline static void BUS_OP_CS1_DISABLE() {
|
|||||||
BUS_CTRL_REG |= _CS1;
|
BUS_CTRL_REG |= _CS1;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#if 0
|
||||||
|
static void delay() {
|
||||||
|
asm volatile (
|
||||||
|
"push r12\n"
|
||||||
|
"mov.w #5, r12\n"
|
||||||
|
"loop:\n"
|
||||||
|
"dec.w r12\n"
|
||||||
|
"jnz loop\n"
|
||||||
|
"pop r12\n"
|
||||||
|
);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
static uint8_t psgReadShadow(uint8_t chip, uint8_t address) {
|
static uint8_t psgReadShadow(uint8_t chip, uint8_t address) {
|
||||||
return psgShadowRegisters[chip][address];
|
return psgShadowRegisters[chip][address];
|
||||||
}
|
}
|
||||||
@ -162,5 +175,21 @@ void psgInit() {
|
|||||||
// disable everything
|
// disable everything
|
||||||
psgWrite(0, _ENABLE_REG, 0xff);
|
psgWrite(0, _ENABLE_REG, 0xff);
|
||||||
psgWrite(1, _ENABLE_REG, 0xff);
|
psgWrite(1, _ENABLE_REG, 0xff);
|
||||||
|
|
||||||
|
// volume to 0 on all channels
|
||||||
|
psgWrite(0, CHANNEL_A_AMPLITUDE_REG, 0);
|
||||||
|
psgWrite(0, CHANNEL_B_AMPLITUDE_REG, 0);
|
||||||
|
psgWrite(0, CHANNEL_C_AMPLITUDE_REG, 0);
|
||||||
|
psgWrite(1, CHANNEL_A_AMPLITUDE_REG, 0);
|
||||||
|
psgWrite(1, CHANNEL_B_AMPLITUDE_REG, 0);
|
||||||
|
psgWrite(1, CHANNEL_C_AMPLITUDE_REG, 0);
|
||||||
|
|
||||||
|
// frequency preset
|
||||||
|
psgWriteFrequency(0, 0, 0);
|
||||||
|
psgWriteFrequency(0, 1, 0);
|
||||||
|
psgWriteFrequency(0, 2, 0);
|
||||||
|
psgWriteFrequency(1, 0, 0);
|
||||||
|
psgWriteFrequency(1, 1, 0);
|
||||||
|
psgWriteFrequency(1, 2, 0);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -52,6 +52,16 @@ uint16_t schAdd(void (*exec)(void *), void *handle, uint32_t delay, uint32_t per
|
|||||||
return taskId;
|
return taskId;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/*
|
||||||
|
void schDel(void (*exec)(void *), void *handle) {
|
||||||
|
for (uint16_t i = 0; i < MAX_NUM_OF_TASKS; i++) {
|
||||||
|
if ((tasks[i].exec == exec) && (tasks[i].handle == handle)) {
|
||||||
|
tasks[i].exec = NULL;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
*/
|
||||||
void schDel(uint16_t taskId) {
|
void schDel(uint16_t taskId) {
|
||||||
tasks[taskId].exec = NULL;
|
tasks[taskId].exec = NULL;
|
||||||
}
|
}
|
||||||
|
@ -96,11 +96,9 @@ void sequencerExec(void *handle) {
|
|||||||
melody->state = e_PlayTone;
|
melody->state = e_PlayTone;
|
||||||
break;
|
break;
|
||||||
case e_Hold:
|
case e_Hold:
|
||||||
psgPlayTone(melodies->chip, channel, 0, e_O_Null, e_Pause);
|
|
||||||
break;
|
break;
|
||||||
case e_Terminate:
|
case e_Terminate:
|
||||||
schDel(melodies->taskId);
|
schDel(melodies->taskId);
|
||||||
psgPlayTone(melodies->chip, channel, 0, e_O_Null, e_Pause);
|
|
||||||
slots &= ~(melodies->slotMask);
|
slots &= ~(melodies->slotMask);
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
@ -108,8 +106,6 @@ void sequencerExec(void *handle) {
|
|||||||
}
|
}
|
||||||
|
|
||||||
void sequencerPlayMelodies(t_melodies *melodies) {
|
void sequencerPlayMelodies(t_melodies *melodies) {
|
||||||
melodies->slotMask = (1 << melodies->chip);
|
|
||||||
|
|
||||||
if ((slots & melodies->slotMask) != 0) {
|
if ((slots & melodies->slotMask) != 0) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
@ -127,11 +123,8 @@ void sequencerPlayMelodies(t_melodies *melodies) {
|
|||||||
}
|
}
|
||||||
|
|
||||||
void sequencerStopMelodies(t_melodies *melodies) {
|
void sequencerStopMelodies(t_melodies *melodies) {
|
||||||
schDel(melodies->taskId);
|
|
||||||
slots &= ~(melodies->slotMask);
|
slots &= ~(melodies->slotMask);
|
||||||
for (uint8_t channel = 0; channel < melodies->numOfMelodies; channel++) {
|
schDel(melodies->taskId);
|
||||||
psgPlayTone(melodies->chip, channel, 0, e_O_Null, e_Pause);
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void sequencerChangePace(t_melodies *melodies) {
|
void sequencerChangePace(t_melodies *melodies) {
|
||||||
|
@ -51,8 +51,8 @@ typedef struct {
|
|||||||
#define SEQUENCER_PERIOD 4 // ms
|
#define SEQUENCER_PERIOD 4 // ms
|
||||||
#define NUM_OF_CHANNELS 3
|
#define NUM_OF_CHANNELS 3
|
||||||
typedef struct {
|
typedef struct {
|
||||||
uint8_t slotMask;
|
|
||||||
uint8_t chip;
|
uint8_t chip;
|
||||||
|
uint8_t slotMask;
|
||||||
uint8_t taskId;
|
uint8_t taskId;
|
||||||
uint16_t quarterLength;
|
uint16_t quarterLength;
|
||||||
uint8_t numOfMelodies;
|
uint8_t numOfMelodies;
|
||||||
|
@ -1,6 +1,10 @@
|
|||||||
#include <msp430g2553.h>
|
#include <msp430g2553.h>
|
||||||
#include "soundCodes.h"
|
#include "soundCodes.h"
|
||||||
|
|
||||||
|
;; .global cmd
|
||||||
|
;; .section .data.spi,"aw"
|
||||||
|
;;cmd:
|
||||||
|
;; .byte
|
||||||
|
|
||||||
.section ".text","ax",@progbits
|
.section ".text","ax",@progbits
|
||||||
receive_isr:
|
receive_isr:
|
||||||
@ -25,18 +29,19 @@ spiCmdHandler_2:
|
|||||||
spiCmdHandler_3:
|
spiCmdHandler_3:
|
||||||
bit #SOUND_START, &cmd
|
bit #SOUND_START, &cmd
|
||||||
jz spiCmdHandler_4
|
jz spiCmdHandler_4
|
||||||
call #playMelodyTetris
|
;;call #playMelodyTetris
|
||||||
bic #SOUND_START, &cmd
|
bic #SOUND_START, &cmd
|
||||||
spiCmdHandler_4:
|
spiCmdHandler_4:
|
||||||
bit #SOUND_GAMEOVER, &cmd
|
bit #SOUND_GAMEOVER, &cmd
|
||||||
jz spiCmdHandler_5
|
jz spiCmdHandler_5
|
||||||
call #stopMelodyTetris
|
;;call #stopMelodyTetris
|
||||||
|
;; insert a call here
|
||||||
bic #SOUND_GAMEOVER, &cmd
|
bic #SOUND_GAMEOVER, &cmd
|
||||||
spiCmdHandler_5:
|
spiCmdHandler_5:
|
||||||
bit #SOUND_FANFARE, &cmd
|
bit #SOUND_FANFARE, &cmd
|
||||||
jz spiCmdHandler_6
|
jz spiCmdHandler_6
|
||||||
call #playMelodyTetrisFaster
|
;;call #playMelodyTetrisFaster
|
||||||
call #playTusch1
|
;;call #playTusch1
|
||||||
bic #SOUND_FANFARE, &cmd
|
bic #SOUND_FANFARE, &cmd
|
||||||
spiCmdHandler_6:
|
spiCmdHandler_6:
|
||||||
bit #SOUND_LOCK, &cmd
|
bit #SOUND_LOCK, &cmd
|
||||||
@ -51,14 +56,12 @@ spiCmdHandler_7:
|
|||||||
spiCmdHandler_8:
|
spiCmdHandler_8:
|
||||||
bit #SOUND_PLING, &cmd
|
bit #SOUND_PLING, &cmd
|
||||||
jz spiCmdHandler_end
|
jz spiCmdHandler_end
|
||||||
call #playPling
|
;;call #playPling
|
||||||
bic #SOUND_PLING, &cmd
|
bic #SOUND_PLING, &cmd
|
||||||
spiCmdHandler_end:
|
spiCmdHandler_end:
|
||||||
ret
|
ret
|
||||||
|
|
||||||
|
|
||||||
.section "__interrupt_vector_8","ax",@progbits
|
.section "__interrupt_vector_8","ax",@progbits
|
||||||
.word receive_isr
|
.word receive_isr
|
||||||
|
|
||||||
|
|
||||||
.end
|
.end
|
||||||
|
Reference in New Issue
Block a user