split up code

This commit is contained in:
Olaf Rempel 2012-03-02 17:35:35 +01:00
parent 84b160bcc7
commit 953c12a3c7
7 changed files with 694 additions and 487 deletions

7
.gitignore vendored
View File

@ -1,6 +1 @@
*.o
*.elf
*.bin
*.hex
*.lst
*.map
build

View File

@ -1,51 +1,59 @@
PRG = rgb16mpm
OBJ = main.o
MCU_TARGET = atmega32
OPTIMIZE = -Os
# ############################
DEFS =
LIBS =
PRG = rgb16mpm
MCU_TARGET = atmega32
# You should not have to change anything below here.
# ############################
CC = avr-gcc
BUILD_DIR = build
SRC = $(wildcard *.c)
OUTPUTS = .hex .bin _eeprom.hex _eeprom.bin
# Override is only needed by avr-lib build system.
CFLAGS = -Os -g -Wall -mmcu=$(MCU_TARGET)
CFLAGS += -pipe -MMD -MP -MG -MF $(BUILD_DIR)/$(*D)/$(*F).d
LDFLAGS = -Wl,-Map,$(BUILD_DIR)/$(*D)/$(*F).map,--cref
override CFLAGS = -g -Wall $(OPTIMIZE) -mmcu=$(MCU_TARGET) $(DEFS)
override LDFLAGS = -Wl,-Map,$(PRG).map
CC = avr-gcc
OBJCOPY = avr-objcopy
OBJDUMP = avr-objdump
SIZE = avr-size
OBJCOPY = avr-objcopy
OBJDUMP = avr-objdump
SIZE = avr-size
# ############################
all: $(PRG).elf lst text
$(SIZE) -x -A $(PRG).elf
.PHONY: all clean install
all: $(patsubst %,$(BUILD_DIR)/$(PRG)%, .elf $(OUTPUTS))
@$(SIZE) -x -A $<
$(PRG).elf: $(OBJ)
$(CC) $(CFLAGS) $(LDFLAGS) -o $@ $^ $(LIBS)
.SECONDARY: $(patsubst %,$(BUILD_DIR)/%, $(SRC:.c=.o))
$(BUILD_DIR)/%.elf: $(patsubst %,$(BUILD_DIR)/%, $(SRC:.c=.o))
@echo " Linking file: $@"
@$(CC) $(CFLAGS) $(LDFLAGS) $^ -o $@
@$(OBJDUMP) -h -S $@ > $(subst elf,lst,$@)
$(BUILD_DIR)/%.o: %.c $(MAKEFILE_LIST)
@echo " Building file: $<"
@$(shell test -d $(BUILD_DIR)/$(*D) || mkdir -p $(BUILD_DIR)/$(*D))
@$(CC) $(CFLAGS) -o $@ -c $<
$(BUILD_DIR)/%.hex: $(BUILD_DIR)/%.elf
@$(OBJCOPY) -j .text -j .data -O ihex $< $@
$(BUILD_DIR)/%.bin: $(BUILD_DIR)/%.elf
@$(OBJCOPY) -j .text -j .data -O binary $< $@
$(BUILD_DIR)/%_eeprom.hex: $(BUILD_DIR)/%.elf
@$(OBJCOPY) -j .eeprom --change-section-lma .eeprom=0 -O ihex $< $@
$(BUILD_DIR)/%_eeprom.bin: $(BUILD_DIR)/%.elf
@$(OBJCOPY) -j .eeprom --change-section-lma .eeprom=0 -O binary $< $@
include $(shell find $(BUILD_DIR) -name \*.d 2> /dev/null)
# ############################
clean:
rm -rf *.o *.lst *.map $(PRG).elf *.hex *.bin
rm -rf $(BUILD_DIR)
lst: $(PRG).lst
%.lst: %.elf
$(OBJDUMP) -h -S $< > $@
# Rules for building the .text rom images
text: hex bin
hex: $(PRG).hex
bin: $(PRG).bin
%.hex: %.elf
$(OBJCOPY) -j .text -j .data -O ihex $< $@
%.bin: %.elf
$(OBJCOPY) -j .text -j .data -O binary $< $@
install: text
install: $(BUILD_DIR)/$(PRG).hex
# avrdude -p m32 -c dragon_isp -P usb -U flash:w:$(PRG).hex
mpmboot -d /dev/ttyUSB0 -a 0x11 -w flash:$(PRG).hex
mpmboot -d /dev/ttyUSB0 -a 0x11 -w flash:$<

97
eeprom.c Normal file
View File

@ -0,0 +1,97 @@
/***************************************************************************
* nvram parameter read/write *
* *
* Copyright (C) 2011 - 2012 by Olaf Rempel *
* razzor AT kopf MINUS tisch DOT de *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; version 2 of the License, *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
***************************************************************************/
#include <avr/io.h>
#include <avr/interrupt.h>
#include <avr/pgmspace.h>
#include <avr/eeprom.h>
#include <util/crc16.h>
#include "rgb16mpm.h"
static uint16_t nvram_write_pos;
struct _nvdata nvram_data;
static struct _nvdata nvram_eeprom EEMEM = NVRAM_DEFAULTS;
static struct _nvdata nvram_defaults PROGMEM = NVRAM_DEFAULTS;
/* store nvram data to eeprom */
ISR(EE_RDY_vect) {
EECR &= ~(1<<EERIE);
sei();
if (nvram_write_pos < sizeof(struct _nvdata)) {
/* not a function: shorter IRQ entry (fast IRQ re-enable) */
EEARL = (nvram_write_pos & 0xFF);
EEARH = (nvram_write_pos >> 8) & 0xFF;
EEDR = ((uint8_t *)&nvram_data)[nvram_write_pos++];
cli();
EECR |= (1<<EEMWE);
EECR |= (1<<EEWE);
sei();
EECR |= (1<<EERIE);
}
}
/* create crc and store nvram data to eeprom */
void eeprom_write(void)
{
uint8_t i;
uint16_t crc = 0x0000;
uint8_t *tmp = (uint8_t *)&nvram_data;
nvram_data.nvram_size = sizeof(struct _nvdata);
for (i = 0; i < sizeof(struct _nvdata) -2; i++) {
crc = _crc_ccitt_update(crc, *tmp++);
}
nvram_data.nvram_crc = crc;
nvram_write_pos = 0;
EEARL = (nvram_write_pos & 0xFF);
EEARH = (nvram_write_pos >> 8) & 0xFF;
EEDR = ((uint8_t *)&nvram_data)[nvram_write_pos++];
cli();
EECR |= (1<<EEMWE);
EECR |= (1<<EEWE);
sei();
EECR |= (1<<EERIE);
}
/* read nvram from eeprom and check crc */
void eeprom_read(void)
{
uint8_t i;
uint16_t crc = 0x0000;
uint8_t *tmp = (uint8_t *)&nvram_data;
eeprom_read_block(&nvram_data, &nvram_eeprom, sizeof(struct _nvdata));
for (i = 0; i < sizeof(struct _nvdata); i++) {
crc = _crc_ccitt_update(crc, *tmp++);
}
/* if nvram content is invalid, overwrite with defaults */
if ((nvram_data.nvram_size != sizeof(struct _nvdata)) || (crc != 0x0000)) {
memcpy_P(&nvram_data, &nvram_defaults, sizeof(struct _nvdata));
eeprom_write();
}
}

451
main.c
View File

@ -20,10 +20,10 @@
***************************************************************************/
#include <avr/io.h>
#include <avr/interrupt.h>
#include <avr/wdt.h>
#include <stdio.h>
#include "rgb16mpm.h"
/*
* using ATmega32 @8MHz:
* Fuse H: 0xD9 (no bootloader, jtag disabled)
@ -41,424 +41,15 @@
* PD3 -> /LED
*/
#define F_CPU 8000000
#include <util/delay.h>
#define ROW1 PORTB1 /* RED */
#define ROW2 PORTB0 /* GREEN */
#define ROW3 PORTB3 /* BLUE */
#define ROW4 PORTB2 /* not used */
#define RXTX PORTD2 /* RS485 TX enable */
#define LED PORTD3
/* running without mpmboot? */
#define STANDALONE 0
#if (STANDALONE)
#define OSCCAL 0xAA
#define BAUDRATE 115200
#define MPM_ADDRESS 0x11
#define UART_CALC_BAUDRATE(baudRate) (((uint32_t)F_CPU) / (((uint32_t)baudRate)*16) -1)
#endif /* STANDALONE */
const static uint8_t versioninfo[16] = "rgb16mpm v0.99";
#define CMD_WAIT 0x00
#define CMD_SWITCH_MODE 0x01
#define CMD_GET_VERSION 0x02
#define CMD_GET_CHIPINFO 0x03 /* bootloader / mpmboot */
#define CMD_READ_MEMORY 0x11 /* bootloader / mpmboot */
#define CMD_WRITE_MEMORY 0x12 /* bootloader / mpmboot */
#define CMD_WRITE_COLOR 0x81
#define CMD_WRITE_RAW_COLOR 0x82
#define CMD_READ_RAW_COLOR 0x83
#define CMD_WRITE_CONFIG 0x81
/* 16 values per color */
static uint8_t chan_value[3][16];
/* (16 +1) * 4 values (portA, portC, OCR0, flags) per color */
static uint8_t chan_rawdata[3][17 * 4];
/* used only in softpwm ISRs */
register uint8_t * pCurrentStep asm("r2"); /* r3:r2 */
/* used to sync softpwm ISRs and color_update() */
register uint8_t nextColor asm("r4"); /* r4 */
/* worst case: 9+2+12+8+7+13 = 61 clks -> 7.625us @8MHz */
ISR(TIMER0_OVF_vect, ISR_NAKED)
{
asm volatile(
/* save registers 2+1+2+2+2 = 9 */
"push r24 \n\t"
"in r24, __SREG__ \n\t"
"push r24 \n\t"
"push r30 \n\t"
"push r31 \n\t"
::
);
asm volatile(
/* disable outputs 1+1 = 2 */
"out %0, r1 \n\t" /* PORTA = 0x00; */
"out %1, r1 \n\t" /* PORTC = 0x00; */
:: "I" (_SFR_IO_ADDR(PORTA)),
"I" (_SFR_IO_ADDR(PORTC))
);
asm volatile(
/* switch color and assign pCurrentStep */ // R G B
"mov r24, %0 \n\t" // 1 1 1
"inc %0 \n\t" /* nextColor++ */ // 2 2 2
"cpi r24, 1 \n\t" // 3 3 3
"brlo L_red%= \n\t" /* if (nextColor < 1) -> red */ // 5 4 4
"breq L_green%= \n\t" /* if (nextColor == 1) -> green */ // - 6 5
"clr %0 \n\t" /* nextColor = 0; */ // - - 6
"ldi r24, %7 \n\t" /* PORTB = (1<<ROW4); */ // - - 7
"ldi r30, lo8(%3) \n\t" /* pCurrentStep = &rawdata[2]; */ // - - 8
"ldi r31, hi8(%3) \n\t" // - - 9
"rjmp L_end%= \n\t" // - - 11
"L_red%=: \n\t" /* red: */
"ldi r24, %5 \n\t" /* PORTB = (1<<ROW1); */ // 6 - -
"ldi r30, lo8(%1) \n\t" /* pCurrentStep = &rawdata[0]; */ // 7 - -
"ldi r31, hi8(%1) \n\t" // 8 - -
"rjmp L_end%= \n\t" // 10 - -
"L_green%=: \n\t" /* green: */
"ldi r24, %6 \n\t" /* PORTB = (1<<ROW2); */ // - 7 -
"ldi r30, lo8(%2) \n\t" /* pCurrentStep = &rawdata[1]; */ // - 8 -
"ldi r31, hi8(%2) \n\t" // - 9 -
"L_end%=: \n\t"
"out %4, r24 \n\t" /* set PORTB */ // 11 10 12
:: "r" (nextColor),
"i" (&chan_rawdata[0]), /* RED */
"i" (&chan_rawdata[1]), /* GREEN */
"i" (&chan_rawdata[2]), /* BLUE */
"I" (_SFR_IO_ADDR(PORTB)),
"i" ((1<<ROW1)), /* RED */
"i" ((1<<ROW2)), /* GREEN */
"i" ((1<<ROW3)) /* BLUE */
);
asm volatile(
/* load table values 1+1+1+1+1+1+1+1+1 = 8 */
"ld r24, z+ \n\t"
"out %1, r24 \n\t" /* PORTA = *pCurrentStep++; */
"ld r24, z+ \n\t"
"out %2, r24 \n\t" /* PORTC = *pCurrentStep++; */
"ld r24, z+ \n\t"
"out %3, r24 \n\t" /* OCR0 = *pCurrentStep++; */
"ld r24, z+ \n\t"
"movw %0, r30 \n\t"
:: "r" (pCurrentStep),
"I" (_SFR_IO_ADDR(PORTA)),
"I" (_SFR_IO_ADDR(PORTC)),
"I" (_SFR_IO_ADDR(OCR0))
);
asm volatile(
/* check if IRQ must be enabled 1+1+1+1+1+1+1 = 3/7 */
"or r24, r24 \n\t" /* if (*pCurrentStep++) { */
"breq L_skip%= \n\t"
"ldi r24, %1 \n\t" /* TIFR = (1<<OCF0); */
"out %0, r24 \n\t"
"in r24, %2 \n\t" /* TIMSK |= (1<<OCIE0); */
"ori r24, %3 \n\t"
"out %2, r24 \n\t"
"L_skip%=: \n\t" /* } */
:: "I" (_SFR_IO_ADDR(TIFR)),
"M" ((1<<OCF0)),
"I" (_SFR_IO_ADDR(TIMSK)),
"M" ((1<<OCIE0))
);
asm volatile(
/* restore registers 2+2+2+1+2+4 = 13 */
"pop r31 \n\t"
"pop r30 \n\t"
"pop r24 \n\t"
"out __SREG__, r24 \n\t"
"pop r24 \n\t"
"reti \n\t"
::
);
}
/* worst case: 9+9+5+13 = 36 clks -> 4.5us @ 8MHz */
ISR(TIMER0_COMP_vect, ISR_NAKED)
{
asm volatile(
/* save registers 2+1+2+2+2 = 9 */
"push r24 \n\t"
"in r24, __SREG__ \n\t"
"push r24 \n\t"
"push r30 \n\t"
"push r31 \n\t"
::
);
asm volatile(
/* load table values 1+1+1+1+1+1+1+1+1 = 9 */
"movw r30, %0 \n\t"
"ld r24, z+ \n\t"
"out %1, r24 \n\t" /* PORTA = *pCurrentStep++; */
"ld r24, z+ \n\t"
"out %2, r24 \n\t" /* PORTC = *pCurrentStep++; */
"ld r24, z+ \n\t"
"out %3, r24 \n\t" /* OCR0 = *pCurrentStep++; */
"ld r24, z+ \n\t"
"movw %0, r30 \n\t"
:: "r" (pCurrentStep),
"I" (_SFR_IO_ADDR(PORTA)),
"I" (_SFR_IO_ADDR(PORTC)),
"I" (_SFR_IO_ADDR(OCR0))
);
asm volatile(
/* check if IRQ must be disabled 1+1+1+1+1 = 3/5 */
"or r24, r24 \n\t" /* if (!(*pCurrentStep++)) { */
"brne L_skip%= \n\t"
"in r24, %0 \n\t" /* TIMSK &= ~(1<<OCIE0); */
"andi r24, %1 \n\t"
"out %0, r24 \n\t"
"L_skip%=: \n\t" /* } */
:: "I" (_SFR_IO_ADDR(TIMSK)),
"M" (0xFD) /* ~(1<<OCIE0) */
);
asm volatile(
/* restore registers 2+2+2+1+2+4 = 13 */
"pop r31 \n\t"
"pop r30 \n\t"
"pop r24 \n\t"
"out __SREG__, r24 \n\t"
"pop r24 \n\t"
"reti \n\t"
::
);
}
/* calc chan_valueX => chan_rawdataX */
static void calculate_timer_values(uint8_t *value, uint8_t *pDataStart)
{
uint8_t *pData = pDataStart +4; /* skip first entry (init) */
uint8_t index = 0;
uint16_t chan_used = 0xFFFF;
uint16_t chan_init = 0xFFFF;
/* loop until all channels are calculated */
while (chan_used) {
uint8_t i;
uint8_t min_value = 0xFF;
uint16_t chan_tmp = chan_used;
uint16_t chan_mask = 0x0001;
for (i = 0; i < 16; i++) {
/* skip if channel already used */
if (chan_used & chan_mask)
{
/* channel is not used (value 0x00) */
if (value[i] == 0x00) {
chan_init &= (~chan_mask);
chan_used &= (~chan_mask);
/* found a new lower value */
} else if (value[i] < min_value) {
min_value = value[i];
chan_tmp = chan_used & (~chan_mask);
/* found another value with the same value */
} else if (value[i] == min_value) {
chan_tmp &= (~chan_mask);
}
}
chan_mask <<= 1;
}
chan_used &= chan_tmp;
if (min_value < 0xFF) {
/* set new outputs */
*pData++ = (chan_used & 0xFF); /* PORTA */
*pData++ = ((chan_used >> 8) & 0xFF); /* PORTC */
/* previous step needs timervalue and enable IRQ */
*(pData++ -4) = min_value; /* OCR0 */
*(pData++ -4) = 0x01; /* flags */
}
index++;
}
/* fill all remaining slots */
while (index < 16) {
/* repeat enabled outputs */
*pData++ = (chan_used & 0xFF); /* PORTA */
*pData++ = ((chan_used >> 8) & 0xFF); /* PORTC */
/* previous step was last one (no timevalue / disable IRQ) */
*(pData++ -4) = 0x00; /* OCR0 */
*(pData++ -4) = 0x00; /* flags */
index++;
}
/* first slot/init: enable only channels that are > 0 */
pData = pDataStart;
*pData++ = (chan_init & 0xFF); /* PORTA */
*pData++ = ((chan_init >> 8) & 0xFF); /* PORTC */
}
static uint8_t rx_cmd;
static uint16_t rx_bcnt = 0xFF;
static uint16_t rx_length;
static uint8_t tx_cmd;
static uint8_t tx_cause;
static uint16_t tx_length;
static uint16_t tx_bcnt;
ISR(USART_RXC_vect)
{
uint8_t data = UDR;
sei();
if (rx_bcnt == 0xFF) {
/* MPM address stored in TWI address register by bootloader */
if (data == TWAR) {
UCSRA &= ~(1<<MPCM);
rx_bcnt = 0;
}
} else {
if (rx_bcnt == 0) {
rx_cmd = data;
} else if ((rx_bcnt == 1) || (rx_bcnt == 2)) {
rx_length = (rx_length << 8) | data;
} else if ((rx_bcnt -3) < rx_length) {
// TODO: get data
}
if ((rx_bcnt -2) == rx_length) {
/* enable RS485 TX */
PORTD |= (1<<RXTX);
/* first byte */
tx_cmd = rx_cmd;
UDR = rx_cmd;
/* prepare header */
tx_bcnt = 1;
tx_cause = 0;
tx_length = 0;
if (tx_cmd == CMD_GET_VERSION) {
tx_length = sizeof(versioninfo);
}
/* enable interrupt */
UCSRB |= (1<<UDRIE);
}
rx_bcnt++;
}
}
ISR(USART_UDRE_vect)
{
/* enable IRQs again, but prevent multiple UDRE IRQs */
UCSRB &= ~(1<<UDRIE);
sei();
if ((tx_bcnt < 4) || (tx_bcnt -4) < tx_length) {
uint16_t pos = (tx_bcnt -4);
uint8_t data = 0xFF;
if (tx_bcnt == 1) {
data = tx_cause;
} else if (tx_bcnt == 2) {
data = (tx_length >> 8);
} else if (tx_bcnt == 3) {
data = (tx_length & 0xFF);
} else if (tx_cmd == CMD_GET_VERSION) {
data = versioninfo[pos];
} else {
data = 0xAA;
}
UDR = data;
/* re-enable for next round */
UCSRB |= (1<<UDRIE);
}
tx_bcnt++;
}
ISR(USART_TXC_vect, ISR_NOBLOCK)
{
/* disable RS485 TX */
PORTD &= ~(1<<RXTX);
/* enable MP mode again */
UCSRA |= (1<<MPCM);
rx_bcnt = 0xFF; // FIXME: cli?
#if !(STANDALONE)
if (tx_cmd == CMD_SWITCH_MODE) { // FIXME: check mode
wdt_enable(WDTO_15MS);
}
#endif /* !(STANDALONE) */
}
int main(void) __attribute__ ((noreturn));
int main(void)
{
/* 16 PWM Outputs */
PORTA = 0x00;
DDRA = 0xFF;
PORTC = 0x00;
DDRC = 0xFF;
/* color ROWs */
PORTB = 0x00;
DDRB = (1<<ROW1) | (1<<ROW2) | (1<<ROW3) | (1<<ROW4);
DDRD = (1<<LED);
PORTD = (1<<LED);
DDRD = (1<<RXTX) | (1<<LED);
#if (STANDALONE)
OSCCAL = OSCCAL_VALUE;
#endif /* (STANDALONE) */
/* timer0, FCPU/64, overflow interrupt */
TCCR0 = (1<<CS01) | (1<<CS00); /* FCPU/64 */
TIMSK = (1<<TOIE0);
TCNT0 = 0x00;
/* USART config */
/* Multi Drop Mode, 9n1 */
UCSRA = (1<<MPCM);
UCSRB = (1<<RXEN) | (1<<TXEN) | (1<<RXCIE) | (1<<TXCIE) | (1<<UCSZ2);
UCSRC = (1<<URSEL) | (1<<UCSZ1) | (1<<UCSZ0);
#if (STANDALONE)
UBRRH = (UART_CALC_BAUDRATE(BAUDRATE)>>8) & 0xFF;
UBRRL = (UART_CALC_BAUDRATE(BAUDRATE) & 0xFF);
/* MPM address stored in TWI address register */
TWAR = MPM_ADDRESS;
#endif /* (STANDALONE) */
eeprom_read();
rgb_init();
mpm_init();
sei();
@ -467,36 +58,12 @@ int main(void)
uint16_t ramp = 0;
uint8_t step = 0;
#if 0
/* create worst case for R+G, relaxed for B */
for (x = 0; x < 16; x++) {
chan_value[0][x] = 254 - x;
chan_value[1][x] = x +1;
chan_value[2][x] = x * 16;
}
x = 0;
#endif
while (1) {
uint8_t color_update = 0x07;
while (color_update) {
if ((color_update & 0x01) && (nextColor == 2)) {
calculate_timer_values(chan_value[0], chan_rawdata[0]);
color_update &= ~(0x01);
/* wait for complete update */
rgb_update(COLOR_MASK, 1);
} else if ((color_update & 0x02) && (nextColor == 0)) {
calculate_timer_values(chan_value[1], chan_rawdata[1]);
color_update &= ~(0x02);
} else if ((color_update & 0x04) && (nextColor == 1)) {
calculate_timer_values(chan_value[2], chan_rawdata[2]);
color_update &= ~(0x04);
}
}
#if 1
PORTD ^= (1<<LED);
// _delay_ms(100);
step++;
@ -567,7 +134,7 @@ int main(void)
uint8_t i, j;
for (i = 0; i < 16; i++) {
for (j = 0; j < 3; j++) {
#if 0
#if 1
if (x == i) {
chan_value[j][i] = color[j];

169
mpmctrl.c Normal file
View File

@ -0,0 +1,169 @@
/***************************************************************************
* mpm comms *
* *
* Copyright (C) 2011 - 2012 by Olaf Rempel *
* razzor AT kopf MINUS tisch DOT de *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; version 2 of the License, *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
***************************************************************************/
#include <avr/io.h>
#include <avr/interrupt.h>
#include <avr/wdt.h>
#include "rgb16mpm.h"
#define CMD_WAIT 0x00
#define CMD_SWITCH_MODE 0x01
#define CMD_GET_VERSION 0x02
#define CMD_GET_CHIPINFO 0x03 /* bootloader / mpmboot */
#define CMD_READ_MEMORY 0x11 /* bootloader / mpmboot */
#define CMD_WRITE_MEMORY 0x12 /* bootloader / mpmboot */
#define CMD_WRITE_COLOR 0x81
#define CMD_WRITE_RAW_COLOR 0x82
#define CMD_READ_RAW_COLOR 0x83
#define CMD_WRITE_CONFIG 0x81
#define UART_CALC_BAUDRATE(baudRate) (((uint32_t)F_CPU) / (((uint32_t)baudRate)*16) -1)
const static uint8_t versioninfo[16] = "rgb16mpm v0.99";
static uint8_t rx_cmd;
static uint16_t rx_bcnt = 0xFF;
static uint16_t rx_length;
static uint8_t tx_cmd;
static uint8_t tx_cause;
static uint16_t tx_length;
static uint16_t tx_bcnt;
ISR(USART_RXC_vect)
{
uint8_t data = UDR;
sei();
if (rx_bcnt == 0xFF) {
/* MPM address stored in TWI address register by bootloader */
if (data == TWAR) {
UCSRA &= ~(1<<MPCM);
rx_bcnt = 0;
}
} else {
if (rx_bcnt == 0) {
rx_cmd = data;
} else if ((rx_bcnt == 1) || (rx_bcnt == 2)) {
rx_length = (rx_length << 8) | data;
} else if ((rx_bcnt -3) < rx_length) {
// TODO: get data
}
if ((rx_bcnt -2) == rx_length) {
/* enable RS485 TX */
PORTD |= (1<<RXTX);
/* first byte */
tx_cmd = rx_cmd;
UDR = rx_cmd;
/* prepare header */
tx_bcnt = 1;
tx_cause = 0;
tx_length = 0;
if (tx_cmd == CMD_GET_VERSION) {
tx_length = sizeof(versioninfo);
}
/* enable interrupt */
UCSRB |= (1<<UDRIE);
}
rx_bcnt++;
}
}
ISR(USART_UDRE_vect)
{
/* enable IRQs again, but prevent multiple UDRE IRQs */
UCSRB &= ~(1<<UDRIE);
sei();
if ((tx_bcnt < 4) || (tx_bcnt -4) < tx_length) {
uint16_t pos = (tx_bcnt -4);
uint8_t data = 0xFF;
if (tx_bcnt == 1) {
data = tx_cause;
} else if (tx_bcnt == 2) {
data = (tx_length >> 8);
} else if (tx_bcnt == 3) {
data = (tx_length & 0xFF);
} else if (tx_cmd == CMD_GET_VERSION) {
data = versioninfo[pos];
} else {
data = 0xAA;
}
UDR = data;
/* re-enable for next round */
UCSRB |= (1<<UDRIE);
}
tx_bcnt++;
}
ISR(USART_TXC_vect, ISR_NOBLOCK)
{
/* disable RS485 TX */
PORTD &= ~(1<<RXTX);
/* enable MP mode again */
UCSRA |= (1<<MPCM);
rx_bcnt = 0xFF; // FIXME: cli?
#if !(STANDALONE)
if (tx_cmd == CMD_SWITCH_MODE) { // FIXME: check mode
wdt_enable(WDTO_15MS);
}
#endif /* !(STANDALONE) */
}
void mpm_init(void)
{
PORTD &= ~(1<<RXTX);
DDRD |= (1<<RXTX);
/* USART config */
/* Multi Drop Mode, 9n1 */
UCSRA = (1<<MPCM);
UCSRB = (1<<RXEN) | (1<<TXEN) | (1<<RXCIE) | (1<<TXCIE) | (1<<UCSZ2);
UCSRC = (1<<URSEL) | (1<<UCSZ1) | (1<<UCSZ0);
#if (STANDALONE)
OSCCAL = OSCCAL_VALUE;
UBRRH = (UART_CALC_BAUDRATE(BAUDRATE)>>8) & 0xFF;
UBRRL = (UART_CALC_BAUDRATE(BAUDRATE) & 0xFF);
/* MPM address stored in TWI address register */
TWAR = MPM_ADDRESS;
#endif /* (STANDALONE) */
}

58
rgb16mpm.h Normal file
View File

@ -0,0 +1,58 @@
#ifndef _RGB16MPM_H_
#define _RGB16MPM_H_
#define F_CPU 8000000
#include <util/delay.h>
#define ROW1 PORTB1 /* RED */
#define ROW2 PORTB0 /* GREEN */
#define ROW3 PORTB3 /* BLUE */
#define ROW4 PORTB2 /* not used */
#define RXTX PORTD2 /* RS485 TX enable */
#define LED PORTD3
/* running without mpmboot? */
#define STANDALONE 0
#if (STANDALONE)
#define OSCCAL 0xAA
#define BAUDRATE 115200
#define MPM_ADDRESS 0x11
#endif /* STANDALONE */
#define COLOR_RED 0
#define COLOR_GREEN 1
#define COLOR_BLUE 2
#define COLOR_MASK ((1<<COLOR_RED) | (1<<COLOR_GREEN) | (1<<COLOR_BLUE))
struct _nvdata {
uint16_t nvram_size; /* first */
uint8_t initialRGB[3][16]; /* initial color values */
uint16_t nvram_crc; /* last */
};
#define NVRAM_DEFAULTS {\
.initialRGB = { { 0xFF, 0xFF, 0xFF, 0x80, 0x00, 0x00, 0x00, 0x00, 0x00, 0x80, 0xFF, 0xFF, 0x20, 0x40, 0x80, 0xFF, }, \
{ 0x00, 0x80, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x80, 0x00, 0x00, 0x00, 0x00, 0x20, 0x40, 0x80, 0xFF, }, \
{ 0x00, 0x00, 0x00, 0x00, 0x00, 0x80, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x80, 0x20, 0x40, 0x80, 0xFF, } }, \
};
/* eeprom.c vars */
extern struct _nvdata nvram_data;
/* eeprom.c funcs */
void eeprom_write(void);
void eeprom_read(void);
/* mpmctrl.c funcs */
void mpm_init(void);
/* rgbctrl.c vars */
extern uint8_t chan_value[3][16];
/* rgbctrl.c funcs */
void rgb_init(void);
uint8_t rgb_update(uint8_t dirty_mask, uint8_t blocking);
#endif /* _RGB16MPM_H_ */

313
rgbctrl.c Normal file
View File

@ -0,0 +1,313 @@
/***************************************************************************
* nvram parameter read/write *
* *
* Copyright (C) 2011 - 2012 by Olaf Rempel *
* razzor AT kopf MINUS tisch DOT de *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; version 2 of the License, *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
***************************************************************************/
#include <avr/io.h>
#include <avr/interrupt.h>
#include <string.h>
#include "rgb16mpm.h"
/* 16 values per color */
uint8_t chan_value[3][16];
/* (16 +1) * 4 values (portA, portC, OCR0, flags) per color */
static uint8_t chan_rawdata[3][17 * 4];
/* used only in softpwm ISRs */
register uint8_t * pCurrentStep asm("r2"); /* r3:r2 */
/* used to sync softpwm ISRs and color_update() */
register uint8_t nextColor asm("r4"); /* r4 */
/* worst case: 9+2+12+8+7+13 = 61 clks -> 7.625us @8MHz */
ISR(TIMER0_OVF_vect, ISR_NAKED)
{
asm volatile(
/* save registers 2+1+2+2+2 = 9 */
"push r24 \n\t"
"in r24, __SREG__ \n\t"
"push r24 \n\t"
"push r30 \n\t"
"push r31 \n\t"
::
);
asm volatile(
/* disable outputs 1+1 = 2 */
"out %0, r1 \n\t" /* PORTA = 0x00; */
"out %1, r1 \n\t" /* PORTC = 0x00; */
:: "I" (_SFR_IO_ADDR(PORTA)),
"I" (_SFR_IO_ADDR(PORTC))
);
asm volatile(
/* switch color and assign pCurrentStep */ // R G B
"mov r24, %0 \n\t" // 1 1 1
"inc %0 \n\t" /* nextColor++ */ // 2 2 2
"cpi r24, 1 \n\t" // 3 3 3
"brlo L_red%= \n\t" /* if (nextColor < 1) -> red */ // 5 4 4
"breq L_green%= \n\t" /* if (nextColor == 1) -> green */ // - 6 5
"clr %0 \n\t" /* nextColor = 0; */ // - - 6
"ldi r24, %7 \n\t" /* PORTB = (1<<ROW4); */ // - - 7
"ldi r30, lo8(%3) \n\t" /* pCurrentStep = &rawdata[2]; */ // - - 8
"ldi r31, hi8(%3) \n\t" // - - 9
"rjmp L_end%= \n\t" // - - 11
"L_red%=: \n\t" /* red: */
"ldi r24, %5 \n\t" /* PORTB = (1<<ROW1); */ // 6 - -
"ldi r30, lo8(%1) \n\t" /* pCurrentStep = &rawdata[0]; */ // 7 - -
"ldi r31, hi8(%1) \n\t" // 8 - -
"rjmp L_end%= \n\t" // 10 - -
"L_green%=: \n\t" /* green: */
"ldi r24, %6 \n\t" /* PORTB = (1<<ROW2); */ // - 7 -
"ldi r30, lo8(%2) \n\t" /* pCurrentStep = &rawdata[1]; */ // - 8 -
"ldi r31, hi8(%2) \n\t" // - 9 -
"L_end%=: \n\t"
"out %4, r24 \n\t" /* set PORTB */ // 11 10 12
:: "r" (nextColor),
"i" (&chan_rawdata[0]), /* RED */
"i" (&chan_rawdata[1]), /* GREEN */
"i" (&chan_rawdata[2]), /* BLUE */
"I" (_SFR_IO_ADDR(PORTB)),
"i" ((1<<ROW1)), /* RED */
"i" ((1<<ROW2)), /* GREEN */
"i" ((1<<ROW3)) /* BLUE */
);
asm volatile(
/* load table values 1+1+1+1+1+1+1+1+1 = 8 */
"ld r24, z+ \n\t"
"out %1, r24 \n\t" /* PORTA = *pCurrentStep++; */
"ld r24, z+ \n\t"
"out %2, r24 \n\t" /* PORTC = *pCurrentStep++; */
"ld r24, z+ \n\t"
"out %3, r24 \n\t" /* OCR0 = *pCurrentStep++; */
"ld r24, z+ \n\t"
"movw %0, r30 \n\t"
:: "r" (pCurrentStep),
"I" (_SFR_IO_ADDR(PORTA)),
"I" (_SFR_IO_ADDR(PORTC)),
"I" (_SFR_IO_ADDR(OCR0))
);
asm volatile(
/* check if IRQ must be enabled 1+1+1+1+1+1+1 = 3/7 */
"or r24, r24 \n\t" /* if (*pCurrentStep++) { */
"breq L_skip%= \n\t"
"ldi r24, %1 \n\t" /* TIFR = (1<<OCF0); */
"out %0, r24 \n\t"
"in r24, %2 \n\t" /* TIMSK |= (1<<OCIE0); */
"ori r24, %3 \n\t"
"out %2, r24 \n\t"
"L_skip%=: \n\t" /* } */
:: "I" (_SFR_IO_ADDR(TIFR)),
"M" ((1<<OCF0)),
"I" (_SFR_IO_ADDR(TIMSK)),
"M" ((1<<OCIE0))
);
asm volatile(
/* restore registers 2+2+2+1+2+4 = 13 */
"pop r31 \n\t"
"pop r30 \n\t"
"pop r24 \n\t"
"out __SREG__, r24 \n\t"
"pop r24 \n\t"
"reti \n\t"
::
);
}
/* worst case: 9+9+5+13 = 36 clks -> 4.5us @ 8MHz */
ISR(TIMER0_COMP_vect, ISR_NAKED)
{
asm volatile(
/* save registers 2+1+2+2+2 = 9 */
"push r24 \n\t"
"in r24, __SREG__ \n\t"
"push r24 \n\t"
"push r30 \n\t"
"push r31 \n\t"
::
);
asm volatile(
/* load table values 1+1+1+1+1+1+1+1+1 = 9 */
"movw r30, %0 \n\t"
"ld r24, z+ \n\t"
"out %1, r24 \n\t" /* PORTA = *pCurrentStep++; */
"ld r24, z+ \n\t"
"out %2, r24 \n\t" /* PORTC = *pCurrentStep++; */
"ld r24, z+ \n\t"
"out %3, r24 \n\t" /* OCR0 = *pCurrentStep++; */
"ld r24, z+ \n\t"
"movw %0, r30 \n\t"
:: "r" (pCurrentStep),
"I" (_SFR_IO_ADDR(PORTA)),
"I" (_SFR_IO_ADDR(PORTC)),
"I" (_SFR_IO_ADDR(OCR0))
);
asm volatile(
/* check if IRQ must be disabled 1+1+1+1+1 = 3/5 */
"or r24, r24 \n\t" /* if (!(*pCurrentStep++)) { */
"brne L_skip%= \n\t"
"in r24, %0 \n\t" /* TIMSK &= ~(1<<OCIE0); */
"andi r24, %1 \n\t"
"out %0, r24 \n\t"
"L_skip%=: \n\t" /* } */
:: "I" (_SFR_IO_ADDR(TIMSK)),
"M" (0xFD) /* ~(1<<OCIE0) */
);
asm volatile(
/* restore registers 2+2+2+1+2+4 = 13 */
"pop r31 \n\t"
"pop r30 \n\t"
"pop r24 \n\t"
"out __SREG__, r24 \n\t"
"pop r24 \n\t"
"reti \n\t"
::
);
}
/* calc chan_valueX => chan_rawdataX */
static void calculate_timer_values(uint8_t *value, uint8_t *pDataStart)
{
uint8_t *pData = pDataStart +4; /* skip first entry (init) */
uint8_t index = 0;
uint16_t chan_used = 0xFFFF;
uint16_t chan_init = 0xFFFF;
/* loop until all channels are calculated */
while (chan_used) {
uint8_t i;
uint8_t min_value = 0xFF;
uint16_t chan_tmp = chan_used;
uint16_t chan_mask = 0x0001;
for (i = 0; i < 16; i++) {
/* skip if channel already used */
if (chan_used & chan_mask)
{
/* channel is not used (value 0x00) */
if (value[i] == 0x00) {
chan_init &= (~chan_mask);
chan_used &= (~chan_mask);
/* found a new lower value */
} else if (value[i] < min_value) {
min_value = value[i];
chan_tmp = chan_used & (~chan_mask);
/* found another value with the same value */
} else if (value[i] == min_value) {
chan_tmp &= (~chan_mask);
}
}
chan_mask <<= 1;
}
chan_used &= chan_tmp;
if (min_value < 0xFF) {
/* set new outputs */
*pData++ = (chan_used & 0xFF); /* PORTA */
*pData++ = ((chan_used >> 8) & 0xFF); /* PORTC */
/* previous step needs timervalue and enable IRQ */
*(pData++ -4) = min_value; /* OCR0 */
*(pData++ -4) = 0x01; /* flags */
}
index++;
}
/* fill all remaining slots */
while (index < 16) {
/* repeat enabled outputs */
*pData++ = (chan_used & 0xFF); /* PORTA */
*pData++ = ((chan_used >> 8) & 0xFF); /* PORTC */
/* previous step was last one (no timevalue / disable IRQ) */
*(pData++ -4) = 0x00; /* OCR0 */
*(pData++ -4) = 0x00; /* flags */
index++;
}
/* first slot/init: enable only channels that are > 0 */
pData = pDataStart;
*pData++ = (chan_init & 0xFF); /* PORTA */
*pData++ = ((chan_init >> 8) & 0xFF); /* PORTC */
}
uint8_t rgb_update(uint8_t dirty_mask, uint8_t blocking)
{
static uint8_t chan_dirty;
chan_dirty |= (dirty_mask & COLOR_MASK);
do {
if ((chan_dirty & (1<<COLOR_RED)) && (nextColor == COLOR_BLUE)) {
calculate_timer_values(chan_value[COLOR_RED], chan_rawdata[COLOR_RED]);
chan_dirty &= ~(1<<COLOR_RED);
} else if ((chan_dirty & (1<<COLOR_GREEN)) && (nextColor == COLOR_RED)) {
calculate_timer_values(chan_value[COLOR_GREEN], chan_rawdata[COLOR_GREEN]);
chan_dirty &= ~(1<<COLOR_GREEN);
} else if ((chan_dirty & (1<<COLOR_BLUE)) && (nextColor == COLOR_GREEN)) {
calculate_timer_values(chan_value[COLOR_BLUE], chan_rawdata[COLOR_BLUE]);
chan_dirty &= ~(1<<COLOR_BLUE);
} else if (!blocking) {
break;
}
} while (chan_dirty);
return chan_dirty;
}
void rgb_init(void)
{
/* 16 PWM Outputs */
PORTA = 0x00;
DDRA = 0xFF;
PORTC = 0x00;
DDRC = 0xFF;
/* color ROWs */
PORTB &= ~((1<<ROW1) | (1<<ROW2) | (1<<ROW3) | (1<<ROW4));
DDRB |= (1<<ROW1) | (1<<ROW2) | (1<<ROW3) | (1<<ROW4);
/* timer0, FCPU/64, overflow interrupt */
TCCR0 = (1<<CS01) | (1<<CS00); /* FCPU/64 */
TIMSK = (1<<TOIE0);
/* load initial values from eeprom */
memcpy(chan_value, nvram_data.initialRGB, sizeof(chan_value));
}