From: Mikko Rasa Date: Mon, 13 May 2013 17:18:01 +0000 (+0300) Subject: Reorganize the directory structure X-Git-Url: http://git.tdb.fi/?p=model-railway-devices.git;a=commitdiff_plain;h=9c37d18b9c70fdb70dfec453398c4649e9e57586 Reorganize the directory structure These were forked off the r2c2 repo since especially the s88w stuff is not tied to it. --- diff --git a/.gitignore b/.gitignore new file mode 100644 index 0000000..d6c2e45 --- /dev/null +++ b/.gitignore @@ -0,0 +1,2 @@ +*.elf +*.hex diff --git a/common/build.mk b/common/build.mk new file mode 100644 index 0000000..96d0f93 --- /dev/null +++ b/common/build.mk @@ -0,0 +1,42 @@ +MCU := atmega328p +CLOCK := 16000000 +CC := avr-gcc +CFLAGS := -Wall -Os -ffunction-sections -fdata-sections -mmcu=$(MCU) -DF_CPU=$(CLOCK) $(patsubst %,-D%,$(FEATURES)) -I../common +LDFLAGS := -Os -Wl,--gc-sections -mmcu=$(MCU) +AVRDUDE := avrdude +OBJCOPY := avr-objcopy +ifeq ($(MCU),atmega168) +BAUD := 19200 +else +BAUD := 57600 +endif + +VPATH := ../common + +help: + @echo "Targets:" + @echo " %.hex: Build firmware from %.c" + @echo " upload-%: Upload firmware to AVR" + @echo " clean: Clean all built files" + @echo + @echo "Variables:" + @echo " MCU: Microcontroller type" + @echo " Arduino Duemilanove = atmega328p (default)" + @echo " Arduino Mini = atmega168" + +%.hex: %.elf + $(OBJCOPY) -O ihex $< $@ + +%.elf: %.o + $(CC) $(LDFLAGS) -o $@ $^ + +%.o: %.c + $(CC) -c $(CFLAGS) -o $@ $< + +upload-%: %.hex + $(AVRDUDE) -p$(MCU) -carduino -P/dev/ttyUSB0 -b$(BAUD) -D -Uflash:w:$<:i + +clean: + $(RM) *.hex + $(RM) *.elf + $(RM) *.o diff --git a/common/delay.h b/common/delay.h new file mode 100644 index 0000000..725d22b --- /dev/null +++ b/common/delay.h @@ -0,0 +1,45 @@ +#ifndef DELAY_H_ +#define DELAY_H_ + +static inline void __attribute__((always_inline)) delay_loop8(uint8_t count) +{ + __asm__ volatile ( + "1: dec %0" "\n\t" + "brne 1b" + : "=r" (count) + : "0" (count) + ); +} + +static inline void __attribute__((always_inline)) delay_loop16(uint16_t count) +{ + __asm__ volatile ( + "1: sbiw %0, 1" "\n\t" + "brne 1b" + : "=r" (count) + : "0" (count) + ); +} + +static inline void __attribute__((always_inline)) delay_us(uint16_t us) +{ + uint16_t clocks = F_CPU/1000000*us; + if(clocks<768) + delay_loop8(clocks/3); + else + delay_loop16(clocks/4); +} + +static inline void __attribute__((always_inline)) delay_ms(uint16_t ms) +{ + if(ms<0x40000/(F_CPU/1000)) + delay_loop16(F_CPU/1000*ms/4); + else + { + uint16_t i = ms*10; + while(--i) + delay_loop16(F_CPU/40000); + } +} + +#endif diff --git a/common/eeprom.c b/common/eeprom.c new file mode 100644 index 0000000..9027ed0 --- /dev/null +++ b/common/eeprom.c @@ -0,0 +1,29 @@ +#include +#include "eeprom.h" + +#define BIT(n) (1<<(n)) + +static void eeprom_wait(void) +{ + while(EECR&BIT(EEPE)) ; +} + +void eeprom_write(uint16_t addr, uint8_t data) +{ + eeprom_wait(); + EEARH = addr>>8; + EEARL = addr; + EEDR = data; + EECR = BIT(EEMPE); + EECR |= BIT(EEPE); + eeprom_wait(); +} + +uint8_t eeprom_read(uint16_t addr) +{ + eeprom_wait(); + EEARH = addr>>8; + EEARL = addr; + EECR = BIT(EERE); + return EEDR; +} diff --git a/common/eeprom.h b/common/eeprom.h new file mode 100644 index 0000000..903ce96 --- /dev/null +++ b/common/eeprom.h @@ -0,0 +1,7 @@ +#ifndef EEPROM_H_ +#define EEPROM_H_ + +void eeprom_write(uint16_t, uint8_t); +uint8_t eeprom_read(uint16_t); + +#endif diff --git a/common/lcd.c b/common/lcd.c new file mode 100644 index 0000000..f4e0387 --- /dev/null +++ b/common/lcd.c @@ -0,0 +1,208 @@ +/* +ATMega pinout (with LCD_SHIFTREG): +B0 - HD44780 RS +B1 - HD44780 clock +B2 - shift reg data +B3 - shift reg clock + +ATMega pinout (without LCD_SHIFTREG): +D4 - HD44780 RS +D5 - HD44780 clock +D6 - HD44780 data 0 +D7 - HD44780 data 1 +B0 - HD44780 data 2 +B1 - HD44780 data 3 +B2 - HD44780 data 4 +B3 - HD44780 data 5 +B4 - HD44780 data 6 +B5 - HD44780 data 7 + +In both cases, HD44780 R/W needs to be connected to ground. +*/ +#include +#include "delay.h" +#include "lcd.h" +#include "timer.h" + +#ifdef LCD_SHIFTREG +#define CLOCK_PORT PORTB +#define CLOCK_BIT 0x02 +#define REGSEL_PORT PORTB +#define REGSEL_BIT 0x01 +#else +#define CLOCK_PORT PORTD +#define CLOCK_BIT 0x20 +#define REGSEL_PORT PORTD +#define REGSEL_BIT 0x10 +#endif + +#ifndef LCD_BUFSIZE +#define LCD_BUFSIZE 32 +#endif + +#define NOP() __asm__("nop") + +#ifdef LCD_ASYNC +static volatile uint8_t lcd_busy = 0; +static uint8_t lcd_buffer[LCD_BUFSIZE]; +static volatile uint8_t lcd_buf_head = 0; +static volatile uint8_t lcd_buf_tail = 0; +#endif + +static void lcd_clock(void) +{ + delay_us(1); + CLOCK_PORT |= CLOCK_BIT; + delay_us(1); + CLOCK_PORT &= ~CLOCK_BIT; +} + +static void lcd_set_data(uint8_t d) +{ +#ifdef LCD_SHIFTREG + uint8_t i; + for(i=0; i<8; ++i) + { + PORTB = (PORTB&~0x04)|((d&1)<<2); + PORTB |= 0x08; + NOP(); + PORTB &= ~0x08; + d >>= 1; + } +#else + PORTD = (PORTD&0x3F) | (d<<6); + PORTB = (PORTB&0xC0) | (d>>2); +#endif +} + +static void lcd_command(uint8_t c) +{ + REGSEL_PORT &= ~REGSEL_BIT; + lcd_set_data(c); + lcd_clock(); +} + +static void lcd_delay(uint16_t us) +{ +#ifdef LCD_ASYNC + lcd_busy = 1; + timer_start_us(0, us); +#else + delay_us(us); +#endif +} + +#ifdef LCD_ASYNC +static void lcd_wait(void) +{ + while(lcd_busy) ; +} + +static void lcd_buffer_push(uint8_t byte) +{ + while((lcd_buf_head+1)%sizeof(lcd_buffer)==lcd_buf_tail) ; + lcd_buffer[lcd_buf_head] = byte; + lcd_buf_head = (lcd_buf_head+1)%sizeof(lcd_buffer); +} + +static uint8_t lcd_buffer_pop(void) +{ + uint8_t byte = lcd_buffer[lcd_buf_tail]; + lcd_buf_tail = (lcd_buf_tail+1)%sizeof(lcd_buffer); + return byte; +} + +static void lcd_timer(void) +{ + if(lcd_busy) + { + if(lcd_buf_head!=lcd_buf_tail) + { + uint8_t byte = lcd_buffer_pop(); + if(byte==0xFF) + { + REGSEL_PORT |= REGSEL_BIT; + byte = lcd_buffer_pop(); + } + else if(byte>=0x80) + REGSEL_PORT &= ~REGSEL_BIT; + else + REGSEL_PORT |= REGSEL_BIT; + lcd_set_data(byte); + lcd_clock(); + lcd_delay(50); + } + else + { + lcd_busy = 0; + timer_stop(0); + } + } +} + +TIMER_SET_CALLBACK(0, lcd_timer) +#endif + +void lcd_init(void) +{ +#ifdef LCD_SHIFTREG + DDRB |= 0x0F; + PORTB &= ~0x0F; +#else + DDRD |= 0xF0; + PORTD &= ~0xF0; + DDRB |= 0x3F; + PORTB &= ~0x3F; +#endif + + delay_ms(20); + lcd_command(0x38); + delay_us(50); + lcd_command(0x0C); + delay_us(50); +} + +void lcd_clear(void) +{ +#ifdef LCD_ASYNC + lcd_wait(); +#endif + lcd_command(0x01); + lcd_delay(1700); +} + +void lcd_gotoxy(uint8_t x, uint8_t y) +{ + uint8_t a = x+10*y; + if(y&1) + a += 54; + +#ifdef LCD_ASYNC + if(lcd_busy) + { + lcd_buffer_push(a|0x80); + return; + } +#endif + + lcd_command(a|0x80); + lcd_delay(50); +} + +void lcd_write(uint8_t c) +{ +#ifdef LCD_ASYNC + if(lcd_busy) + { + if(c>=0x80) + lcd_buffer_push(0xFF); + lcd_buffer_push(c); + return; + } +#endif + + REGSEL_PORT |= REGSEL_BIT; + lcd_set_data(c); + lcd_clock(); + lcd_delay(50); +} diff --git a/common/lcd.h b/common/lcd.h new file mode 100644 index 0000000..abb1017 --- /dev/null +++ b/common/lcd.h @@ -0,0 +1,9 @@ +#ifndef LCD_H_ +#define LCD_H_ + +void lcd_init(void); +void lcd_clear(void); +void lcd_gotoxy(uint8_t, uint8_t); +void lcd_write(uint8_t); + +#endif diff --git a/common/serial.c b/common/serial.c new file mode 100644 index 0000000..2bf6901 --- /dev/null +++ b/common/serial.c @@ -0,0 +1,22 @@ +#include +#include "serial.h" + +#define BIT(n) (1<<(n)) + +void serial_init(uint16_t baud) +{ + DDRD = (DDRD&~0x03) | 0x02; + PORTD &= ~0x03; + + baud = (F_CPU/16+baud/2)/baud-1; + UBRR0H = baud>>8; + UBRR0L = baud; + UCSR0C = BIT(UCSZ00) | BIT(UCSZ01); // 8N1 + UCSR0B = BIT(RXEN0) | BIT(TXEN0) | BIT(RXCIE0); +} + +void serial_write(uint8_t c) +{ + while(!(UCSR0A&(1< + +#define SERIAL_SET_CALLBACK(f) \ + ISR(USART_RX_vect) \ + { \ + char c = UDR0; \ + f(c); \ + } + +void serial_init(uint16_t); +void serial_write(uint8_t); + +#endif diff --git a/common/timer.c b/common/timer.c new file mode 100644 index 0000000..99625f8 --- /dev/null +++ b/common/timer.c @@ -0,0 +1,101 @@ +#include +#include "timer.h" + +#define BIT(n) (1<<(n)) + +static void timer_start(uint8_t num, uint32_t period) +{ + uint8_t cs; + + if(num==0) + { + if(period<0x100) + { + cs = BIT(CS00); + } + else if(period<0x800) + { + cs = BIT(CS01); + period /= 8; + } + else if(period<0x4000) + { + cs = BIT(CS01) | BIT(CS00); + period /= 64; + } + else if(period<0x10000) + { + cs = BIT(CS02); + period /= 256; + } + else + { + cs = BIT(CS02) | BIT(CS00); + period /= 1024; + if(period>0xFF) + period = 0xFF; + } + TCCR0A = BIT(WGM01); + TCCR0B = cs; + OCR0A = period; + TIMSK0 = BIT(OCIE0A); + } + if(num==1) + { + if(period<0x10000) + { + cs = BIT(CS10); + } + else if(period<0x80000) + { + cs = BIT(CS11); + period /= 8; + } + else if(period<0x400000) + { + cs = BIT(CS11) | BIT(CS10); + period /= 64; + } + else if(period<0x1000000) + { + cs = BIT(CS12); + period /= 256; + } + else + { + cs = BIT(CS12) | BIT(CS10); + period /= 1024; + if(period>0xFFFF) + period = 0xFFFF; + } + TCCR1A = 0; + TCCR1B = BIT(WGM12) | cs; + OCR1AH = period>>8; + OCR1AL = period; + TIMSK1 = BIT(OCIE1A); + } +} + +void timer_start_hz(uint8_t num, uint32_t freq_p, uint8_t freq_q) +{ + timer_start(num, F_CPU*freq_q/freq_p); +} + +void timer_start_us(uint8_t num, uint32_t us) +{ + timer_start(num, F_CPU/1000000*us); +} + +void timer_stop(uint8_t num) +{ + if(num==0) + { + TCCR0B = 0; + TIMSK0 = 0; + } + else if(num==1) + { + TCCR1B = 0; + TIMSK1 = 0; + } +} diff --git a/common/timer.h b/common/timer.h new file mode 100644 index 0000000..2869caa --- /dev/null +++ b/common/timer.h @@ -0,0 +1,16 @@ +#ifndef TIMER_H_ +#define TIMER_H_ + +#include + +#define TIMER_SET_CALLBACK(n, f) \ + ISR(TIMER ## n ## _COMPA_vect) \ + { \ + f(); \ + } + +void timer_start_hz(uint8_t, uint32_t, uint8_t); +void timer_start_us(uint8_t, uint32_t); +void timer_stop(uint8_t); + +#endif diff --git a/firmware/Makefile b/firmware/Makefile deleted file mode 100644 index b92db65..0000000 --- a/firmware/Makefile +++ /dev/null @@ -1,44 +0,0 @@ -MCU := atmega328p -CLOCK := 16000000 -CC := avr-gcc -FEATURES := LCD_SHIFTREG LCD_ASYNC -CFLAGS := -Wall -Os -ffunction-sections -fdata-sections -mmcu=$(MCU) -DF_CPU=$(CLOCK) $(patsubst %,-D%,$(FEATURES)) -LDFLAGS := -Os -Wl,--gc-sections -mmcu=$(MCU) -AVRDUDE := avrdude -OBJCOPY := avr-objcopy -ifeq ($(MCU),atmega168) -BAUD := 19200 -else -BAUD := 57600 -endif - -help: - @echo "Targets:" - @echo " %.hex: Build firmware from %.c" - @echo " upload-%: Upload firmware to AVR" - @echo " clean: Clean all built files" - @echo - @echo "Variables:" - @echo " MCU: Microcontroller type" - @echo " Arduino Duemilanove = atmega328p (default)" - @echo " Arduino Mini = atmega168" - -%.hex: %.elf - $(OBJCOPY) -O ihex $< $@ - -%.elf: %.o - $(CC) $(LDFLAGS) -o $@ $^ - -%.o: %.c - $(CC) -c $(CFLAGS) -o $@ $< - -upload-%: %.hex - $(AVRDUDE) -p$(MCU) -carduino -P/dev/ttyUSB0 -b$(BAUD) -D -Uflash:w:$<:i - -clean: - $(RM) *.hex - $(RM) *.elf - $(RM) *.o - -s88w-t.elf: serial.o timer.o eeprom.o -s88w-r.elf: serial.o lcd.o timer.o diff --git a/firmware/ctrl.c b/firmware/ctrl.c deleted file mode 100644 index 0ac212e..0000000 --- a/firmware/ctrl.c +++ /dev/null @@ -1,221 +0,0 @@ -#include -#include - -#define BIT(n) (1<<(n)) -#define NOP() __asm__("nop"); - -uint8_t digits[11] = -{ - 0x3F, - 0x06, - 0x5B, - 0x4F, - 0x66, - 0x6D, - 0x7D, - 0x07, - 0x7F, - 0x6F, - 0x40 -}; - -uint16_t read_input(void); -uint16_t read_input_filtered(void); -void write_serial(uint8_t); -void write_7seg(uint8_t); - -uint8_t speed = 0; -uint16_t funcs = 0; -volatile uint8_t ticks = 0; -volatile uint8_t rx_buf[3]; -volatile uint8_t rx_fill = 0; - -ISR(TIMER1_COMPA_vect) -{ - if(ticks<255) - ++ticks; -} - -ISR(USART_RX_vect) -{ - uint8_t c = UDR0; - if(rx_fill==0) - { - if(c=='A' || c=='S') - rx_buf[rx_fill++] = c; - } - else - { - rx_buf[rx_fill++] = c; - if(rx_buf[0]=='A' && rx_fill==3) - { - uint8_t n = (rx_buf[1]-'0')*10+(rx_buf[2]-'0'); - write_7seg(n/10); - write_7seg(n%10); - rx_fill = 0; - } - else if(rx_buf[0]=='S' && rx_fill==3) - { - speed = (rx_buf[1]-'0')*10+(rx_buf[2]-'0'); - rx_fill = 0; - } - } -} - -int main() -{ - uint16_t state = 0; - - DDRD = 0x02; // 00000010 - PORTD = 0xFC; // 11111100 - DDRB = 0x3F; // 00111111 - PORTB = 0x0F; // 00001111 - - write_7seg(10); - write_7seg(10); - - // 9600 baud, 8N1 - UBRR0H = 0; - UBRR0L = 103; - UCSR0C = BIT(UCSZ00) | BIT(UCSZ01); - UCSR0B = BIT(RXEN0) | BIT(TXEN0) | BIT(RXCIE0); - - TCCR1A = 0; - TCCR1B = BIT(WGM12) | BIT(CS12); - OCR1AH = 24; - OCR1AL = 106; - TIMSK1 = BIT(OCIE1A); - - sei(); - - while(1) - { - uint16_t toggled; - uint8_t i; - uint16_t input; - - input = read_input_filtered(); - input ^= 0xFFFC; - - toggled = state^input; - state = input; - - if((toggled&3)==2 && (state&1)) - { - uint8_t action = 0; - if(state&2) - { - if(speed<14) - { - ++speed; - action = 1; - } - } - else - { - if(speed>0) - { - --speed; - action = 1; - } - else if(ticks>10) - action = 2; - } - - if(action==1) - { - write_serial('S'); - write_serial('0'+speed/10); - write_serial('0'+speed%10); - } - else if(action==2) - write_serial('R'); - - ticks = 0; - } - - for(i=0; i<14; ++i) - { - uint16_t bit = 4<>2; - input |= pins&3; - input |= (pins&0x3C)<<(row*4); - } - - return input; -} - -uint16_t read_input_filtered(void) -{ - uint16_t valid = 0xFFFF; - uint16_t prev; - uint16_t input; - uint8_t i; - - prev = read_input(); - for(i=0; i<20; ++i) - { - input = read_input(); - valid &= ~(input^prev); - prev = input; - } - - return input&valid; -} - -void write_serial(uint8_t c) -{ - while(!(UCSR0A&(1< -#include "eeprom.h" - -#define BIT(n) (1<<(n)) - -static void eeprom_wait(void) -{ - while(EECR&BIT(EEPE)) ; -} - -void eeprom_write(uint16_t addr, uint8_t data) -{ - eeprom_wait(); - EEARH = addr>>8; - EEARL = addr; - EEDR = data; - EECR = BIT(EEMPE); - EECR |= BIT(EEPE); - eeprom_wait(); -} - -uint8_t eeprom_read(uint16_t addr) -{ - eeprom_wait(); - EEARH = addr>>8; - EEARL = addr; - EECR = BIT(EERE); - return EEDR; -} diff --git a/firmware/eeprom.h b/firmware/eeprom.h deleted file mode 100644 index 903ce96..0000000 --- a/firmware/eeprom.h +++ /dev/null @@ -1,7 +0,0 @@ -#ifndef EEPROM_H_ -#define EEPROM_H_ - -void eeprom_write(uint16_t, uint8_t); -uint8_t eeprom_read(uint16_t); - -#endif diff --git a/firmware/lcd.c b/firmware/lcd.c deleted file mode 100644 index f4e0387..0000000 --- a/firmware/lcd.c +++ /dev/null @@ -1,208 +0,0 @@ -/* -ATMega pinout (with LCD_SHIFTREG): -B0 - HD44780 RS -B1 - HD44780 clock -B2 - shift reg data -B3 - shift reg clock - -ATMega pinout (without LCD_SHIFTREG): -D4 - HD44780 RS -D5 - HD44780 clock -D6 - HD44780 data 0 -D7 - HD44780 data 1 -B0 - HD44780 data 2 -B1 - HD44780 data 3 -B2 - HD44780 data 4 -B3 - HD44780 data 5 -B4 - HD44780 data 6 -B5 - HD44780 data 7 - -In both cases, HD44780 R/W needs to be connected to ground. -*/ -#include -#include "delay.h" -#include "lcd.h" -#include "timer.h" - -#ifdef LCD_SHIFTREG -#define CLOCK_PORT PORTB -#define CLOCK_BIT 0x02 -#define REGSEL_PORT PORTB -#define REGSEL_BIT 0x01 -#else -#define CLOCK_PORT PORTD -#define CLOCK_BIT 0x20 -#define REGSEL_PORT PORTD -#define REGSEL_BIT 0x10 -#endif - -#ifndef LCD_BUFSIZE -#define LCD_BUFSIZE 32 -#endif - -#define NOP() __asm__("nop") - -#ifdef LCD_ASYNC -static volatile uint8_t lcd_busy = 0; -static uint8_t lcd_buffer[LCD_BUFSIZE]; -static volatile uint8_t lcd_buf_head = 0; -static volatile uint8_t lcd_buf_tail = 0; -#endif - -static void lcd_clock(void) -{ - delay_us(1); - CLOCK_PORT |= CLOCK_BIT; - delay_us(1); - CLOCK_PORT &= ~CLOCK_BIT; -} - -static void lcd_set_data(uint8_t d) -{ -#ifdef LCD_SHIFTREG - uint8_t i; - for(i=0; i<8; ++i) - { - PORTB = (PORTB&~0x04)|((d&1)<<2); - PORTB |= 0x08; - NOP(); - PORTB &= ~0x08; - d >>= 1; - } -#else - PORTD = (PORTD&0x3F) | (d<<6); - PORTB = (PORTB&0xC0) | (d>>2); -#endif -} - -static void lcd_command(uint8_t c) -{ - REGSEL_PORT &= ~REGSEL_BIT; - lcd_set_data(c); - lcd_clock(); -} - -static void lcd_delay(uint16_t us) -{ -#ifdef LCD_ASYNC - lcd_busy = 1; - timer_start_us(0, us); -#else - delay_us(us); -#endif -} - -#ifdef LCD_ASYNC -static void lcd_wait(void) -{ - while(lcd_busy) ; -} - -static void lcd_buffer_push(uint8_t byte) -{ - while((lcd_buf_head+1)%sizeof(lcd_buffer)==lcd_buf_tail) ; - lcd_buffer[lcd_buf_head] = byte; - lcd_buf_head = (lcd_buf_head+1)%sizeof(lcd_buffer); -} - -static uint8_t lcd_buffer_pop(void) -{ - uint8_t byte = lcd_buffer[lcd_buf_tail]; - lcd_buf_tail = (lcd_buf_tail+1)%sizeof(lcd_buffer); - return byte; -} - -static void lcd_timer(void) -{ - if(lcd_busy) - { - if(lcd_buf_head!=lcd_buf_tail) - { - uint8_t byte = lcd_buffer_pop(); - if(byte==0xFF) - { - REGSEL_PORT |= REGSEL_BIT; - byte = lcd_buffer_pop(); - } - else if(byte>=0x80) - REGSEL_PORT &= ~REGSEL_BIT; - else - REGSEL_PORT |= REGSEL_BIT; - lcd_set_data(byte); - lcd_clock(); - lcd_delay(50); - } - else - { - lcd_busy = 0; - timer_stop(0); - } - } -} - -TIMER_SET_CALLBACK(0, lcd_timer) -#endif - -void lcd_init(void) -{ -#ifdef LCD_SHIFTREG - DDRB |= 0x0F; - PORTB &= ~0x0F; -#else - DDRD |= 0xF0; - PORTD &= ~0xF0; - DDRB |= 0x3F; - PORTB &= ~0x3F; -#endif - - delay_ms(20); - lcd_command(0x38); - delay_us(50); - lcd_command(0x0C); - delay_us(50); -} - -void lcd_clear(void) -{ -#ifdef LCD_ASYNC - lcd_wait(); -#endif - lcd_command(0x01); - lcd_delay(1700); -} - -void lcd_gotoxy(uint8_t x, uint8_t y) -{ - uint8_t a = x+10*y; - if(y&1) - a += 54; - -#ifdef LCD_ASYNC - if(lcd_busy) - { - lcd_buffer_push(a|0x80); - return; - } -#endif - - lcd_command(a|0x80); - lcd_delay(50); -} - -void lcd_write(uint8_t c) -{ -#ifdef LCD_ASYNC - if(lcd_busy) - { - if(c>=0x80) - lcd_buffer_push(0xFF); - lcd_buffer_push(c); - return; - } -#endif - - REGSEL_PORT |= REGSEL_BIT; - lcd_set_data(c); - lcd_clock(); - lcd_delay(50); -} diff --git a/firmware/lcd.h b/firmware/lcd.h deleted file mode 100644 index abb1017..0000000 --- a/firmware/lcd.h +++ /dev/null @@ -1,9 +0,0 @@ -#ifndef LCD_H_ -#define LCD_H_ - -void lcd_init(void); -void lcd_clear(void); -void lcd_gotoxy(uint8_t, uint8_t); -void lcd_write(uint8_t); - -#endif diff --git a/firmware/s88w-r.c b/firmware/s88w-r.c deleted file mode 100644 index 0198974..0000000 --- a/firmware/s88w-r.c +++ /dev/null @@ -1,219 +0,0 @@ -/* -Firmware for wireless S88 receiver module - -S88 pinout: -1 - DATA -2 - GND -3 - CLOCK -4 - LOAD -5 - RESET -6 - POWER - -ATMega pinout: -D0 - serial RX -D1 - serial TX -D2 - S88 DATA -D3 - S88 CLOCK -D4 - S88 LOAD -D5 - S88 RESET -*/ - -#include -#include -#include "lcd.h" -#include "serial.h" -#include "delay.h" - -#define DATA_OUT PORTD2 -#define CLOCK PIND3 -#define LOAD PIND4 -#define RESET PIND5 - -#define LCD_DISABLE PINB4 - -#define BIT(n) (1<<(n)) - -void receive(uint8_t); -uint8_t hexdigit(uint8_t); -uint8_t decode_hex(uint8_t); - -volatile uint8_t rx_buf[7]; -volatile uint8_t rx_fill = 0xFF; -volatile uint8_t input[128] = { 0 }; -volatile uint8_t latch[128] = { 0 }; -volatile uint8_t lcd_enabled = 0; -uint8_t log_row = 0; -uint8_t log_col = 0; - -int main() -{ - uint8_t clock_high = 0; - uint8_t bits = 0; - uint8_t n_bits = 8; - uint8_t offset = 0; - uint8_t i; - - DDRD = 0x06; // 00000110 - PORTD = 0xC0; // 11000000 - DDRB = 0x20; // 00100000 - PORTB = 0x1F; // 00011111 - - serial_init(9600); - lcd_init(); - - sei(); - - while(1) - { - uint8_t b_pins, d_pins; - - b_pins = PINB; - d_pins = PIND; - - if(d_pins&BIT(CLOCK)) - { - if(!clock_high) - { - if(d_pins&BIT(LOAD)) - { - offset = 0; - bits = latch[0]; - n_bits = 8; - } - else - { - bits >>= 1; - if(!--n_bits) - { - ++offset; - bits = latch[offset]; - n_bits = 8; - } - } - - if(bits&1) - PORTD |= BIT(DATA_OUT); - else - PORTD &= ~BIT(DATA_OUT); - - clock_high = 1; - } - } - else if(clock_high) - clock_high = 0; - - if(d_pins&BIT(RESET)) - { - uint8_t i; - for(i=0; i<128; ++i) - latch[i] = input[i]; - } - - if(b_pins&BIT(LCD_DISABLE)) - { - if(lcd_enabled) - { - lcd_enabled = 0; - - lcd_clear(); - } - } - else if(!lcd_enabled) - { - lcd_enabled = 1; - log_row = 0; - log_col = 0; - - lcd_clear(); - for(i=0; i<20; ++i) - lcd_write(hexdigit(input[9-i/2]>>(4-i%2*4))); - lcd_gotoxy(0, 1); - lcd_write(255); - } - } -} - -void receive(uint8_t c) -{ - if(rx_fill==0xFF) - { - if(c==':') - rx_fill = 0; - } - else if(c=='.') - { - if(rx_fill>=4) - { - uint16_t offset; - uint8_t nibbles; - uint8_t i; - - offset = (decode_hex(rx_buf[0])<<8) | (decode_hex(rx_buf[1])<<4) | decode_hex(rx_buf[2]); - nibbles = (offset&3); - offset >>= 2; - if(rx_fill>3+nibbles) - { - for(i=0; i<=nibbles; ++i) - { - uint16_t j = offset+nibbles-i; - uint8_t shift = 4*(j&1); - uint8_t bits = decode_hex(rx_buf[3+i]); - input[j/2] = (input[j/2]&~(0xF<=20) - { - log_col = 0; - ++log_row; - if(log_row>=3) - log_row = 0; - lcd_gotoxy(log_col, 1+log_row); - } - lcd_write(255); - } -} - -SERIAL_SET_CALLBACK(receive) - -uint8_t hexdigit(uint8_t n) -{ - n &= 0xF; - if(n<10) - return '0'+n; - else - return 'A'+(n-0xA); -} - -uint8_t decode_hex(uint8_t c) -{ - if(c>='0' && c<='9') - return c-'0'; - else if(c>='A' && c<='F') - return 0xA+(c-'A'); - else - return 0; -} diff --git a/firmware/s88w-t.c b/firmware/s88w-t.c deleted file mode 100644 index 692eac5..0000000 --- a/firmware/s88w-t.c +++ /dev/null @@ -1,177 +0,0 @@ -/* -Firmware for wireless S88 transmitter module - -ATMega pinout: -D0 - serial RX -D1 - serial TX -D2 - input 1 -D3 - input 2 -D4 - input 3 -D5 - input 4 -D6 - input 5 -D7 - input 6 -B0 - input 7 -B1 - input 8 -B2 - input 9 -B3 - input 10 -B4 - input 11 -B5 - input 12 - -Inputs are pulled high by internal pull-up resistors. Connect to GND to -activate. - -The module can be configured by sending a string of form ":Shhh." over the -serial port, where hhh is a hex number. Lower two bits indicate the number of -inputs (00=4, 01=8, 10=12, 11=16) and upper ten bits indicate offset of lowest -input in multiples of 4 bits. At the moment there are no provisions for -having 16 physical inputs. - -Example: ":S016." would configure the module to have 12 inputs at offset 20. -*/ - -#include -#include -#include "eeprom.h" -#include "serial.h" -#include "timer.h" - -#define BIT(n) (1<<(n)) - -void receive(uint8_t); -void send_state(void); -uint8_t hexdigit(uint8_t); -uint8_t decode_hex(uint8_t); - -uint8_t rx_buf[4]; -uint8_t rx_fill = 0xFF; -volatile uint8_t nibbles = 2; -volatile uint8_t offset = 0; -volatile uint16_t state = 0; -volatile uint8_t time_since_send = 0; - -int main() -{ - if(eeprom_read(0)==0xA5) - { - offset = eeprom_read(1)<<8; - offset |= eeprom_read(2); - nibbles = eeprom_read(3); - } - - DDRD = 0x02; // 00000010 - PORTD = 0xFC; // 11111100 - DDRB = 0x00; // 00000000 - PORTB = 0x3F; // 00111111 - - serial_init(9600); - timer_start_hz(1, 100, 1); - - sei(); - - while(1) - { - uint8_t i, j; - uint16_t input = 0; - uint16_t valid = 0xFFF; - - for(i=0; i<100; ++i) - { - uint16_t pins = 0; - for(j=0; j<100; ++j) - pins |= ~((PIND>>2) | ((PINB&0x3F)<<6)); - - if(i==0) - input = pins; - - valid &= ~(pins^input); - } - - input &= valid; - input |= state&~valid; - input &= (1<<(nibbles*4))-1; - - if(input!=state && time_since_send>5) - { - state = input; - send_state(); - } - } - - return 0; -} - -void receive(uint8_t c) -{ - if(rx_fill==0xFF) - { - if(c==':') - rx_fill = 0; - } - else if(c=='.') - { - if(rx_buf[0]=='S' && rx_fill==4) - { - offset = (decode_hex(rx_buf[1])<<8) | (decode_hex(rx_buf[2])<<4) | decode_hex(rx_buf[3]); - nibbles = (offset&3)+1; - offset &= 0xFFC; - - eeprom_write(0, 0xA5); - eeprom_write(1, offset>>8); - eeprom_write(2, offset); - eeprom_write(3, nibbles); - } - rx_fill = 0xFF; - } - else - { - if(rx_fill>8)); - serial_write(hexdigit(offset>>4)); - serial_write(hexdigit(offset|(nibbles-1))); - for(i=nibbles; i--;) - serial_write(hexdigit(state>>(i*4))); - serial_write('.'); - - time_since_send = 0; -} - -void timer(void) -{ - ++time_since_send; - if(time_since_send>200) - send_state(); -} - -TIMER_SET_CALLBACK(1, timer) - -uint8_t hexdigit(uint8_t n) -{ - n &= 0xF; - if(n<10) - return '0'+n; - else - return 'A'+(n-0xA); -} - -uint8_t decode_hex(uint8_t c) -{ - if(c>='0' && c<='9') - return c-'0'; - else if(c>='A' && c<='F') - return 0xA+(c-'A'); - else - return 0; -} diff --git a/firmware/s88w-t.svg b/firmware/s88w-t.svg deleted file mode 100644 index edd250b..0000000 --- a/firmware/s88w-t.svg +++ /dev/null @@ -1,2365 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - image/svg+xml - - - - - - - - J1 - - - - - - - - - - - - - 3.3kΩ - - - - - - - - - - - - - - - - - - - - - - - - - - LM2574 - VIN - GND - OFF - - - - - - VOUT - FB - 5 - 4 - 1 - 7 - - - SIG GND - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - FR206 - LTV847 - - Arduino Mini - - XBee - IO2 (PD2) - IO3 (PD3) - IO4 (PD4) - IO5 (PD5) - IO6 (PD6) - IO7 (PD7) - IO8 (PB0) - IO9 (PB1) - TX (PD0) - RX (PD1) - - - - - - - - - Vcc - GND - Vcc - DOUT - DIN - GND - AD5 - - EZ1085 - - 1 - 7 - 5 - 6 - 8 - 9 - 10 - 11 - 12 - 2 - 21 - 23 - - 1 - 2 - 7 - 5 - 6 - 8 - 9 - 10 - 11 - 12 - 3 - 4 - 13 - 14 - 15 - 16 - 1 - 2 - 7 - 5 - 6 - 8 - 9 - 10 - 11 - 12 - 3 - 4 - 13 - 14 - 15 - 16 - - 680µH - - - - - - - - - - - - 22µF - - - - - - - - 220µF - - - - - - - - - - - - 1.8kΩ - VIN - VOUT - GND - - 1.8kΩ - - 3.3kΩ - - - - - - - - 3 - 2 - 15 - 1 - 10 - - - - 100Ω - - - - - - - - - 1kΩ - - - - - - - - - - 3 - 2 - 1 - 2 - 3 - 1N5819 - - diff --git a/firmware/serial.c b/firmware/serial.c deleted file mode 100644 index 2bf6901..0000000 --- a/firmware/serial.c +++ /dev/null @@ -1,22 +0,0 @@ -#include -#include "serial.h" - -#define BIT(n) (1<<(n)) - -void serial_init(uint16_t baud) -{ - DDRD = (DDRD&~0x03) | 0x02; - PORTD &= ~0x03; - - baud = (F_CPU/16+baud/2)/baud-1; - UBRR0H = baud>>8; - UBRR0L = baud; - UCSR0C = BIT(UCSZ00) | BIT(UCSZ01); // 8N1 - UCSR0B = BIT(RXEN0) | BIT(TXEN0) | BIT(RXCIE0); -} - -void serial_write(uint8_t c) -{ - while(!(UCSR0A&(1< - -#define SERIAL_SET_CALLBACK(f) \ - ISR(USART_RX_vect) \ - { \ - char c = UDR0; \ - f(c); \ - } - -void serial_init(uint16_t); -void serial_write(uint8_t); - -#endif diff --git a/firmware/timer.c b/firmware/timer.c deleted file mode 100644 index 99625f8..0000000 --- a/firmware/timer.c +++ /dev/null @@ -1,101 +0,0 @@ -#include -#include "timer.h" - -#define BIT(n) (1<<(n)) - -static void timer_start(uint8_t num, uint32_t period) -{ - uint8_t cs; - - if(num==0) - { - if(period<0x100) - { - cs = BIT(CS00); - } - else if(period<0x800) - { - cs = BIT(CS01); - period /= 8; - } - else if(period<0x4000) - { - cs = BIT(CS01) | BIT(CS00); - period /= 64; - } - else if(period<0x10000) - { - cs = BIT(CS02); - period /= 256; - } - else - { - cs = BIT(CS02) | BIT(CS00); - period /= 1024; - if(period>0xFF) - period = 0xFF; - } - TCCR0A = BIT(WGM01); - TCCR0B = cs; - OCR0A = period; - TIMSK0 = BIT(OCIE0A); - } - if(num==1) - { - if(period<0x10000) - { - cs = BIT(CS10); - } - else if(period<0x80000) - { - cs = BIT(CS11); - period /= 8; - } - else if(period<0x400000) - { - cs = BIT(CS11) | BIT(CS10); - period /= 64; - } - else if(period<0x1000000) - { - cs = BIT(CS12); - period /= 256; - } - else - { - cs = BIT(CS12) | BIT(CS10); - period /= 1024; - if(period>0xFFFF) - period = 0xFFFF; - } - TCCR1A = 0; - TCCR1B = BIT(WGM12) | cs; - OCR1AH = period>>8; - OCR1AL = period; - TIMSK1 = BIT(OCIE1A); - } -} - -void timer_start_hz(uint8_t num, uint32_t freq_p, uint8_t freq_q) -{ - timer_start(num, F_CPU*freq_q/freq_p); -} - -void timer_start_us(uint8_t num, uint32_t us) -{ - timer_start(num, F_CPU/1000000*us); -} - -void timer_stop(uint8_t num) -{ - if(num==0) - { - TCCR0B = 0; - TIMSK0 = 0; - } - else if(num==1) - { - TCCR1B = 0; - TIMSK1 = 0; - } -} diff --git a/firmware/timer.h b/firmware/timer.h deleted file mode 100644 index 2869caa..0000000 --- a/firmware/timer.h +++ /dev/null @@ -1,16 +0,0 @@ -#ifndef TIMER_H_ -#define TIMER_H_ - -#include - -#define TIMER_SET_CALLBACK(n, f) \ - ISR(TIMER ## n ## _COMPA_vect) \ - { \ - f(); \ - } - -void timer_start_hz(uint8_t, uint32_t, uint8_t); -void timer_start_us(uint8_t, uint32_t); -void timer_stop(uint8_t); - -#endif diff --git a/misc/Makefile b/misc/Makefile new file mode 100644 index 0000000..c7b57b4 --- /dev/null +++ b/misc/Makefile @@ -0,0 +1 @@ +include ../common/build.mk diff --git a/misc/ctrl.c b/misc/ctrl.c new file mode 100644 index 0000000..0ac212e --- /dev/null +++ b/misc/ctrl.c @@ -0,0 +1,221 @@ +#include +#include + +#define BIT(n) (1<<(n)) +#define NOP() __asm__("nop"); + +uint8_t digits[11] = +{ + 0x3F, + 0x06, + 0x5B, + 0x4F, + 0x66, + 0x6D, + 0x7D, + 0x07, + 0x7F, + 0x6F, + 0x40 +}; + +uint16_t read_input(void); +uint16_t read_input_filtered(void); +void write_serial(uint8_t); +void write_7seg(uint8_t); + +uint8_t speed = 0; +uint16_t funcs = 0; +volatile uint8_t ticks = 0; +volatile uint8_t rx_buf[3]; +volatile uint8_t rx_fill = 0; + +ISR(TIMER1_COMPA_vect) +{ + if(ticks<255) + ++ticks; +} + +ISR(USART_RX_vect) +{ + uint8_t c = UDR0; + if(rx_fill==0) + { + if(c=='A' || c=='S') + rx_buf[rx_fill++] = c; + } + else + { + rx_buf[rx_fill++] = c; + if(rx_buf[0]=='A' && rx_fill==3) + { + uint8_t n = (rx_buf[1]-'0')*10+(rx_buf[2]-'0'); + write_7seg(n/10); + write_7seg(n%10); + rx_fill = 0; + } + else if(rx_buf[0]=='S' && rx_fill==3) + { + speed = (rx_buf[1]-'0')*10+(rx_buf[2]-'0'); + rx_fill = 0; + } + } +} + +int main() +{ + uint16_t state = 0; + + DDRD = 0x02; // 00000010 + PORTD = 0xFC; // 11111100 + DDRB = 0x3F; // 00111111 + PORTB = 0x0F; // 00001111 + + write_7seg(10); + write_7seg(10); + + // 9600 baud, 8N1 + UBRR0H = 0; + UBRR0L = 103; + UCSR0C = BIT(UCSZ00) | BIT(UCSZ01); + UCSR0B = BIT(RXEN0) | BIT(TXEN0) | BIT(RXCIE0); + + TCCR1A = 0; + TCCR1B = BIT(WGM12) | BIT(CS12); + OCR1AH = 24; + OCR1AL = 106; + TIMSK1 = BIT(OCIE1A); + + sei(); + + while(1) + { + uint16_t toggled; + uint8_t i; + uint16_t input; + + input = read_input_filtered(); + input ^= 0xFFFC; + + toggled = state^input; + state = input; + + if((toggled&3)==2 && (state&1)) + { + uint8_t action = 0; + if(state&2) + { + if(speed<14) + { + ++speed; + action = 1; + } + } + else + { + if(speed>0) + { + --speed; + action = 1; + } + else if(ticks>10) + action = 2; + } + + if(action==1) + { + write_serial('S'); + write_serial('0'+speed/10); + write_serial('0'+speed%10); + } + else if(action==2) + write_serial('R'); + + ticks = 0; + } + + for(i=0; i<14; ++i) + { + uint16_t bit = 4<>2; + input |= pins&3; + input |= (pins&0x3C)<<(row*4); + } + + return input; +} + +uint16_t read_input_filtered(void) +{ + uint16_t valid = 0xFFFF; + uint16_t prev; + uint16_t input; + uint8_t i; + + prev = read_input(); + for(i=0; i<20; ++i) + { + input = read_input(); + valid &= ~(input^prev); + prev = input; + } + + return input&valid; +} + +void write_serial(uint8_t c) +{ + while(!(UCSR0A&(1< +#include +#include "lcd.h" +#include "serial.h" +#include "delay.h" + +#define DATA_OUT PORTD2 +#define CLOCK PIND3 +#define LOAD PIND4 +#define RESET PIND5 + +#define LCD_DISABLE PINB4 + +#define BIT(n) (1<<(n)) + +void receive(uint8_t); +uint8_t hexdigit(uint8_t); +uint8_t decode_hex(uint8_t); + +volatile uint8_t rx_buf[7]; +volatile uint8_t rx_fill = 0xFF; +volatile uint8_t input[128] = { 0 }; +volatile uint8_t latch[128] = { 0 }; +volatile uint8_t lcd_enabled = 0; +uint8_t log_row = 0; +uint8_t log_col = 0; + +int main() +{ + uint8_t clock_high = 0; + uint8_t bits = 0; + uint8_t n_bits = 8; + uint8_t offset = 0; + uint8_t i; + + DDRD = 0x06; // 00000110 + PORTD = 0xC0; // 11000000 + DDRB = 0x20; // 00100000 + PORTB = 0x1F; // 00011111 + + serial_init(9600); + lcd_init(); + + sei(); + + while(1) + { + uint8_t b_pins, d_pins; + + b_pins = PINB; + d_pins = PIND; + + if(d_pins&BIT(CLOCK)) + { + if(!clock_high) + { + if(d_pins&BIT(LOAD)) + { + offset = 0; + bits = latch[0]; + n_bits = 8; + } + else + { + bits >>= 1; + if(!--n_bits) + { + ++offset; + bits = latch[offset]; + n_bits = 8; + } + } + + if(bits&1) + PORTD |= BIT(DATA_OUT); + else + PORTD &= ~BIT(DATA_OUT); + + clock_high = 1; + } + } + else if(clock_high) + clock_high = 0; + + if(d_pins&BIT(RESET)) + { + uint8_t i; + for(i=0; i<128; ++i) + latch[i] = input[i]; + } + + if(b_pins&BIT(LCD_DISABLE)) + { + if(lcd_enabled) + { + lcd_enabled = 0; + + lcd_clear(); + } + } + else if(!lcd_enabled) + { + lcd_enabled = 1; + log_row = 0; + log_col = 0; + + lcd_clear(); + for(i=0; i<20; ++i) + lcd_write(hexdigit(input[9-i/2]>>(4-i%2*4))); + lcd_gotoxy(0, 1); + lcd_write(255); + } + } +} + +void receive(uint8_t c) +{ + if(rx_fill==0xFF) + { + if(c==':') + rx_fill = 0; + } + else if(c=='.') + { + if(rx_fill>=4) + { + uint16_t offset; + uint8_t nibbles; + uint8_t i; + + offset = (decode_hex(rx_buf[0])<<8) | (decode_hex(rx_buf[1])<<4) | decode_hex(rx_buf[2]); + nibbles = (offset&3); + offset >>= 2; + if(rx_fill>3+nibbles) + { + for(i=0; i<=nibbles; ++i) + { + uint16_t j = offset+nibbles-i; + uint8_t shift = 4*(j&1); + uint8_t bits = decode_hex(rx_buf[3+i]); + input[j/2] = (input[j/2]&~(0xF<=20) + { + log_col = 0; + ++log_row; + if(log_row>=3) + log_row = 0; + lcd_gotoxy(log_col, 1+log_row); + } + lcd_write(255); + } +} + +SERIAL_SET_CALLBACK(receive) + +uint8_t hexdigit(uint8_t n) +{ + n &= 0xF; + if(n<10) + return '0'+n; + else + return 'A'+(n-0xA); +} + +uint8_t decode_hex(uint8_t c) +{ + if(c>='0' && c<='9') + return c-'0'; + else if(c>='A' && c<='F') + return 0xA+(c-'A'); + else + return 0; +} diff --git a/s88w/s88w-t.c b/s88w/s88w-t.c new file mode 100644 index 0000000..692eac5 --- /dev/null +++ b/s88w/s88w-t.c @@ -0,0 +1,177 @@ +/* +Firmware for wireless S88 transmitter module + +ATMega pinout: +D0 - serial RX +D1 - serial TX +D2 - input 1 +D3 - input 2 +D4 - input 3 +D5 - input 4 +D6 - input 5 +D7 - input 6 +B0 - input 7 +B1 - input 8 +B2 - input 9 +B3 - input 10 +B4 - input 11 +B5 - input 12 + +Inputs are pulled high by internal pull-up resistors. Connect to GND to +activate. + +The module can be configured by sending a string of form ":Shhh." over the +serial port, where hhh is a hex number. Lower two bits indicate the number of +inputs (00=4, 01=8, 10=12, 11=16) and upper ten bits indicate offset of lowest +input in multiples of 4 bits. At the moment there are no provisions for +having 16 physical inputs. + +Example: ":S016." would configure the module to have 12 inputs at offset 20. +*/ + +#include +#include +#include "eeprom.h" +#include "serial.h" +#include "timer.h" + +#define BIT(n) (1<<(n)) + +void receive(uint8_t); +void send_state(void); +uint8_t hexdigit(uint8_t); +uint8_t decode_hex(uint8_t); + +uint8_t rx_buf[4]; +uint8_t rx_fill = 0xFF; +volatile uint8_t nibbles = 2; +volatile uint8_t offset = 0; +volatile uint16_t state = 0; +volatile uint8_t time_since_send = 0; + +int main() +{ + if(eeprom_read(0)==0xA5) + { + offset = eeprom_read(1)<<8; + offset |= eeprom_read(2); + nibbles = eeprom_read(3); + } + + DDRD = 0x02; // 00000010 + PORTD = 0xFC; // 11111100 + DDRB = 0x00; // 00000000 + PORTB = 0x3F; // 00111111 + + serial_init(9600); + timer_start_hz(1, 100, 1); + + sei(); + + while(1) + { + uint8_t i, j; + uint16_t input = 0; + uint16_t valid = 0xFFF; + + for(i=0; i<100; ++i) + { + uint16_t pins = 0; + for(j=0; j<100; ++j) + pins |= ~((PIND>>2) | ((PINB&0x3F)<<6)); + + if(i==0) + input = pins; + + valid &= ~(pins^input); + } + + input &= valid; + input |= state&~valid; + input &= (1<<(nibbles*4))-1; + + if(input!=state && time_since_send>5) + { + state = input; + send_state(); + } + } + + return 0; +} + +void receive(uint8_t c) +{ + if(rx_fill==0xFF) + { + if(c==':') + rx_fill = 0; + } + else if(c=='.') + { + if(rx_buf[0]=='S' && rx_fill==4) + { + offset = (decode_hex(rx_buf[1])<<8) | (decode_hex(rx_buf[2])<<4) | decode_hex(rx_buf[3]); + nibbles = (offset&3)+1; + offset &= 0xFFC; + + eeprom_write(0, 0xA5); + eeprom_write(1, offset>>8); + eeprom_write(2, offset); + eeprom_write(3, nibbles); + } + rx_fill = 0xFF; + } + else + { + if(rx_fill>8)); + serial_write(hexdigit(offset>>4)); + serial_write(hexdigit(offset|(nibbles-1))); + for(i=nibbles; i--;) + serial_write(hexdigit(state>>(i*4))); + serial_write('.'); + + time_since_send = 0; +} + +void timer(void) +{ + ++time_since_send; + if(time_since_send>200) + send_state(); +} + +TIMER_SET_CALLBACK(1, timer) + +uint8_t hexdigit(uint8_t n) +{ + n &= 0xF; + if(n<10) + return '0'+n; + else + return 'A'+(n-0xA); +} + +uint8_t decode_hex(uint8_t c) +{ + if(c>='0' && c<='9') + return c-'0'; + else if(c>='A' && c<='F') + return 0xA+(c-'A'); + else + return 0; +} diff --git a/s88w/s88w-t.svg b/s88w/s88w-t.svg new file mode 100644 index 0000000..edd250b --- /dev/null +++ b/s88w/s88w-t.svg @@ -0,0 +1,2365 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + image/svg+xml + + + + + + + + J1 + + + + + + + + + + + + + 3.3kΩ + + + + + + + + + + + + + + + + + + + + + + + + + + LM2574 + VIN + GND + OFF + + + + + + VOUT + FB + 5 + 4 + 1 + 7 + + + SIG GND + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + FR206 + LTV847 + + Arduino Mini + + XBee + IO2 (PD2) + IO3 (PD3) + IO4 (PD4) + IO5 (PD5) + IO6 (PD6) + IO7 (PD7) + IO8 (PB0) + IO9 (PB1) + TX (PD0) + RX (PD1) + + + + + + + + + Vcc + GND + Vcc + DOUT + DIN + GND + AD5 + + EZ1085 + + 1 + 7 + 5 + 6 + 8 + 9 + 10 + 11 + 12 + 2 + 21 + 23 + + 1 + 2 + 7 + 5 + 6 + 8 + 9 + 10 + 11 + 12 + 3 + 4 + 13 + 14 + 15 + 16 + 1 + 2 + 7 + 5 + 6 + 8 + 9 + 10 + 11 + 12 + 3 + 4 + 13 + 14 + 15 + 16 + + 680µH + + + + + + + + + + + + 22µF + + + + + + + + 220µF + + + + + + + + + + + + 1.8kΩ + VIN + VOUT + GND + + 1.8kΩ + + 3.3kΩ + + + + + + + + 3 + 2 + 15 + 1 + 10 + + + + 100Ω + + + + + + + + + 1kΩ + + + + + + + + + + 3 + 2 + 1 + 2 + 3 + 1N5819 + +