This commit is contained in:
Олег Бородин
2024-08-20 18:12:45 +02:00
commit daac0e8e1f
24 changed files with 28759 additions and 0 deletions

5
.gitignore vendored Normal file
View File

@@ -0,0 +1,5 @@
*.o
*.hex
*.bin
*.elf
*.d

67
Makefile Normal file
View File

@@ -0,0 +1,67 @@
CC = avr-gcc
OBJCOPY = avr-objcopy
SIZE = avr-size
F_CPU = 16000000UL
MCU = atmega328p
CFLAGS += -DF_CPU=$(F_CPU) -mmcu=$(MCU)
CFLAGS += -I. -O2 --std=c99
CFLAGS += -ffunction-sections -fdata-sections
LDFLAGS += -s -mmcu=$(MCU)
LDFLAGS += -Wl,--gc-sections
LDFLAGS += -Wl,-u,vfprintf -lprintf_flt
MAIN_OBJS += main.o
MAIN_OBJS += contr.o
MAIN_OBJS += eeprom.o
MAIN_OBJS += i2c.o
MAIN_OBJS += disp.o
MAIN_OBJS += fifo.o
MAIN_OBJS += uart.o
MAIN_OBJS += tool.o
MAIN_OBJS += timer.o
MAIN_OBJS += temp.o
MAIN_ELF = main.elf
MAIN_HEX = main.hex
all: $(MAIN_HEX)
$(MAIN_ELF): $(MAIN_OBJS)
$(CC) $(LDFLAGS) -o $(MAIN_ELF) $(MAIN_OBJS)
$(SIZE) --format=berkeley $@
%.o: %.c
$(CC) $(CFLAGS) -c $*.c -o $*.o
$(CC) -MM $(CFLAGS) $*.c > $*.d
$(MAIN_HEX): $(MAIN_ELF)
$(OBJCOPY) -O ihex -R .eeprom $< $@
AVRDUDE = sudo avrdude
TTY_PORT = /dev/ttyUSB0
TTY_SPEED = 115200
BACKUP = $(MAIN_HEX).bak
upload: $(MAIN_HEX)
$(AVRDUDE) -c arduino -p ATMEGA328P -P $(TTY_PORT) -b $(TTY_SPEED) -U flash:w:$<
download:
$(AVRDUDE) -F -V -c arduino -p m328p -P $(TTY_PORT) -b $(TTY_SPEED) -U flash:r:$(BACKUP):i
# $(AVRDUDE) -F -V -c arduino -p ATMEGA328P -P $(TTY_PORT) -b $(TTY_SPEED) -U flash:r:$(BACKUP):i
#avrdude -P /dev/ttyUSB0 -b 115200 -p m328p -c arduino -U flash:w:MicroPA50+_BETA1.5.hex:i
clean:
rm -f *.i *.o *.s
rm -f *.elf *.bin *~ *.hex
rm -f *.d
-include $(MAIN_OBJS:.o=.d)
#EOF

26
README.md Normal file
View File

@@ -0,0 +1,26 @@
# Micro PA50 controller
## Ports
```
/*
* D0 - PD0 RX
* D1 - PD1 TX
* D2 - PD2 IN PTT IN
* D3 - PD3 IN KEY
* D4 - PD4 OUT RELAY5 TX SWITCH
* D5 - PD5 IN FREQ OSC MC74HC4060A
* D6 - PD6 OUT 10M
* D7 - PD7 OUT 20M
* D8 - PB0 OUT 40M
* D9 - PB1 OUT 80M
* D10 - PB2 OUT BUZZER
* D11 - PB3 IN TEMP DS18B20
* D12 - PB4 OUT FAN
* D13 - PB5 OUT PA ATT SWITCH
*
* A0 PC0 - V.REV
* A1 PC1 - V.FWD
* A2 PC2 - ICOM
* A3 PC3 - V.VCC
*/
```

543
contr.c Normal file
View File

@@ -0,0 +1,543 @@
/*
* Copyright 2017 Oleg Borodin <onborodin@gmail.com>
*/
#include <stdint.h>
#include <stdbool.h>
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
#include <avr/interrupt.h>
#include <util/delay.h>
#include <eeprom.h>
#include <disp.h>
#include <tool.h>
#include <uart.h>
#include <timer.h>
#include <temp.h>
#include <contr.h>
#define CONTR_BAND_OFF 0x01
#define CONTR_BAND_10M 0x02
#define CONTR_BAND_20M 0x03
#define CONTR_BAND_40M 0x04
#define CONTR_BAND_80M 0x05
#define VCCS_SIZE 12
typedef struct {
uint16_t fwd_power;
uint16_t ref_power;
uint16_t temp;
uint16_t freq;
uint16_t vcc;
uint8_t band;
bool key_was_pressed;
uint16_t key_time_counter;
uint16_t key_time_untap;
uint16_t key_tap_counter;
bool key_strokes_ended;
uint16_t vccs[VCCS_SIZE];
size_t vccs_pos;
} contr_t;
contr_t contr;
void contr_key_init(void);
void contr_key_handle(void);
void contr_key_reset(void);
void contr_switch_band(void);
void contr_set_band(uint8_t band);
void contr_txrelay_init(void);
void contr_txrelay_on(void);
void contr_txrelay_off(void);
void contr_txrelay_onoff(void);
void contr_relay10m_init(void);
void contr_relay10m_on(void);
void contr_relay10m_off(void);
void contr_relay20m_init(void);
void contr_relay20m_on(void);
void contr_relay20m_off(void);
void contr_relay40m_init(void);
void contr_relay40m_on(void);
void contr_relay40m_off(void);
void contr_relay80m_init(void);
void contr_relay80m_on(void);
void contr_relay80m_off(void);
void contr_buzzer_init(void);
void contr_buzzer_on(void);
void contr_buzzer_off(void);
void contr_buzzer_onoff(void);
void contr_fan_init(void);
void contr_fan_on(void);
void contr_fan_off(void);
void contr_fan_onoff(void);
bool contr_fan_is_on(void);
void contr_att_init(void);
void contr_att_on(void);
void contr_att_off(void);
void contr_timer_init(void);
void contr_adc_init(void);
float contr_vcc_read(void);
void contr_write_band(void);
void contr_read_band(void);
void contr_timer_init(void) {
/* Disable comparators */
REG_SETDOWN_BIT(TCCR0A, COM0A1);
REG_SETDOWN_BIT(TCCR0A, COM0A0);
REG_SETDOWN_BIT(TCCR0A, COM0B1);
REG_SETDOWN_BIT(TCCR0A, COM0B0);
/* Set normal mode */
REG_SETDOWN_BIT(TCCR0A, WGM01);
REG_SETDOWN_BIT(TCCR0A, WGM00);
/* Set clock to 1/64 */
REG_SETDOWN_BIT(TCCR0B, CS02);
REG_SETUP_BIT(TCCR0B, CS01);
REG_SETUP_BIT(TCCR0B, CS00);
/* Enable timer interrupt */
REG_SETUP_BIT(TIMSK0, TOIE0);
REG_SETUP(TCNT0, TIMER_INITVAL);
}
ISR(TIMER0_OVF_vect) {
contr_key_handle();
volatile uint8_t xchar;
while ((xchar = fifo_getc(&uart_outbuf)) > 0) {
while (!REG_BIT_ISUP(UCSR0A, UDRE0));
UDR0 = xchar;
}
REG_SETUP(TCNT0, TIMER_INITVAL);
}
/*
* D0 - PD0 RX
* D1 - PD1 TX
* D2 - PD2 IN PTT IN
* D3 - PD3 IN KEY
* D4 - PD4 OUT RELAY5 TX SWITCH
* D5 - PD5 IN FREQ OSC MC74HC4060A
* D6 - PD6 OUT 10M
* D7 - PD7 OUT 20M
* D8 - PB0 OUT 40M
* D9 - PB1 OUT 80M
* D10 - PB2 OUT BUZZER
* D11 - PB3 IN TEMP DS18B20
* D12 - PB4 OUT FAN
* D13 - PB5 OUT PA ATT SWITCH
*
* A0 PC0 - V.REV
* A1 PC1 - V.FWD
* A2 PC2 - ICOM
* A3 PC3 - V.VCC
*/
void contr_init(void) {
contr.fwd_power = 0;
contr.ref_power = 0;
contr.temp = 0;
contr.freq = 0;
contr.vcc = 0;
contr.band = CONTR_BAND_OFF;
contr.vccs_pos = 0;
for (size_t i = 0; i < VCCS_SIZE; i++) {
contr.vccs[i] = 0.0F;
}
contr.key_was_pressed = false;
contr.key_time_counter = 0;
contr.key_tap_counter = 0;
contr.key_strokes_ended = false;
}
void contr_setup(void) {
contr_read_band();
contr_txrelay_init();
contr_txrelay_off();
contr_att_init();
contr_att_off();
contr_relay10m_init();
contr_relay20m_init();
contr_relay40m_init();
contr_relay80m_init();
contr_relay10m_off();
contr_relay20m_off();
contr_relay40m_off();
contr_relay80m_off();
contr_buzzer_init();
contr_buzzer_off();
contr_fan_init();
contr_fan_off();
contr_key_init();
contr_adc_init();
contr_timer_init();
}
void contr_switch_band(void) {
contr_txrelay_off();
_delay_ms(100);
contr_relay80m_off();
contr_relay40m_off();
contr_relay20m_off();
contr_relay10m_off();
_delay_ms(100);
switch (contr.band) {
case CONTR_BAND_10M:
contr_relay20m_on();
contr.band = CONTR_BAND_20M;
break;
case CONTR_BAND_20M:
contr_relay40m_on();
contr.band = CONTR_BAND_40M;
break;
case CONTR_BAND_40M:
contr_relay80m_on();
contr.band = CONTR_BAND_80M;
break;
case CONTR_BAND_80M:
contr_relay10m_on();
contr.band = CONTR_BAND_10M;
break;
default:
break;
}
contr_write_band();
_delay_ms(100);
contr_att_on();
_delay_ms(100);
}
void contr_logo(void) {
char dispstr[10] = { '\0' };
sprintf(dispstr, "R2DFX");
disp_string(2, 3, dispstr);
}
/*******************************************************/
void contr_main(void) {
uint16_t counter = 0;
char dispstr[10] = { '\0' };
char* bandstr = NULL;
sprintf(dispstr, "Made by R2FDX");
disp_string(1, 1, dispstr);
_delay_ms(1000);
disp_clear();
printf("READY>\n\r# ");
while (true) {
_delay_ms(100);
if (contr.key_strokes_ended) {
switch (contr.key_tap_counter) {
case 1:
contr_key_reset();
contr_switch_band();
break;
case 2:
contr_key_reset();
//contr_txrelay_onoff();
break;
case 3:
contr_key_reset();
contr_buzzer_onoff();
break;
case 5:
contr_key_reset();
contr_fan_onoff();
break;
default:
contr_key_reset();
break;
}
}
switch (contr.band) {
case CONTR_BAND_10M:
bandstr = "10m";
break;
case CONTR_BAND_20M:
bandstr = "20m";
break;
case CONTR_BAND_40M:
bandstr = "40m";
break;
case CONTR_BAND_80M:
bandstr = "80m";
break;
case CONTR_BAND_OFF:
bandstr = "OFF";
break;
}
disp_string(0, 12, bandstr);
sprintf(dispstr, "%3.2fV", contr_vcc_read());
disp_string(0, 0, dispstr);
sprintf(dispstr, "%3.2fC", ds18b20_get_temp());
disp_string(3, 0, dispstr);
if (contr.key_tap_counter) {
sprintf(dispstr, "%2d", contr.key_tap_counter);
disp_string(3, 12, dispstr);
} else {
sprintf(dispstr, " ");
disp_string(3, 12, dispstr);
}
counter++;
}
}
/* D4 PD4: Set input relay 5 output */
void contr_txrelay_init(void) {
REG_SETUP_BIT(DDRD, PD4);
}
void contr_txrelay_on(void) {
REG_SETUP_BIT(PORTD, PD4);
}
void contr_txrelay_off(void) {
REG_SETDOWN_BIT(PORTD, PD4);
}
void contr_txrelay_onoff(void) {
if (REG_BIT_VALUE(PIND, PD4)) {
contr_txrelay_off();
} else {
contr_txrelay_on();
}
}
/* D6 PD6: Set 10M relay 1 output */
void contr_relay10m_init(void) {
REG_SETUP_BIT(DDRD, PD6);
}
void contr_relay10m_on(void) {
REG_SETUP_BIT(PORTD, PD6);
}
void contr_relay10m_off(void) {
REG_SETDOWN_BIT(PORTD, PD6);
}
/* D7 PD7: Set 20M relay 2 output */
void contr_relay20m_init(void) {
REG_SETUP_BIT(DDRD, PD7);
}
void contr_relay20m_on(void) {
REG_SETUP_BIT(PORTD, PD7);
}
void contr_relay20m_off(void) {
REG_SETDOWN_BIT(PORTD, PD7);
}
/* D8 PB0: Set 40M relay 3 output */
void contr_relay40m_init(void) {
REG_SETUP_BIT(DDRB, PB0);
}
void contr_relay40m_on(void) {
REG_SETUP_BIT(PORTB, PB0);
}
void contr_relay40m_off(void) {
REG_SETDOWN_BIT(PORTB, PB0);
}
/* D9 PB1: Set 80M relay 4 output */
void contr_relay80m_init(void) {
REG_SETUP_BIT(DDRB, PB1);
}
void contr_relay80m_on(void) {
REG_SETUP_BIT(PORTB, PB1);
}
void contr_relay80m_off(void) {
REG_SETDOWN_BIT(PORTB, PB1);
}
/* D10 PB2: Set buzzer output */
void contr_buzzer_init(void) {
REG_SETUP_BIT(DDRB, PB2);
}
void contr_buzzer_on(void) {
REG_SETUP_BIT(PORTB, PB2);
}
void contr_buzzer_off(void) {
REG_SETDOWN_BIT(PORTB, PB2);
}
void contr_buzzer_onoff(void) {
if (REG_BIT_VALUE(PINB, PB2)) {
contr_buzzer_off();
} else {
contr_buzzer_on();
}
}
/* D12 PB4: Set fan output */
void contr_fan_init(void) {
REG_SETUP_BIT(DDRB, PB4);
}
void contr_fan_on(void) {
REG_SETUP_BIT(PORTB, PB4);
}
void contr_fan_off(void) {
REG_SETDOWN_BIT(PORTB, PB4);
}
void contr_fan_onoff(void) {
if (REG_BIT_VALUE(PINB, PB4)) {
contr_fan_off();
} else {
contr_fan_on();
}
}
bool contr_fan_is_on(void) {
if (REG_BIT_VALUE(PINB, PB4)) {
return true;
}
return false;
}
/* D13 PB5: Set attenuator relay output */
void contr_att_init(void) {
REG_SETUP_BIT(DDRB, PB5);
}
void contr_att_on(void) {
REG_SETUP_BIT(PORTB, PB5);
}
void contr_att_off(void) {
REG_SETDOWN_BIT(PORTB, PB5);
}
void contr_adc_init() {
/* Disable ADC */
REG_SETDOWN_BIT(ADCSRA, ADEN);
/* Set reference*/
REG_SETUP_BIT(ADMUX, REFS0);
REG_SETDOWN_BIT(ADMUX, REFS1);
/* Set result type */
REG_SETUP_BIT(ADMUX, ADLAR);
/* Set freq prescale */
REG_SETUP_BIT(ADCSRA, ADPS2);
REG_SETUP_BIT(ADCSRA, ADPS1);
REG_SETUP_BIT(ADCSRA, ADPS0);
/* Disable autoconversion */
REG_SETDOWN_BIT(ADCSRA, ADATE);
/* Disable interrupt */
REG_SETDOWN_BIT(ADCSRA, ADIE);
/* Enable ADC */
REG_SETUP_BIT(ADCSRA, ADEN);
}
float contr_vcc_read(void) {
REG_SETUP_BIT(ADMUX, MUX0);
REG_SETUP_BIT(ADMUX, MUX1);
REG_SETDOWN_BIT(ADMUX, MUX2);
REG_SETDOWN_BIT(ADMUX, MUX3);
REG_SETUP_BIT(ADCSRA, ADSC);
while (ADCSRA & BIT(ADSC));
uint16_t lval = (uint16_t)ADCL;
uint16_t hval = (uint16_t)ADCH;
hval = (hval << 8) & 0xFF00;
lval = lval & 0x00FF;
if (++contr.vccs_pos > VCCS_SIZE) contr.vccs_pos = 0;
contr.vccs[contr.vccs_pos] = (hval | lval);
uint32_t vcc = 0;
uint8_t n = 0;
for (size_t i = 0; i < VCCS_SIZE; i++) {
if (contr.vccs[i]) {
n++;
vcc += contr.vccs[i];
}
}
return (float)vcc / (float)n / 2673.0F;
}
void contr_write_band(void) {
eeprom_write_bytes(0x00, &contr.band, sizeof(contr.band));
}
void contr_read_band(void) {
eeprom_read_bytes(0x00, &contr.band, sizeof(contr.band));
}
void contr_key_init(void) {
/* D3 PD3: Set key input */
REG_SETDOWN_BIT(DDRD, PD3);
REG_SETUP_BIT(PORTD, PD3);
}
bool contr_key_is_pressed(void) {
if (REG_BIT_VALUE(PIND, PD3)) {
return true;
}
return false;
}
void contr_key_handle(void) {
if (!contr.key_was_pressed) {
if (contr_key_is_pressed()) {
contr.key_time_counter++;
contr.key_time_untap++;
}
if (contr.key_time_counter > 100) {
contr.key_time_counter = 0;
contr.key_was_pressed = true;
}
} else {
if (!contr_key_is_pressed()) {
contr.key_time_counter++;
}
if (contr.key_time_counter > 100) {
contr.key_time_counter = 0;
contr.key_was_pressed = false;
contr.key_tap_counter++;
contr.key_time_untap = 0;
}
}
if (contr.key_tap_counter > 0) {
contr.key_time_untap++;
if (contr.key_time_untap > 2000) {
contr.key_strokes_ended = true;
}
if (contr.key_time_untap > 5000) {
contr.key_was_pressed = false;
contr.key_tap_counter = 0;
contr.key_time_untap = 0;
contr.key_strokes_ended = false;
}
} else {
contr.key_time_untap = 0;
}
}
void contr_key_reset(void) {
contr.key_was_pressed = false;
contr.key_tap_counter = 0;
contr.key_time_untap = 0;
contr.key_strokes_ended = false;
}

8
contr.h Normal file
View File

@@ -0,0 +1,8 @@
#ifndef CONTR_H_QWERTY
#define CONTR_H_QWERTY
void contr_init(void);
void contr_setup(void);
void contr_main(void);
#endif

428
disp.c Normal file
View File

@@ -0,0 +1,428 @@
#include <stdlib.h>
#include <stdbool.h>
#include <string.h>
#include <i2c.h>
#include <disp.h>
#define DISP_FONT basefont
#define DISP_I2CADDR (0x78 >> 1)
#define DISP_WIDTH 128
#define DISP_HEIGHT 64
#define DISP_MIN_CHARCODE 32
#define DISP_MAX_CHARCODE 127
#define DISP_CHAR_ARRLEN 16
#define DISP_PAGE_HEIGHT 8
#define DISP_FONT_WIDTH 8
#define DISP_FONT_HEIGHT 2
#define DISP_SEND_CMD 0x00
#define DISP_SEND_DATA 0x40
const uint8_t basefont[DISP_MAX_CHARCODE - DISP_MIN_CHARCODE][DISP_CHAR_ARRLEN] PROGMEM;
typedef struct {
uint8_t max_posx;
uint8_t max_posy;
} disp_t;
disp_t disp;
#define SSD1306_SETLOWCOLUMN 0x00 /* Set Lower Column Start Address for Page Addressing Mode. */
#define SSD1306_SETHIGHCOLUMN 0x10 /* Set Higher Column Start Address for Page Addressing Mode. */
#define SSD1306_MEMORYMODE 0x20 /* Set Memory Addressing Mode. */
#define SSD1306_SETCOLNADDR 0x21
#define SSD1306_SETPAGEADDR 0x22
#define SSD1306_SETSTARTLINE 0x40 /* Set display RAM display start line register from 0 - 63. */
#define SSD1306_SETCONTRAST 0x81 /* Set Display Contrast to one of 256 steps. */
#define SSD1306_CHARGEPUMP 0x8D /* Enable or disable charge pump. Follow with 0X14 enable, 0X10 disable. */
#define SSD1306_SEGREMAP_MIRROR 0xA0 /* Set Segment Re-map between data column and the segment driver. */
#define SSD1306_SEGREMAP 0xA1
#define SSD1306_DISPLAYALLON_RESUME 0xA4 /* Resume display from GRAM content. */
#define SSD1306_DISPLAYALLON 0xA5 /* Force display on regardless of GRAM content. */
#define SSD1306_NORMALDISPLAY 0xA6 /* Set Normal Display. */
#define SSD1306_INVERTDISPLAY 0xA7 /* Set Inverse Display. */
#define SSD1306_SETMULTIPLEX 0xA8 /* Set Multiplex Ratio from 16 to 63. */
#define SSD1306_DISPLAYOFF 0xAE /* Set Display off. */
#define SSD1306_DISPLAYON 0xAF /* Set Display on. */
#define SSD1306_SETSTARTPAGE 0XB0 /* Set GDDRAM Page Start Address. */
#define SSD1306_COMSCANINC 0xC0 /* Set COM output scan direction normal. */
#define SSD1306_COMSCANDEC 0xC8 /* Set COM output scan direction reversed. */
#define SSD1306_SETDISPLAYOFFSET 0xD3 /* Set Display Offset. */
#define SSD1306_SETCOMPINS 0xDA /* Sets COM signals pin configuration to match the OLED panel layout. */
#define SSD1306_SETVCOMDETECT 0xDB /* This command adjusts the VCOMH regulator output. */
#define SSD1306_SETDISPLAYCLOCKDIV 0xD5 /* Set Display Clock Divide Ratio/ Oscillator Frequency. */
#define SSD1306_SETPRECHARGE 0xD9 /* Set Pre-charge Period */
#define SSD1306_DEACTIVATE_SCROLL 0x2E /* Deactivate scroll */
#define SSD1306_NOP 0XE3 /* No Operation Command. */
const uint8_t init_sequence[] PROGMEM = {
SSD1306_DISPLAYOFF,
SSD1306_MEMORYMODE, 0x00,
SSD1306_SETSTARTPAGE,
SSD1306_COMSCANDEC,
SSD1306_SETLOWCOLUMN,
SSD1306_SETHIGHCOLUMN,
SSD1306_SETSTARTLINE,
SSD1306_SETCONTRAST, 0xFF,
SSD1306_SEGREMAP,
SSD1306_NORMALDISPLAY,
SSD1306_SETMULTIPLEX, DISP_HEIGHT - 1,
SSD1306_DISPLAYALLON_RESUME,
SSD1306_SETDISPLAYOFFSET, 0x00,
SSD1306_SETDISPLAYCLOCKDIV, 0xF0,
SSD1306_SETPRECHARGE, 0x22,
SSD1306_SETCOMPINS, 0x12,
SSD1306_SETVCOMDETECT, 0x20,
SSD1306_CHARGEPUMP, 0x14,
SSD1306_DISPLAYON
};
void disp_send_cmd(uint8_t cmd[], uint8_t size) {
i2c_send_addr((DISP_I2CADDR << 1) | 0);
i2c_send_data(DISP_SEND_CMD);
for (uint8_t i = 0; i < size; i++) {
i2c_send_data(cmd[i]);
}
i2c_stop();
}
void disp_send_data(uint8_t data[], uint16_t size) {
i2c_send_addr((DISP_I2CADDR << 1) | 0);
i2c_send_data(DISP_SEND_DATA);
for (uint16_t i = 0; i < size; i++) {
i2c_send_data(data[i]);
}
i2c_stop();
}
void disp_init(void) {
disp.max_posx = 15; //(DISP_WIDTH / DISP_FONT_WIDTH) + 0;
disp.max_posy = DISP_HEIGHT / DISP_FONT_HEIGHT;
uint8_t commands[sizeof(init_sequence)];
for (uint8_t i = 0; i < sizeof(init_sequence); i++) {
commands[i] = (pgm_read_byte(&init_sequence[i]));
}
disp_send_cmd(commands, sizeof(commands));
}
void disp_string(uint8_t posy, uint8_t posx, const char* str) {
size_t idx = 0;
while (str[idx] != '\0') {
char xchar = str[idx];
if ((posx > disp.max_posx) || (posy > disp.max_posy)) {
return;
}
if ((xchar < DISP_MIN_CHARCODE) || (xchar > DISP_MAX_CHARCODE)) {
xchar = '?';
}
uint8_t char_start_col = posx * DISP_FONT_WIDTH;
uint8_t char_end_col = char_start_col + (DISP_FONT_WIDTH - 1);
uint8_t char_start_page = posy * DISP_FONT_HEIGHT;
uint8_t char_end_page = char_start_page + (DISP_FONT_HEIGHT - 1);
uint8_t commands[] = {
SSD1306_SETCOLNADDR, char_start_col, char_end_col,
SSD1306_SETPAGEADDR, char_start_page, char_end_page
};
disp_send_cmd(commands, sizeof(commands));
uint8_t indx = ((uint8_t) xchar) - DISP_MIN_CHARCODE;
uint8_t data[DISP_CHAR_ARRLEN];
for (uint8_t i = 0; i < DISP_CHAR_ARRLEN; i++) {
data[i] = (pgm_read_byte(&(DISP_FONT[indx][i])));
}
disp_send_data(data, DISP_CHAR_ARRLEN);
posx++;
idx++;
}
}
#define DISP_CLEAR_BSIZE 8
#define DISP_PAGE_COUNT 8
void disp_clear(void) {
for (uint8_t p = 0; p < DISP_PAGE_COUNT; p++) {
for (uint8_t x = 0; x < (DISP_WIDTH / DISP_CLEAR_BSIZE); x++) {
uint8_t start_col = x * DISP_PAGE_HEIGHT;
uint8_t end_col = start_col + DISP_CLEAR_BSIZE - 1;
uint8_t commands[] = {
SSD1306_SETCOLNADDR, start_col, end_col,
SSD1306_SETPAGEADDR, p, p
};
disp_send_cmd(commands, sizeof(commands));
uint8_t data[DISP_CLEAR_BSIZE * DISP_PAGE_HEIGHT];
memset(data, 0x00, sizeof(data));
disp_send_data(data, sizeof(data));
}
}
}
void disp_set_invert(bool invert) {
uint8_t commands[1];
if (invert == true) {
commands[0] = SSD1306_INVERTDISPLAY;
} else {
commands[0] = SSD1306_NORMALDISPLAY;
}
disp_send_cmd(commands, sizeof(commands));
}
void disp_set_sleep(bool sleep) {
uint8_t commands[1];
if (sleep == true) {
commands[0] = SSD1306_DISPLAYOFF;
} else {
commands[0] = SSD1306_DISPLAYON;
}
disp_send_cmd(commands, sizeof(commands));
}
void disp_set_contrast(uint8_t contrast) {
uint8_t commands[2] = { SSD1306_SETCONTRAST, contrast };
disp_send_cmd(commands, sizeof(commands));
}
void disp_flip(uint8_t flipping) {
uint8_t commands[2] = {
SSD1306_COMSCANDEC,
SSD1306_SEGREMAP
};
switch (flipping) {
case DISP_FLIP_NORM:
commands[0] = SSD1306_COMSCANDEC;
commands[1] = SSD1306_SEGREMAP;
disp_send_cmd(commands, sizeof(commands));
break;
case DISP_FLIP_HORVER:
commands[0] = SSD1306_COMSCANINC;
commands[1] = SSD1306_SEGREMAP_MIRROR;
disp_send_cmd(commands, sizeof(commands));
break;
case DISP_FLIP_VERT:
commands[0] = SSD1306_COMSCANINC;
commands[1] = SSD1306_SEGREMAP;
disp_send_cmd(commands, sizeof(commands));
break;
case DISP_FLIS_HOR:
commands[0] = SSD1306_COMSCANDEC;
commands[1] = SSD1306_SEGREMAP_MIRROR;
disp_send_cmd(commands, sizeof(commands));
default:
break;
}
}
const uint8_t xxbasefont[][16] PROGMEM = {
{ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }, // 32 '
{ 0x00, 0x00, 0x00, 0xFC, 0xFC, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0D, 0x0D, 0x00, 0x00, 0x00 }, // 33 '!'
{ 0x00, 0x0E, 0x0E, 0x00, 0x00, 0x0E, 0x0E, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }, // 34 '"'
{ 0x20, 0xFC, 0xFC, 0x20, 0xFC, 0xFC, 0x20, 0x00, 0x01, 0x0F, 0x0F, 0x01, 0x0F, 0x0F, 0x01, 0x00 }, // 35 '#'
{ 0x70, 0xF8, 0x88, 0xFE, 0x88, 0x98, 0x10, 0x00, 0x04, 0x0C, 0x08, 0x3F, 0x08, 0x0F, 0x07, 0x00 }, // 36 '$'
{ 0x08, 0x1C, 0x14, 0xC8, 0xF0, 0x3C, 0x0C, 0x00, 0x00, 0x0C, 0x0F, 0x03, 0x04, 0x0A, 0x0E, 0x04 }, // 37 '%'
{ 0x80, 0xD8, 0x7C, 0xE4, 0xBC, 0xD8, 0x40, 0x00, 0x07, 0x0F, 0x08, 0x0C, 0x07, 0x0F, 0x08, 0x00 }, // 38 '&'
{ 0x00, 0x00, 0x00, 0x0E, 0x0E, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }, // 39 '''
{ 0x00, 0x00, 0xF0, 0xF8, 0x0C, 0x04, 0x00, 0x00, 0x00, 0x00, 0x03, 0x07, 0x0C, 0x08, 0x00, 0x00 }, // 40 '('
{ 0x00, 0x00, 0x04, 0x0C, 0xF8, 0xF0, 0x00, 0x00, 0x00, 0x00, 0x08, 0x0C, 0x07, 0x03, 0x00, 0x00 }, // 41 ')'
{ 0x80, 0xA0, 0xE0, 0xC0, 0xE0, 0xA0, 0x80, 0x00, 0x00, 0x02, 0x03, 0x01, 0x03, 0x02, 0x00, 0x00 }, // 42 '*'
{ 0x00, 0x80, 0x80, 0xE0, 0xE0, 0x80, 0x80, 0x00, 0x00, 0x00, 0x00, 0x03, 0x03, 0x00, 0x00, 0x00 }, // 43 '+'
{ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x10, 0x1C, 0x0C, 0x00, 0x00, 0x00 }, // 44 ','
{ 0x80, 0x80, 0x80, 0x80, 0x80, 0x80, 0x80, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }, // 45 '-'
{ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0C, 0x0C, 0x00, 0x00, 0x00 }, // 46 '.'
{ 0x00, 0x00, 0x00, 0xC0, 0xF0, 0x3C, 0x0C, 0x00, 0x00, 0x0C, 0x0F, 0x03, 0x00, 0x00, 0x00, 0x00 }, // 47 '/'
{ 0xF8, 0xFC, 0x84, 0xC4, 0x64, 0xFC, 0xF8, 0x00, 0x07, 0x0F, 0x09, 0x08, 0x08, 0x0F, 0x07, 0x00 }, // 48 '0'
{ 0x00, 0x10, 0x18, 0xFC, 0xFC, 0x00, 0x00, 0x00, 0x00, 0x08, 0x08, 0x0F, 0x0F, 0x08, 0x08, 0x00 }, // 49 '1'
{ 0x18, 0x1C, 0x04, 0x84, 0xC4, 0x7C, 0x38, 0x00, 0x0C, 0x0E, 0x0B, 0x09, 0x08, 0x08, 0x08, 0x00 }, // 50 '2'
{ 0x18, 0x1C, 0x44, 0x44, 0x44, 0xFC, 0xB8, 0x00, 0x06, 0x0E, 0x08, 0x08, 0x08, 0x0F, 0x07, 0x00 }, // 51 '3'
{ 0x80, 0xC0, 0x60, 0x30, 0x18, 0xFC, 0xFC, 0x00, 0x01, 0x01, 0x01, 0x01, 0x01, 0x0F, 0x0F, 0x00 }, // 52 '4'
{ 0x7C, 0x7C, 0x44, 0x44, 0x44, 0xC4, 0x84, 0x00, 0x04, 0x0C, 0x08, 0x08, 0x08, 0x0F, 0x07, 0x00 }, // 53 '5'
{ 0xF0, 0xF8, 0x4C, 0x44, 0x44, 0xC4, 0x80, 0x00, 0x07, 0x0F, 0x08, 0x08, 0x08, 0x0F, 0x07, 0x00 }, // 54 '6'
{ 0x04, 0x04, 0x04, 0x84, 0xE4, 0x7C, 0x1C, 0x00, 0x00, 0x00, 0x0E, 0x0F, 0x01, 0x00, 0x00, 0x00 }, // 55 '7'
{ 0xB8, 0xFC, 0x44, 0x44, 0x44, 0xFC, 0xB8, 0x00, 0x07, 0x0F, 0x08, 0x08, 0x08, 0x0F, 0x07, 0x00 }, // 56 '8'
{ 0x78, 0xFC, 0x84, 0x84, 0x84, 0xFC, 0xF8, 0x00, 0x00, 0x08, 0x08, 0x08, 0x0C, 0x07, 0x03, 0x00 }, // 57 '9'
{ 0x00, 0x00, 0x00, 0x60, 0x60, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0C, 0x0C, 0x00, 0x00, 0x00 }, // 58 ':'
{ 0x00, 0x00, 0x00, 0x60, 0x60, 0x00, 0x00, 0x00, 0x00, 0x00, 0x10, 0x1C, 0x0C, 0x00, 0x00, 0x00 }, // 59 ';'
{ 0x00, 0x80, 0xC0, 0x60, 0x30, 0x18, 0x08, 0x00, 0x00, 0x00, 0x01, 0x03, 0x06, 0x0C, 0x08, 0x00 }, // 60 '<'
{ 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x00, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x00 }, // 61 '='
{ 0x00, 0x08, 0x18, 0x30, 0x60, 0xC0, 0x80, 0x00, 0x00, 0x08, 0x0C, 0x06, 0x03, 0x01, 0x00, 0x00 }, // 62 '>'
{ 0x38, 0x3C, 0x04, 0x84, 0xC4, 0x7C, 0x38, 0x00, 0x00, 0x00, 0x00, 0x0D, 0x0D, 0x00, 0x00, 0x00 }, // 63 '?'
{ 0xF8, 0xFC, 0x04, 0xE4, 0x14, 0xFC, 0xF8, 0x00, 0x07, 0x0F, 0x08, 0x09, 0x0A, 0x0B, 0x0B, 0x00 }, // 64 '@'
{ 0xF8, 0xFC, 0x84, 0x84, 0x84, 0xFC, 0xF8, 0x00, 0x0F, 0x0F, 0x00, 0x00, 0x00, 0x0F, 0x0F, 0x00 }, // 65 'A'
{ 0xFC, 0xFC, 0x44, 0x44, 0x44, 0xFC, 0xB8, 0x00, 0x0F, 0x0F, 0x08, 0x08, 0x08, 0x0F, 0x07, 0x00 }, // 66 'B'
{ 0xF8, 0xFC, 0x04, 0x04, 0x04, 0x1C, 0x18, 0x00, 0x07, 0x0F, 0x08, 0x08, 0x08, 0x0E, 0x06, 0x00 }, // 67 'C'
{ 0xFC, 0xFC, 0x04, 0x04, 0x0C, 0xF8, 0xF0, 0x00, 0x0F, 0x0F, 0x08, 0x08, 0x0C, 0x07, 0x03, 0x00 }, // 68 'D'
{ 0xFC, 0xFC, 0x44, 0x44, 0x44, 0x04, 0x04, 0x00, 0x0F, 0x0F, 0x08, 0x08, 0x08, 0x08, 0x08, 0x00 }, // 69 'E'
{ 0xFC, 0xFC, 0x44, 0x44, 0x44, 0x04, 0x04, 0x00, 0x0F, 0x0F, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }, // 70 'F'
{ 0xF8, 0xFC, 0x04, 0x84, 0x84, 0x9C, 0x98, 0x00, 0x07, 0x0F, 0x08, 0x08, 0x08, 0x0F, 0x07, 0x00 }, // 71 'G'
{ 0xFC, 0xFC, 0x40, 0x40, 0x40, 0xFC, 0xFC, 0x00, 0x0F, 0x0F, 0x00, 0x00, 0x00, 0x0F, 0x0F, 0x00 }, // 72 'H'
{ 0x00, 0x00, 0x04, 0xFC, 0xFC, 0x04, 0x00, 0x00, 0x00, 0x00, 0x08, 0x0F, 0x0F, 0x08, 0x00, 0x00 }, // 73 'I'
{ 0x00, 0x00, 0x00, 0x04, 0xFC, 0xFC, 0x04, 0x00, 0x06, 0x0E, 0x08, 0x08, 0x0F, 0x07, 0x00, 0x00 }, // 74 'J'
{ 0xFC, 0xFC, 0xC0, 0xE0, 0x30, 0x1C, 0x0C, 0x00, 0x0F, 0x0F, 0x00, 0x01, 0x03, 0x0E, 0x0C, 0x00 }, // 75 'K'
{ 0xFC, 0xFC, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0F, 0x0F, 0x08, 0x08, 0x08, 0x08, 0x08, 0x00 }, // 76 'L'
{ 0xFC, 0xF8, 0x30, 0x60, 0x30, 0xF8, 0xFC, 0x00, 0x0F, 0x0F, 0x00, 0x00, 0x00, 0x0F, 0x0F, 0x00 }, // 77 'M'
{ 0xFC, 0xFC, 0x60, 0xC0, 0x80, 0xFC, 0xFC, 0x00, 0x0F, 0x0F, 0x00, 0x00, 0x01, 0x0F, 0x0F, 0x00 }, // 78 'N'
{ 0xF8, 0xFC, 0x04, 0x04, 0x04, 0xFC, 0xF8, 0x00, 0x07, 0x0F, 0x08, 0x08, 0x08, 0x0F, 0x07, 0x00 }, // 79 'O'
{ 0xFC, 0xFC, 0x84, 0x84, 0x84, 0xFC, 0x78, 0x00, 0x0F, 0x0F, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }, // 80 'P'
{ 0xF8, 0xFC, 0x04, 0x04, 0x04, 0xFC, 0xF8, 0x00, 0x07, 0x0F, 0x08, 0x0C, 0x0C, 0x1F, 0x17, 0x00 }, // 81 'Q'
{ 0xFC, 0xFC, 0x84, 0x84, 0x84, 0xFC, 0x78, 0x00, 0x0F, 0x0F, 0x01, 0x03, 0x06, 0x0C, 0x08, 0x00 }, // 82 'R'
{ 0x38, 0x7C, 0x44, 0x44, 0x44, 0xCC, 0x88, 0x00, 0x06, 0x0E, 0x08, 0x08, 0x08, 0x0F, 0x07, 0x00 }, // 83 'S'
{ 0x04, 0x04, 0x04, 0xFC, 0xFC, 0x04, 0x04, 0x04, 0x00, 0x00, 0x00, 0x0F, 0x0F, 0x00, 0x00, 0x00 }, // 84 'T'
{ 0xFC, 0xFC, 0x00, 0x00, 0x00, 0xFC, 0xFC, 0x00, 0x07, 0x0F, 0x08, 0x08, 0x08, 0x0F, 0x07, 0x00 }, // 85 'U'
{ 0x7C, 0xFC, 0x80, 0x00, 0x80, 0xFC, 0x7C, 0x00, 0x00, 0x03, 0x0F, 0x0C, 0x0F, 0x03, 0x00, 0x00 }, // 86 'V'
{ 0xFC, 0xFC, 0x00, 0x80, 0x00, 0xFC, 0xFC, 0x00, 0x0F, 0x07, 0x03, 0x01, 0x03, 0x07, 0x0F, 0x00 }, // 87 'W'
{ 0x0C, 0x3C, 0xF0, 0xC0, 0xF0, 0x3C, 0x0C, 0x00, 0x0C, 0x0F, 0x03, 0x00, 0x03, 0x0F, 0x0C, 0x00 }, // 88 'X'
{ 0x0C, 0x3C, 0x70, 0xC0, 0xC0, 0x70, 0x3C, 0x0C, 0x00, 0x00, 0x00, 0x0F, 0x0F, 0x00, 0x00, 0x00 }, // 89 'Y'
{ 0x04, 0x04, 0x84, 0xC4, 0x64, 0x3C, 0x1C, 0x00, 0x0E, 0x0F, 0x09, 0x08, 0x08, 0x08, 0x08, 0x00 }, // 90 'Z'
{ 0x00, 0x00, 0xFC, 0xFC, 0x04, 0x04, 0x00, 0x00, 0x00, 0x00, 0x0F, 0x0F, 0x08, 0x08, 0x00, 0x00 }, // 91 '['
{ 0x00, 0x0C, 0x3C, 0xF0, 0xC0, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, 0x0F, 0x0C, 0x00 }, // 92 '\'
{ 0x00, 0x00, 0x04, 0x04, 0xFC, 0xFC, 0x00, 0x00, 0x00, 0x00, 0x08, 0x08, 0x0F, 0x0F, 0x00, 0x00 }, // 93 ']'
{ 0x00, 0x08, 0x0C, 0x06, 0x06, 0x0C, 0x08, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }, // 94 '^'
{ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x00 }, // 95 '_'
{ 0x00, 0x00, 0x01, 0x03, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }, // 96 '`'
{ 0x00, 0xA0, 0xA0, 0xA0, 0xA0, 0xE0, 0xC0, 0x00, 0x07, 0x0F, 0x08, 0x08, 0x08, 0x0F, 0x0F, 0x00 }, // 97 'a'
{ 0xFC, 0xFC, 0x20, 0x20, 0x20, 0xE0, 0xC0, 0x00, 0x0F, 0x0F, 0x08, 0x08, 0x08, 0x0F, 0x07, 0x00 }, // 98 'b'
{ 0xC0, 0xE0, 0x20, 0x20, 0x20, 0x60, 0x40, 0x00, 0x07, 0x0F, 0x08, 0x08, 0x08, 0x0C, 0x04, 0x00 }, // 99 'c'
{ 0xC0, 0xE0, 0x20, 0x20, 0x20, 0xFC, 0xFC, 0x00, 0x07, 0x0F, 0x08, 0x08, 0x08, 0x0F, 0x0F, 0x00 }, // 100 'd'
{ 0xC0, 0xE0, 0x20, 0x20, 0x20, 0xE0, 0xC0, 0x00, 0x07, 0x0F, 0x09, 0x09, 0x09, 0x09, 0x01, 0x00 }, // 101 'e'
{ 0x20, 0x20, 0xF8, 0xFC, 0x24, 0x24, 0x04, 0x00, 0x00, 0x00, 0x0F, 0x0F, 0x00, 0x00, 0x00, 0x00 }, // 102 'f'
{ 0xC0, 0xE0, 0x20, 0x20, 0x20, 0xE0, 0xE0, 0x00, 0x07, 0x4F, 0x48, 0x48, 0x48, 0x7F, 0x3F, 0x00 }, // 103 'g'
{ 0xFC, 0xFC, 0x20, 0x20, 0x20, 0xE0, 0xC0, 0x00, 0x0F, 0x0F, 0x00, 0x00, 0x00, 0x0F, 0x0F, 0x00 }, // 104 'h'
{ 0x00, 0x00, 0x20, 0xEC, 0xEC, 0x00, 0x00, 0x00, 0x00, 0x00, 0x08, 0x0F, 0x0F, 0x08, 0x00, 0x00 }, // 105 'i'
{ 0x00, 0x00, 0x00, 0x00, 0x20, 0xEC, 0xEC, 0x00, 0x00, 0x30, 0x70, 0x40, 0x40, 0x7F, 0x3F, 0x00 }, // 106 'j'
{ 0xFC, 0xFC, 0x00, 0x80, 0xC0, 0x60, 0x20, 0x00, 0x0F, 0x0F, 0x01, 0x03, 0x06, 0x0C, 0x08, 0x00 }, // 107 'k'
{ 0x00, 0x00, 0x04, 0xFC, 0xFC, 0x00, 0x00, 0x00, 0x00, 0x00, 0x08, 0x0F, 0x0F, 0x08, 0x00, 0x00 }, // 108 'l'
{ 0xE0, 0xE0, 0x20, 0xE0, 0x20, 0xE0, 0xC0, 0x00, 0x0F, 0x0F, 0x00, 0x0F, 0x00, 0x0F, 0x0F, 0x00 }, // 109 'm'
{ 0xE0, 0xE0, 0x20, 0x20, 0x20, 0xE0, 0xC0, 0x00, 0x0F, 0x0F, 0x00, 0x00, 0x00, 0x0F, 0x0F, 0x00 }, // 110 'n'
{ 0xC0, 0xE0, 0x20, 0x20, 0x20, 0xE0, 0xC0, 0x00, 0x07, 0x0F, 0x08, 0x08, 0x08, 0x0F, 0x07, 0x00 }, // 111 'o'
{ 0xE0, 0xE0, 0x20, 0x20, 0x20, 0xE0, 0xC0, 0x00, 0x7F, 0x7F, 0x08, 0x08, 0x08, 0x0F, 0x07, 0x00 }, // 112 'p'
{ 0xC0, 0xE0, 0x20, 0x20, 0x20, 0xE0, 0xE0, 0x00, 0x07, 0x0F, 0x08, 0x08, 0x08, 0x7F, 0x7F, 0x00 }, // 113 'q'
{ 0xE0, 0xE0, 0xC0, 0x60, 0x20, 0x20, 0x20, 0x00, 0x0F, 0x0F, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }, // 114 'r'
{ 0xC0, 0xE0, 0x20, 0x20, 0x20, 0x20, 0x20, 0x00, 0x08, 0x09, 0x09, 0x09, 0x09, 0x0F, 0x06, 0x00 }, // 115 's'
{ 0x20, 0x20, 0xFC, 0xFC, 0x20, 0x20, 0x00, 0x00, 0x00, 0x00, 0x07, 0x0F, 0x08, 0x08, 0x08, 0x00 }, // 116 't'
{ 0xE0, 0xE0, 0x00, 0x00, 0x00, 0xE0, 0xE0, 0x00, 0x07, 0x0F, 0x08, 0x08, 0x08, 0x0F, 0x0F, 0x00 }, // 117 'u'
{ 0xE0, 0xE0, 0x00, 0x00, 0x00, 0xE0, 0xE0, 0x00, 0x00, 0x03, 0x0F, 0x0C, 0x0F, 0x03, 0x00, 0x00 }, // 118 'v'
{ 0xE0, 0xE0, 0x00, 0x80, 0x00, 0xE0, 0xE0, 0x00, 0x07, 0x0F, 0x08, 0x0F, 0x08, 0x0F, 0x07, 0x00 }, // 119 'w'
{ 0x60, 0xE0, 0x80, 0x00, 0x80, 0xE0, 0x60, 0x00, 0x0C, 0x0E, 0x03, 0x01, 0x03, 0x0E, 0x0C, 0x00 }, // 120 'x'
{ 0xE0, 0xE0, 0x00, 0x00, 0x00, 0xE0, 0xE0, 0x00, 0x07, 0x4F, 0x48, 0x48, 0x48, 0x7F, 0x3F, 0x00 }, // 121 'y'
{ 0x20, 0x20, 0x20, 0xA0, 0xE0, 0x60, 0x20, 0x00, 0x0C, 0x0E, 0x0B, 0x09, 0x08, 0x08, 0x08, 0x00 }, // 122 'z'
{ 0x00, 0x40, 0xF8, 0xBC, 0x04, 0x04, 0x00, 0x00, 0x00, 0x00, 0x07, 0x0F, 0x08, 0x08, 0x00, 0x00 }, // 123 '{'
{ 0x00, 0x00, 0x00, 0xFC, 0xFC, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0F, 0x0F, 0x00, 0x00, 0x00 }, // 124 '|'
{ 0x00, 0x04, 0x04, 0xBC, 0xF8, 0x40, 0x00, 0x00, 0x00, 0x08, 0x08, 0x0F, 0x07, 0x00, 0x00, 0x00 }, // 125 '}'
{ 0x0C, 0x0E, 0x02, 0x06, 0x0C, 0x08, 0x0E, 0x06, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 } // 126 '~'
};
const uint8_t basefont[][16] PROGMEM = {
{ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }, // 32 '
{ 0x00, 0x00, 0x00, 0xFC, 0xFC, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0D, 0x0D, 0x00, 0x00, 0x00 }, // 33 '!'
{ 0x00, 0x0E, 0x0E, 0x00, 0x00, 0x0E, 0x0E, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }, // 34 '"'
{ 0x20, 0xFC, 0xFC, 0x20, 0xFC, 0xFC, 0x20, 0x00, 0x01, 0x0F, 0x0F, 0x01, 0x0F, 0x0F, 0x01, 0x00 }, // 35 '#'
{ 0x70, 0xF8, 0x88, 0xFE, 0x88, 0x98, 0x10, 0x00, 0x04, 0x0C, 0x08, 0x3F, 0x08, 0x0F, 0x07, 0x00 }, // 36 '$'
{ 0x08, 0x1C, 0x14, 0xC8, 0xF0, 0x3C, 0x0C, 0x00, 0x00, 0x0C, 0x0F, 0x03, 0x04, 0x0A, 0x0E, 0x04 }, // 37 '%'
{ 0x80, 0xD8, 0x7C, 0xE4, 0xBC, 0xD8, 0x40, 0x00, 0x07, 0x0F, 0x08, 0x0C, 0x07, 0x0F, 0x08, 0x00 }, // 38 '&'
{ 0x00, 0x00, 0x00, 0x0E, 0x0E, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }, // 39 '''
{ 0x00, 0x00, 0xF0, 0xF8, 0x0C, 0x04, 0x00, 0x00, 0x00, 0x00, 0x03, 0x07, 0x0C, 0x08, 0x00, 0x00 }, // 40 '('
{ 0x00, 0x00, 0x04, 0x0C, 0xF8, 0xF0, 0x00, 0x00, 0x00, 0x00, 0x08, 0x0C, 0x07, 0x03, 0x00, 0x00 }, // 41 ')'
{ 0x80, 0xA0, 0xE0, 0xC0, 0xE0, 0xA0, 0x80, 0x00, 0x00, 0x02, 0x03, 0x01, 0x03, 0x02, 0x00, 0x00 }, // 42 '*'
{ 0x00, 0x80, 0x80, 0xE0, 0xE0, 0x80, 0x80, 0x00, 0x00, 0x00, 0x00, 0x03, 0x03, 0x00, 0x00, 0x00 }, // 43 '+'
{ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x10, 0x1C, 0x0C, 0x00, 0x00, 0x00 }, // 44 ','
{ 0x80, 0x80, 0x80, 0x80, 0x80, 0x80, 0x80, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }, // 45 '-'
{ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0C, 0x0C, 0x00, 0x00, 0x00 }, // 46 '.'
{ 0x00, 0x00, 0x00, 0xC0, 0xF0, 0x3C, 0x0C, 0x00, 0x00, 0x0C, 0x0F, 0x03, 0x00, 0x00, 0x00, 0x00 }, // 47 '/'
{ 0xF8, 0xFC, 0x84, 0xC4, 0x64, 0xFC, 0xF8, 0x00, 0x07, 0x0F, 0x09, 0x08, 0x08, 0x0F, 0x07, 0x00 }, // 48 '0'
{ 0x00, 0x10, 0x18, 0xFC, 0xFC, 0x00, 0x00, 0x00, 0x00, 0x08, 0x08, 0x0F, 0x0F, 0x08, 0x08, 0x00 }, // 49 '1'
{ 0x18, 0x1C, 0x04, 0x84, 0xC4, 0x7C, 0x38, 0x00, 0x0C, 0x0E, 0x0B, 0x09, 0x08, 0x08, 0x08, 0x00 }, // 50 '2'
{ 0x18, 0x1C, 0x44, 0x44, 0x44, 0xFC, 0xB8, 0x00, 0x06, 0x0E, 0x08, 0x08, 0x08, 0x0F, 0x07, 0x00 }, // 51 '3'
{ 0x80, 0xC0, 0x60, 0x30, 0x18, 0xFC, 0xFC, 0x00, 0x01, 0x01, 0x01, 0x01, 0x01, 0x0F, 0x0F, 0x00 }, // 52 '4'
{ 0x7C, 0x7C, 0x44, 0x44, 0x44, 0xC4, 0x84, 0x00, 0x04, 0x0C, 0x08, 0x08, 0x08, 0x0F, 0x07, 0x00 }, // 53 '5'
{ 0xF0, 0xF8, 0x4C, 0x44, 0x44, 0xC4, 0x80, 0x00, 0x07, 0x0F, 0x08, 0x08, 0x08, 0x0F, 0x07, 0x00 }, // 54 '6'
{ 0x04, 0x04, 0x04, 0x84, 0xE4, 0x7C, 0x1C, 0x00, 0x00, 0x00, 0x0E, 0x0F, 0x01, 0x00, 0x00, 0x00 }, // 55 '7'
{ 0xB8, 0xFC, 0x44, 0x44, 0x44, 0xFC, 0xB8, 0x00, 0x07, 0x0F, 0x08, 0x08, 0x08, 0x0F, 0x07, 0x00 }, // 56 '8'
{ 0x78, 0xFC, 0x84, 0x84, 0x84, 0xFC, 0xF8, 0x00, 0x00, 0x08, 0x08, 0x08, 0x0C, 0x07, 0x03, 0x00 }, // 57 '9'
{ 0x00, 0x00, 0x00, 0x60, 0x60, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0C, 0x0C, 0x00, 0x00, 0x00 }, // 58 ':'
{ 0x00, 0x00, 0x00, 0x60, 0x60, 0x00, 0x00, 0x00, 0x00, 0x00, 0x10, 0x1C, 0x0C, 0x00, 0x00, 0x00 }, // 59 ';'
{ 0x00, 0x80, 0xC0, 0x60, 0x30, 0x18, 0x08, 0x00, 0x00, 0x00, 0x01, 0x03, 0x06, 0x0C, 0x08, 0x00 }, // 60 '<'
{ 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x00, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x00 }, // 61 '='
{ 0x00, 0x08, 0x18, 0x30, 0x60, 0xC0, 0x80, 0x00, 0x00, 0x08, 0x0C, 0x06, 0x03, 0x01, 0x00, 0x00 }, // 62 '>'
{ 0x38, 0x3C, 0x04, 0x84, 0xC4, 0x7C, 0x38, 0x00, 0x00, 0x00, 0x00, 0x0D, 0x0D, 0x00, 0x00, 0x00 }, // 63 '?'
{ 0xF8, 0xFC, 0x04, 0xE4, 0x14, 0xFC, 0xF8, 0x00, 0x07, 0x0F, 0x08, 0x09, 0x0A, 0x0B, 0x0B, 0x00 }, // 64 '@'
{ 0xF8, 0xFC, 0x84, 0x84, 0x84, 0xFC, 0xF8, 0x00, 0x0F, 0x0F, 0x00, 0x00, 0x00, 0x0F, 0x0F, 0x00 }, // 65 'A'
{ 0xFC, 0xFC, 0x44, 0x44, 0x44, 0xFC, 0xB8, 0x00, 0x0F, 0x0F, 0x08, 0x08, 0x08, 0x0F, 0x07, 0x00 }, // 66 'B'
{ 0xF8, 0xFC, 0x04, 0x04, 0x04, 0x1C, 0x18, 0x00, 0x07, 0x0F, 0x08, 0x08, 0x08, 0x0E, 0x06, 0x00 }, // 67 'C'
{ 0xFC, 0xFC, 0x04, 0x04, 0x0C, 0xF8, 0xF0, 0x00, 0x0F, 0x0F, 0x08, 0x08, 0x0C, 0x07, 0x03, 0x00 }, // 68 'D'
{ 0xFC, 0xFC, 0x44, 0x44, 0x44, 0x04, 0x04, 0x00, 0x0F, 0x0F, 0x08, 0x08, 0x08, 0x08, 0x08, 0x00 }, // 69 'E'
{ 0xFC, 0xFC, 0x44, 0x44, 0x44, 0x04, 0x04, 0x00, 0x0F, 0x0F, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }, // 70 'F'
{ 0xF8, 0xFC, 0x04, 0x84, 0x84, 0x9C, 0x98, 0x00, 0x07, 0x0F, 0x08, 0x08, 0x08, 0x0F, 0x07, 0x00 }, // 71 'G'
{ 0xFC, 0xFC, 0x40, 0x40, 0x40, 0xFC, 0xFC, 0x00, 0x0F, 0x0F, 0x00, 0x00, 0x00, 0x0F, 0x0F, 0x00 }, // 72 'H'
{ 0x00, 0x00, 0x04, 0xFC, 0xFC, 0x04, 0x00, 0x00, 0x00, 0x00, 0x08, 0x0F, 0x0F, 0x08, 0x00, 0x00 }, // 73 'I'
{ 0x00, 0x00, 0x00, 0x04, 0xFC, 0xFC, 0x04, 0x00, 0x06, 0x0E, 0x08, 0x08, 0x0F, 0x07, 0x00, 0x00 }, // 74 'J'
{ 0xFC, 0xFC, 0xC0, 0xE0, 0x30, 0x1C, 0x0C, 0x00, 0x0F, 0x0F, 0x00, 0x01, 0x03, 0x0E, 0x0C, 0x00 }, // 75 'K'
{ 0xFC, 0xFC, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0F, 0x0F, 0x08, 0x08, 0x08, 0x08, 0x08, 0x00 }, // 76 'L'
{ 0xFC, 0xF8, 0x30, 0x60, 0x30, 0xF8, 0xFC, 0x00, 0x0F, 0x0F, 0x00, 0x00, 0x00, 0x0F, 0x0F, 0x00 }, // 77 'M'
{ 0xFC, 0xFC, 0x60, 0xC0, 0x80, 0xFC, 0xFC, 0x00, 0x0F, 0x0F, 0x00, 0x00, 0x01, 0x0F, 0x0F, 0x00 }, // 78 'N'
{ 0xF8, 0xFC, 0x04, 0x04, 0x04, 0xFC, 0xF8, 0x00, 0x07, 0x0F, 0x08, 0x08, 0x08, 0x0F, 0x07, 0x00 }, // 79 'O'
{ 0xFC, 0xFC, 0x84, 0x84, 0x84, 0xFC, 0x78, 0x00, 0x0F, 0x0F, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }, // 80 'P'
{ 0xF8, 0xFC, 0x04, 0x04, 0x04, 0xFC, 0xF8, 0x00, 0x07, 0x0F, 0x08, 0x0C, 0x0C, 0x1F, 0x17, 0x00 }, // 81 'Q'
{ 0xFC, 0xFC, 0x84, 0x84, 0x84, 0xFC, 0x78, 0x00, 0x0F, 0x0F, 0x01, 0x03, 0x06, 0x0C, 0x08, 0x00 }, // 82 'R'
{ 0x38, 0x7C, 0x44, 0x44, 0x44, 0xCC, 0x88, 0x00, 0x06, 0x0E, 0x08, 0x08, 0x08, 0x0F, 0x07, 0x00 }, // 83 'S'
{ 0x04, 0x04, 0x04, 0xFC, 0xFC, 0x04, 0x04, 0x04, 0x00, 0x00, 0x00, 0x0F, 0x0F, 0x00, 0x00, 0x00 }, // 84 'T'
{ 0xFC, 0xFC, 0x00, 0x00, 0x00, 0xFC, 0xFC, 0x00, 0x07, 0x0F, 0x08, 0x08, 0x08, 0x0F, 0x07, 0x00 }, // 85 'U'
{ 0x7C, 0xFC, 0x80, 0x00, 0x80, 0xFC, 0x7C, 0x00, 0x00, 0x03, 0x0F, 0x0C, 0x0F, 0x03, 0x00, 0x00 }, // 86 'V'
{ 0xFC, 0xFC, 0x00, 0x80, 0x00, 0xFC, 0xFC, 0x00, 0x0F, 0x07, 0x03, 0x01, 0x03, 0x07, 0x0F, 0x00 }, // 87 'W'
{ 0x0C, 0x3C, 0xF0, 0xC0, 0xF0, 0x3C, 0x0C, 0x00, 0x0C, 0x0F, 0x03, 0x00, 0x03, 0x0F, 0x0C, 0x00 }, // 88 'X'
{ 0x0C, 0x3C, 0x70, 0xC0, 0xC0, 0x70, 0x3C, 0x0C, 0x00, 0x00, 0x00, 0x0F, 0x0F, 0x00, 0x00, 0x00 }, // 89 'Y'
{ 0x04, 0x04, 0x84, 0xC4, 0x64, 0x3C, 0x1C, 0x00, 0x0E, 0x0F, 0x09, 0x08, 0x08, 0x08, 0x08, 0x00 }, // 90 'Z'
{ 0x00, 0x00, 0xFC, 0xFC, 0x04, 0x04, 0x00, 0x00, 0x00, 0x00, 0x0F, 0x0F, 0x08, 0x08, 0x00, 0x00 }, // 91 '['
{ 0x00, 0x0C, 0x3C, 0xF0, 0xC0, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, 0x0F, 0x0C, 0x00 }, // 92 '\'
{ 0x00, 0x00, 0x04, 0x04, 0xFC, 0xFC, 0x00, 0x00, 0x00, 0x00, 0x08, 0x08, 0x0F, 0x0F, 0x00, 0x00 }, // 93 ']'
{ 0x00, 0x08, 0x0C, 0x06, 0x06, 0x0C, 0x08, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }, // 94 '^'
{ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x00 }, // 95 '_'
{ 0x00, 0x00, 0x01, 0x03, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }, // 96 '`'
{ 0x00, 0xA0, 0xA0, 0xA0, 0xA0, 0xE0, 0xC0, 0x00, 0x07, 0x0F, 0x08, 0x08, 0x08, 0x0F, 0x0F, 0x00 }, // 97 'a'
{ 0xFC, 0xFC, 0x20, 0x20, 0x20, 0xE0, 0xC0, 0x00, 0x0F, 0x0F, 0x08, 0x08, 0x08, 0x0F, 0x07, 0x00 }, // 98 'b'
{ 0xC0, 0xE0, 0x20, 0x20, 0x20, 0x60, 0x40, 0x00, 0x07, 0x0F, 0x08, 0x08, 0x08, 0x0C, 0x04, 0x00 }, // 99 'c'
{ 0xC0, 0xE0, 0x20, 0x20, 0x20, 0xFC, 0xFC, 0x00, 0x07, 0x0F, 0x08, 0x08, 0x08, 0x0F, 0x0F, 0x00 }, // 100 'd'
{ 0xC0, 0xE0, 0x20, 0x20, 0x20, 0xE0, 0xC0, 0x00, 0x07, 0x0F, 0x09, 0x09, 0x09, 0x09, 0x01, 0x00 }, // 101 'e'
{ 0x20, 0x20, 0xF8, 0xFC, 0x24, 0x24, 0x04, 0x00, 0x00, 0x00, 0x0F, 0x0F, 0x00, 0x00, 0x00, 0x00 }, // 102 'f'
{ 0xC0, 0xE0, 0x20, 0x20, 0x20, 0xE0, 0xE0, 0x00, 0x07, 0x4F, 0x48, 0x48, 0x48, 0x7F, 0x3F, 0x00 }, // 103 'g'
{ 0xFC, 0xFC, 0x20, 0x20, 0x20, 0xE0, 0xC0, 0x00, 0x0F, 0x0F, 0x00, 0x00, 0x00, 0x0F, 0x0F, 0x00 }, // 104 'h'
{ 0x00, 0x00, 0x20, 0xEC, 0xEC, 0x00, 0x00, 0x00, 0x00, 0x00, 0x08, 0x0F, 0x0F, 0x08, 0x00, 0x00 }, // 105 'i'
{ 0x00, 0x00, 0x00, 0x00, 0x20, 0xEC, 0xEC, 0x00, 0x00, 0x30, 0x70, 0x40, 0x40, 0x7F, 0x3F, 0x00 }, // 106 'j'
{ 0xFC, 0xFC, 0x00, 0x80, 0xC0, 0x60, 0x20, 0x00, 0x0F, 0x0F, 0x01, 0x03, 0x06, 0x0C, 0x08, 0x00 }, // 107 'k'
{ 0x00, 0x00, 0x04, 0xFC, 0xFC, 0x00, 0x00, 0x00, 0x00, 0x00, 0x08, 0x0F, 0x0F, 0x08, 0x00, 0x00 }, // 108 'l'
{ 0xE0, 0xE0, 0x20, 0xE0, 0x20, 0xE0, 0xC0, 0x00, 0x0F, 0x0F, 0x00, 0x0F, 0x00, 0x0F, 0x0F, 0x00 }, // 109 'm'
{ 0xE0, 0xE0, 0x20, 0x20, 0x20, 0xE0, 0xC0, 0x00, 0x0F, 0x0F, 0x00, 0x00, 0x00, 0x0F, 0x0F, 0x00 }, // 110 'n'
{ 0xC0, 0xE0, 0x20, 0x20, 0x20, 0xE0, 0xC0, 0x00, 0x07, 0x0F, 0x08, 0x08, 0x08, 0x0F, 0x07, 0x00 }, // 111 'o'
{ 0xE0, 0xE0, 0x20, 0x20, 0x20, 0xE0, 0xC0, 0x00, 0x7F, 0x7F, 0x08, 0x08, 0x08, 0x0F, 0x07, 0x00 }, // 112 'p'
{ 0xC0, 0xE0, 0x20, 0x20, 0x20, 0xE0, 0xE0, 0x00, 0x07, 0x0F, 0x08, 0x08, 0x08, 0x7F, 0x7F, 0x00 }, // 113 'q'
{ 0xE0, 0xE0, 0xC0, 0x60, 0x20, 0x20, 0x20, 0x00, 0x0F, 0x0F, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }, // 114 'r'
{ 0xC0, 0xE0, 0x20, 0x20, 0x20, 0x20, 0x20, 0x00, 0x08, 0x09, 0x09, 0x09, 0x09, 0x0F, 0x06, 0x00 }, // 115 's'
{ 0x20, 0x20, 0xFC, 0xFC, 0x20, 0x20, 0x00, 0x00, 0x00, 0x00, 0x07, 0x0F, 0x08, 0x08, 0x08, 0x00 }, // 116 't'
{ 0xE0, 0xE0, 0x00, 0x00, 0x00, 0xE0, 0xE0, 0x00, 0x07, 0x0F, 0x08, 0x08, 0x08, 0x0F, 0x0F, 0x00 }, // 117 'u'
{ 0xE0, 0xE0, 0x00, 0x00, 0x00, 0xE0, 0xE0, 0x00, 0x00, 0x03, 0x0F, 0x0C, 0x0F, 0x03, 0x00, 0x00 }, // 118 'v'
{ 0xE0, 0xE0, 0x00, 0x80, 0x00, 0xE0, 0xE0, 0x00, 0x07, 0x0F, 0x08, 0x0F, 0x08, 0x0F, 0x07, 0x00 }, // 119 'w'
{ 0x60, 0xE0, 0x80, 0x00, 0x80, 0xE0, 0x60, 0x00, 0x0C, 0x0E, 0x03, 0x01, 0x03, 0x0E, 0x0C, 0x00 }, // 120 'x'
{ 0xE0, 0xE0, 0x00, 0x00, 0x00, 0xE0, 0xE0, 0x00, 0x07, 0x4F, 0x48, 0x48, 0x48, 0x7F, 0x3F, 0x00 }, // 121 'y'
{ 0x20, 0x20, 0x20, 0xA0, 0xE0, 0x60, 0x20, 0x00, 0x0C, 0x0E, 0x0B, 0x09, 0x08, 0x08, 0x08, 0x00 }, // 122 'z'
{ 0x00, 0x40, 0xF8, 0xBC, 0x04, 0x04, 0x00, 0x00, 0x00, 0x00, 0x07, 0x0F, 0x08, 0x08, 0x00, 0x00 }, // 123 '{'
{ 0x00, 0x00, 0x00, 0xFC, 0xFC, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0F, 0x0F, 0x00, 0x00, 0x00 }, // 124 '|'
{ 0x00, 0x04, 0x04, 0xBC, 0xF8, 0x40, 0x00, 0x00, 0x00, 0x08, 0x08, 0x0F, 0x07, 0x00, 0x00, 0x00 }, // 125 '}'
{ 0x0C, 0x0E, 0x02, 0x06, 0x0C, 0x08, 0x0E, 0x06, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 } // 126 '~'
};

26
disp.h Normal file
View File

@@ -0,0 +1,26 @@
#ifndef LCD_H_QWERTY
#define LCD_H_QWERTY
#include <inttypes.h>
#include <avr/pgmspace.h>
#define DISP_FLIP_NORM 0
#define DISP_FLIP_HORVER 1
#define DISP_FLIP_VERT 2
#define DISP_FLIS_HOR 3
void disp_init(void);
void disp_string(uint8_t posy, uint8_t posx, const char* str);
void disp_send_cmd(uint8_t cmd[], uint8_t size);
void disp_send_data(uint8_t data[], uint16_t size);
void disp_set_invert(bool invert);
void disp_set_sleep(bool sleep);
void disp_set_contrast(uint8_t contrast);
void disp_clear(void);
void disp_flip(uint8_t flipping);
#endif

BIN
docs/atmega328p.pdf Normal file

Binary file not shown.

27005
docs/micro-pa50.pdf Normal file

File diff suppressed because it is too large Load Diff

34
eeprom.c Normal file
View File

@@ -0,0 +1,34 @@
#include <stdint.h>
#include <avr/io.h>
#include <eeprom.h>
#include <tool.h>
void eeprom_write_byte(uint16_t address, uint8_t byte) {
while (EECR & BIT(EEPE));
EEAR = address;
EEDR = byte;
REG_SETUP_BIT(EECR, EEMPE);
REG_SETUP_BIT(EECR, EEPE);
}
uint8_t eeprom_read_byte(uint16_t address) {
while (EECR & BIT(EEPE));
EEAR = address;
REG_SETUP_BIT(EECR, EERE);
return EEDR;
}
void eeprom_write_bytes(uint16_t address, uint8_t* data, uint16_t size) {
for (uint16_t i = 0; i < size; i++) {
eeprom_write_byte(address + i, data[i]);
}
}
void eeprom_read_bytes(uint16_t address, uint8_t* data, uint16_t size) {
for (uint16_t i = 0; i < size; i++) {
data[i] = eeprom_read_byte(address + i);
}
}

12
eeprom.h Normal file
View File

@@ -0,0 +1,12 @@
#ifndef _EEPROM_H_QWERTY
#define _EEPROM_H 1
#include <stdint.h>
void eeprom_write_byte(uint16_t address, uint8_t byte);
uint8_t eeprom_read_bite(uint16_t address);
void eeprom_write_bytes(uint16_t address, uint8_t* data, uint16_t size);
void eeprom_read_bytes(uint16_t address, uint8_t* data, uint16_t size);
#endif

128
fifo.c Normal file
View File

@@ -0,0 +1,128 @@
/*
* Copyright 2017 Oleg Borodin <onborodin@gmail.com>
*
*/
#include <stdint.h>
#include <stdbool.h>
#include <string.h>
#include <stdio.h>
#include <fifo.h>
#include <tool.h>
void fifo_init(fifo_t * fifo, uint8_t * buffer, uint8_t buffer_len) {
if (fifo && buffer) {
memset((void **)buffer, 0, buffer_len);
fifo->buffer_len = buffer_len;
fifo->buffer = buffer;
fifo->head = 0;
fifo->tail = 0;
}
}
uint8_t fifo_count(const fifo_t * fifo) {
if (fifo) {
return (fifo->head - fifo->tail);
}
return 0;
}
bool fifo_full(const fifo_t * fifo) {
if (fifo) {
return (fifo_count(fifo) == fifo->buffer_len);
}
return true;
}
bool fifo_empty(const fifo_t * fifo) {
if (fifo) {
return (fifo_count(fifo) == 0);
}
return true;
}
uint8_t fifo_peek(const fifo_t * fifo) {
uint8_t data = 0;
if (!fifo_empty(fifo)) {
data = fifo->buffer[fifo->tail % fifo->buffer_len];
}
return data;
}
bool fifo_back(fifo_t * fifo) {
if (!fifo_empty(fifo)) {
fifo->head--;
return true;
}
return false;
}
uint8_t fifo_getc(fifo_t * fifo) {
uint8_t data = 0;
if (!fifo_empty(fifo)) {
data = fifo->buffer[fifo->tail % fifo->buffer_len];
fifo->tail++;
}
return data;
}
bool fifo_putc(fifo_t * fifo, uint8_t data) {
bool status = false;
if (fifo) {
if (!fifo_full(fifo)) {
fifo->buffer[fifo->head % fifo->buffer_len] = data;
fifo->head++;
status = true;
}
}
return status;
}
uint8_t fifo_puts(fifo_t * fifo, uint8_t * string) {
if (fifo) {
for (uint8_t i = 0; i < str_len(string); i++) {
if (!fifo_putc(fifo, string[i]))
return i;
}
}
return 0;
}
bool fifo_scanc(fifo_t * fifo, uint8_t c) {
if (fifo) {
if (!fifo_empty(fifo)) {
uint8_t tail = fifo->tail;
for (uint8_t i = 0; i < fifo_count(fifo); i++) {
uint8_t data = fifo->buffer[tail % fifo->buffer_len];
if (data == c) {
return true;
}
tail++;
}
}
return false;
}
return false;
}
uint8_t fifo_get_token(fifo_t * fifo, uint8_t * str, uint8_t len, uint8_t term) {
if (fifo) {
memset((void *)str, 0, len);
if (fifo_scanc(fifo, term) && str) {
uint8_t i = 0, c = 0;
while ((c = fifo_getc(fifo)) != 0 && c != term && i < len) {
str[i] = c;
i++;
}
return i;
}
return 0;
}
return 0;
}

32
fifo.h Normal file
View File

@@ -0,0 +1,32 @@
/*
* Copyright 2017 Oleg Borodin <onborodin@gmail.com>
*
*/
#ifndef UART_H_IUI
#define UART_H_IUI
#ifndef FIFO_BUFFER_SIZE
#define FIFO_BUFFER_SIZE 128
#endif
typedef struct fifo {
volatile uint8_t head;
volatile uint8_t tail;
volatile uint8_t *buffer;
uint8_t buffer_len;
} fifo_t;
void fifo_init(fifo_t * b, uint8_t * buffer, uint8_t buffer_len);
uint8_t fifo_count(const fifo_t * b);
bool fifo_full(const fifo_t * b);
bool fifo_empty(const fifo_t * b);
uint8_t fifo_peek(const fifo_t * b);
uint8_t fifo_getc(fifo_t * b);
bool fifo_putc(fifo_t * b, uint8_t data);
uint8_t fifo_puts(fifo_t * b, uint8_t * str);
bool fifo_scanc(fifo_t * b, uint8_t c);
uint8_t fifo_get_token(fifo_t * b, uint8_t * str, uint8_t len, uint8_t);
bool fifo_back(fifo_t * b);
#endif

93
i2c.c Normal file
View File

@@ -0,0 +1,93 @@
#include <i2c.h>
uint8_t i2c_error;
void i2c_init(void) {
switch (PSC_I2C) {
case 4:
TWSR = 0x1;
break;
case 16:
TWSR = 0x2;
break;
case 64:
TWSR = 0x3;
break;
default:
TWSR = 0x00;
break;
}
TWBR = (uint8_t) SET_TWBR;
TWCR = (1 << TWEN);
}
void i2c_send_addr(uint8_t i2c_addr) {
TWCR = (1 << TWINT) | (1 << TWSTA) | (1 << TWEN);
uint16_t timeout = F_CPU / F_I2C * 2.0;
while ((TWCR & (1 << TWINT)) == 0 && timeout != 0) {
timeout--;
if (timeout == 0) {
i2c_error |= (1 << I2C_ERR_START);
return;
}
};
TWDR = i2c_addr;
TWCR = (1 << TWINT) | (1 << TWEN);
timeout = F_CPU / F_I2C * 2.0;
while ((TWCR & (1 << TWINT)) == 0 && timeout != 0) {
timeout--;
if (timeout == 0) {
i2c_error |= (1 << I2C_ERR_SENDADRESS);
return;
}
};
}
void i2c_stop(void) {
TWCR = (1 << TWINT) | (1 << TWSTO) | (1 << TWEN);
}
void i2c_send_data(uint8_t byte) {
TWDR = byte;
TWCR = (1 << TWINT) | (1 << TWEN);
uint16_t timeout = F_CPU / F_I2C * 2.0;
while ((TWCR & (1 << TWINT)) == 0 && timeout != 0) {
timeout--;
if (timeout == 0) {
i2c_error |= (1 << I2C_ERR_BYTE);
return;
}
};
}
uint8_t i2c_read_ack(void) {
TWCR = (1 << TWINT) | (1 << TWEN) | (1 << TWEA);
uint16_t timeout = F_CPU / F_I2C * 2.0;
while ((TWCR & (1 << TWINT)) == 0 && timeout != 0) {
timeout--;
if (timeout == 0) {
i2c_error |= (1 << I2C_ERR_READACK);
return 0;
}
};
return TWDR;
}
uint8_t i2c_read_nack(void) {
TWCR = (1 << TWINT) | (1 << TWEN);
uint16_t timeout = F_CPU / F_I2C * 2.0;
while ((TWCR & (1 << TWINT)) == 0 && timeout != 0) {
timeout--;
if (timeout == 0) {
i2c_error |= (1 << I2C_ERR_READNACK);
return 0;
}
};
return TWDR;
}

30
i2c.h Normal file
View File

@@ -0,0 +1,30 @@
#ifndef I2C_H_QWERTY
#define I2C_H_QWERTY
#define PSC_I2C 1 // I2C prescaler
#define F_I2C 400000UL // I2C Clock
#define SET_TWBR (F_CPU/F_I2C-16UL)/(PSC_I2C*2UL)
#include <stdio.h>
#include <avr/io.h>
extern uint8_t i2c_error;
#define I2C_ERR_START 0 // Timeout start-condition
#define I2C_ERR_SENDADRESS 1 // Timeout device-adress
#define I2C_ERR_BYTE 2 // Timeout byte-transmission
#define I2C_ERR_READACK 3 // Timeout read acknowledge
#define I2C_ERR_READNACK 4 // Timeout read nacknowledge
void i2c_init(void);
void i2c_send_addr(uint8_t addr);
void i2c_send_data(uint8_t byte);
uint8_t i2c_read_ack(void);
uint8_t i2c_read_nack(void);
void i2c_stop(void);
#endif

32
main.c Normal file
View File

@@ -0,0 +1,32 @@
#include <stdint.h>
#include <stdbool.h>
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
#include <avr/io.h>
#include <util/delay.h>
#include <avr/pgmspace.h>
#include <avr/interrupt.h>
#include <tool.h>
#include <uart.h>
#include <i2c.h>
#include <disp.h>
#include <timer.h>
#include <contr.h>
int main(void) {
uart_init();
i2c_init();
uartio_init();
disp_init();
disp_clear();
timer_init();
contr_init();
contr_setup();
sei();
contr_main();
return 0;
}

93
temp.c Normal file
View File

@@ -0,0 +1,93 @@
#include <stdint.h>
#include <avr/io.h>
#include <util/delay.h>
#include <avr/interrupt.h>
#include <tool.h>
#include <temp.h>
uint8_t ds18b20_reset() {
uint8_t error;
REG_SETDOWN_BIT(DS18B20_PORT, DS18B20_PB);
REG_SETUP_BIT(DS18B20_DDR, DS18B20_PB);
_delay_us(480);
cli();
REG_SETDOWN_BIT(DS18B20_DDR, DS18B20_PB);
_delay_us(60);
sei();
error = REG_BIT_VALUE(DS18B20_PIN, DS18B20_PB);
_delay_us(420);
return error;
}
void ds18b20_write_bit(uint8_t bit) {
cli();
REG_SETDOWN_BIT(DS18B20_PORT, DS18B20_PB);
REG_SETUP_BIT(DS18B20_DDR, DS18B20_PB);
_delay_us(1);
if (bit) {
REG_SETDOWN_BIT(DS18B20_DDR, DS18B20_PB);
}
_delay_us(60);
REG_SETDOWN_BIT(DS18B20_DDR, DS18B20_PB);
sei();
}
uint8_t ds18b20_read_bit(void) {
cli();
uint8_t bit = 0x00;
REG_SETDOWN_BIT(DS18B20_PORT, DS18B20_PB);
REG_SETUP_BIT(DS18B20_DDR, DS18B20_PB);
_delay_us(1);
REG_SETDOWN_BIT(DS18B20_DDR, DS18B20_PB);
_delay_us(14);
if (REG_BIT_VALUE(DS18B20_PIN, DS18B20_PB)) {
bit = 0x01;
}
_delay_us(45);
sei();
return bit;
}
void ds18b20_write_byte(uint8_t byte) {
int i = 8;
while (i--) {
ds18b20_write_bit(byte & 0x01);
byte >>= 1;
}
}
uint8_t ds18b20_read_byte(void) {
uint8_t i = 8, byte = 0;
while (i--) {
byte >>= 1;
byte |= (ds18b20_read_bit() << 7);
}
return byte;
}
float ds18b20_get_temp() {
uint8_t ltemp;
uint8_t htemp;
float temp = 0.0F;
ds18b20_reset();
ds18b20_write_byte(DS18B20_CMD_SKIPROM);
ds18b20_write_byte(DS18B20_CMD_CONVERTTEMP);
while (!ds18b20_read_bit());
ds18b20_reset();
ds18b20_write_byte(DS18B20_CMD_SKIPROM);
ds18b20_write_byte(DS18B20_CMD_RSCRATCHPAD);
ltemp = ds18b20_read_byte();
htemp = ds18b20_read_byte();
temp = ((htemp << 8) + ltemp) * 0.0625F;
return temp;
}

28
temp.h Normal file
View File

@@ -0,0 +1,28 @@
#ifndef DS18B20_H_QWERTY
#define DS18B20_H_QWERTY
#include <avr/io.h>
#define DS18B20_PORT PORTB
#define DS18B20_DDR DDRB
#define DS18B20_PIN PINB
#define DS18B20_PB PB3
#define DS18B20_CMD_CONVERTTEMP 0x44
#define DS18B20_CMD_RSCRATCHPAD 0xBE
#define DS18B20_CMD_WSCRATCHPAD 0x4E
#define DS18B20_CMD_CPYSCRATCHPAD 0x48
#define DS18B20_CMD_RECEEPROM 0xB8
#define DS18B20_CMD_RPWRSUPPLY 0xB4
#define DS18B20_CMD_SEARCHROM 0xF0
#define DS18B20_CMD_READROM 0x33
#define DS18B20_CMD_MATCHROM 0x55
#define DS18B20_CMD_SKIPROM 0xCC
#define DS18B20_CMD_ALARMSEARCH 0xEC
//#define DS18B20_STOPINT 1
float ds18b20_get_temp();
#endif

36
timer.c Normal file
View File

@@ -0,0 +1,36 @@
/*
* Copyright 2017 Oleg Borodin <onborodin@gmail.com>
*/
#include <stdint.h>
#include <stdbool.h>
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
#include <avr/pgmspace.h>
#include <avr/interrupt.h>
#include <avr/io.h>
#include <util/delay.h>
#include <tool.h>
#include <timer.h>
void timer_init(void) {
/* Disable comparators */
REG_SETDOWN_BIT(TCCR0A, COM0A1);
REG_SETDOWN_BIT(TCCR0A, COM0A0);
REG_SETDOWN_BIT(TCCR0A, COM0B1);
REG_SETDOWN_BIT(TCCR0A, COM0B0);
/* Set normal mode */
REG_SETDOWN_BIT(TCCR0A, WGM01);
REG_SETDOWN_BIT(TCCR0A, WGM00);
/* Set clock to 1/64 */
REG_SETDOWN_BIT(TCCR0B, CS02);
REG_SETUP_BIT(TCCR0B, CS01);
REG_SETUP_BIT(TCCR0B, CS00);
/* Enable timer interrupt */
REG_SETUP_BIT(TIMSK0, TOIE0);
REG_SETUP(TCNT0, TIMER_INITVAL);
}

8
timer.h Normal file
View File

@@ -0,0 +1,8 @@
#ifndef TIMER_H_QWERTY
#define TIMER_H_QWERTY
#define TIMER_INITVAL 128
void timer_init(void);
#endif

19
tool.c Normal file
View File

@@ -0,0 +1,19 @@
/*
* Copyright 2017 Oleg Borodin <onborodin@gmail.com>
*/
#include <stdlib.h>
#include <stdint.h>
#include <stdbool.h>
#include <tool.h>
uint16_t str_len(uint8_t * str) {
uint16_t i = 0;
while (str[i] != 0)
i++;
return i;
}
int get_rand(int min, int max) {
return (rand() % (max - min)) + min;
}

23
tool.h Normal file
View File

@@ -0,0 +1,23 @@
/*
* Copyright 2017 Oleg Borodin <onborodin@gmail.com>
*
*/
#ifndef TOOLS_H_QWERTY
#define TOOLS_H_QWERTY
#define MAX_LINE_LEN 1024
#define REG_SETUP_BIT(reg, bit) (reg) |= (1 << (bit))
#define REG_SETDOWN_BIT(reg, bit) (reg) &= ~(1 << (bit))
#define REG_BIT_ISUP(reg, bit) ((reg) & (1 << (bit)))
#define REG_SETVAL(reg, value) ((reg) = (value))
#define REG_SETUP(reg, value) ((reg) |= (value))
#define REG_SETDOWN(reg, value) ((reg) &= ~(value))
#define REG_BIT_VALUE(reg, value) ((reg) & (1 << (value)))
#define BIT(bit) (1 << (bit))
uint16_t str_len(uint8_t * str);
#endif

62
uart.c Normal file
View File

@@ -0,0 +1,62 @@
/*
* Copyright 2017 Oleg Borodin <onborodin@gmail.com>
*
*/
#include <stdio.h>
#include <stdbool.h>
#include <avr/io.h>
#include <util/delay.h>
#define BAUD 38400
#include <util/setbaud.h>
#include <tool.h>
#include <fifo.h>
#include <uart.h>
static uint8_t inbuf[FIFO_BUFFER_SIZE];
static uint8_t outbuf[FIFO_BUFFER_SIZE];
fifo_t uart_inbuf, uart_outbuf;
FILE uart_stream = FDEV_SETUP_STREAM(uart_putchar, uart_getchar, _FDEV_SETUP_RW);
int uart_putchar(char c, FILE * stream) {
return fifo_putc(&uart_outbuf, c);
}
int uart_getchar(FILE * stream) {
return (int)fifo_getc(&uart_inbuf);
}
void uartio_init(void) {
fifo_init(&uart_inbuf, inbuf, sizeof(inbuf));
fifo_init(&uart_outbuf, outbuf, sizeof(outbuf));
stdout = &uart_stream;
stdin = &uart_stream;
stderr = &uart_stream;
}
void uart_init(void) {
/* Set port speed */
UBRR0H = UBRRH_VALUE;
UBRR0L = UBRRL_VALUE;
/* Disable double speed operation */
REG_SETDOWN_BIT(UCSR0A, U2X0);
/* Set character size to 8 bit */
REG_SETDOWN_BIT(UCSR0B, UCSZ02);
REG_SETUP_BIT(UCSR0C, UCSZ01);
REG_SETUP_BIT(UCSR0C, UCSZ00);
/* Set one stop bit, no parity */
REG_SETDOWN_BIT(UCSR0C, USBS0);
REG_SETDOWN_BIT(UCSR0C, UPM00);
REG_SETDOWN_BIT(UCSR0C, UPM01);
/* Enable TX and RX */
REG_SETUP_BIT(UCSR0B, TXEN0);
REG_SETUP_BIT(UCSR0B, RXEN0);
/* Disable receive & transmit interrupts */
REG_SETDOWN_BIT(UCSR0B, RXCIE0);
REG_SETDOWN_BIT(UCSR0B, UDRIE0);
_delay_ms(20);
}

21
uart.h Normal file
View File

@@ -0,0 +1,21 @@
/*
* Copyright 2017 Oleg Borodin <onborodin@gmail.com>
*
*/
#ifndef UART_H_QWERTY
#define UART_H_QWERTY
#include <stdio.h>
#include <fifo.h>
extern fifo_t uart_inbuf, uart_outbuf;
extern FILE uart_stream;
void uartio_init(void);
void uart_init(void);
int uart_putchar(char c, FILE * stream);
int uart_getchar(FILE * stream);
#endif