working with i2c ioctl
This commit is contained in:
commit
ccf0fbd21a
7
.gitignore
vendored
Normal file
7
.gitignore
vendored
Normal file
@ -0,0 +1,7 @@
|
||||
*.o
|
||||
*.elf
|
||||
*.bin
|
||||
*.hex
|
||||
*.lst
|
||||
*.map
|
||||
Host/i2c-test
|
9
Host/Makefile
Normal file
9
Host/Makefile
Normal file
@ -0,0 +1,9 @@
|
||||
all:
|
||||
gcc -O2 -Wall i2c-test.c -o i2c-test
|
||||
|
||||
driver:
|
||||
sudo modprobe i2c-dev
|
||||
|
||||
perm:
|
||||
sudo chgrp dialout /dev/i2c-0
|
||||
|
175
Host/i2c-test.c
Normal file
175
Host/i2c-test.c
Normal file
@ -0,0 +1,175 @@
|
||||
/*
|
||||
* config file:
|
||||
* - i2c device
|
||||
* - i2c address
|
||||
* - email-address
|
||||
* - reporting config (when logging / mailing)
|
||||
* - thresholds for do shutdown
|
||||
*
|
||||
* parameters:
|
||||
* -d run as daemon
|
||||
* -f foreground
|
||||
* -v debug
|
||||
* -c [idle|charge|test|poweroff] command (not with -d)
|
||||
* --config
|
||||
* --help
|
||||
*
|
||||
* in command mode try to use daemon first (via unix-socket)
|
||||
* then fallback to i2c
|
||||
*/
|
||||
#include <stdint.h>
|
||||
#include <stdio.h>
|
||||
#include <stdlib.h>
|
||||
#include <unistd.h>
|
||||
#include <string.h>
|
||||
|
||||
#include <sys/ioctl.h>
|
||||
#include <sys/types.h>
|
||||
#include <sys/stat.h>
|
||||
#include <fcntl.h>
|
||||
|
||||
#include <linux/i2c.h>
|
||||
#include <linux/i2c-dev.h>
|
||||
|
||||
struct read_data {
|
||||
uint8_t sys_state;
|
||||
|
||||
int16_t adc_current;
|
||||
int16_t adc_ubat;
|
||||
int16_t adc_uin;
|
||||
|
||||
int16_t uin_loss;
|
||||
int16_t uin_restore;
|
||||
int16_t ubat_full;
|
||||
int16_t ubat_low;
|
||||
int16_t ubat_critical;
|
||||
int16_t ibat_full;
|
||||
uint16_t crc16;
|
||||
} __attribute__((__packed__));
|
||||
|
||||
struct write_data {
|
||||
uint8_t sys_state;
|
||||
|
||||
int16_t uin_loss;
|
||||
int16_t uin_restore;
|
||||
int16_t ubat_full;
|
||||
int16_t ubat_low;
|
||||
int16_t ubat_critical;
|
||||
int16_t ibat_full;
|
||||
uint16_t crc16;
|
||||
} __attribute__((__packed__));
|
||||
|
||||
enum {
|
||||
STATE_IDLE = 0x01,
|
||||
STATE_TEST = 0x02,
|
||||
STATE_CHARGE = 0x04,
|
||||
STATE_DISCHARGE = 0x08,
|
||||
STATE_POWEROFF = 0x10,
|
||||
};
|
||||
|
||||
static char * state2str(uint8_t state)
|
||||
{
|
||||
switch (state) {
|
||||
case STATE_IDLE:
|
||||
return "STATE_IDLE";
|
||||
|
||||
case STATE_TEST:
|
||||
return "STATE_TEST";
|
||||
|
||||
case STATE_CHARGE:
|
||||
return "STATE_CHARGE";
|
||||
|
||||
case STATE_DISCHARGE:
|
||||
return "STATE_DISCHARGE";
|
||||
|
||||
case STATE_POWEROFF:
|
||||
return "STATE_POWEROFF";
|
||||
|
||||
default:
|
||||
return "<UNKNOWN>";
|
||||
}
|
||||
}
|
||||
|
||||
static int i2c_open(const char *path)
|
||||
{
|
||||
int fd = open(path, O_RDWR);
|
||||
if (fd < 0) {
|
||||
perror("open()");
|
||||
return -1;
|
||||
}
|
||||
|
||||
unsigned long funcs;
|
||||
if (ioctl(fd, I2C_FUNCS, &funcs)) {
|
||||
perror("ioctl(I2C_FUNCS)");
|
||||
close(fd);
|
||||
return -1;
|
||||
}
|
||||
|
||||
if (!(funcs & I2C_FUNC_I2C)) {
|
||||
fprintf(stderr, "I2C_FUNC_I2C not supported!\n");
|
||||
close(fd);
|
||||
return -1;
|
||||
}
|
||||
|
||||
return fd;
|
||||
}
|
||||
|
||||
static int i2c_setaddress(int fd, int address)
|
||||
{
|
||||
if (ioctl(fd, I2C_SLAVE, address) < 0) {
|
||||
perror("ioctl(I2C_SLAVE)");
|
||||
close(fd);
|
||||
return -1;
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
int main(int argc, char *argv[])
|
||||
{
|
||||
int fd = i2c_open("/dev/i2c-0");
|
||||
if (fd < 0)
|
||||
exit(-1);
|
||||
|
||||
if (i2c_setaddress(fd, 0x10) < 0)
|
||||
exit(-1);
|
||||
|
||||
int cnt = 0;
|
||||
|
||||
while (1) {
|
||||
struct read_data rdbuf;
|
||||
memset(&rdbuf, 0, sizeof(rdbuf));
|
||||
|
||||
int ret = read(fd, &rdbuf, sizeof(rdbuf));
|
||||
if (ret <= 0)
|
||||
perror("read()");
|
||||
|
||||
printf("state:0x%02x I:%5dmA Ubat:%5dmV Usup:%5dmV (%s) [%5d,%5d,%5d,%5d,%5d,%5d,0x%04x]\n",
|
||||
rdbuf.sys_state, rdbuf.adc_current, rdbuf.adc_ubat,
|
||||
rdbuf.adc_uin, state2str(rdbuf.sys_state),
|
||||
rdbuf.uin_loss, rdbuf.uin_restore, rdbuf.ubat_full,
|
||||
rdbuf.ubat_low, rdbuf.ubat_critical, rdbuf.ibat_full,
|
||||
rdbuf.crc16);
|
||||
|
||||
sleep(1);
|
||||
cnt++;
|
||||
|
||||
if (cnt == 5) {
|
||||
struct write_data wrbuf = {
|
||||
.sys_state = STATE_CHARGE,
|
||||
.uin_loss = 12000,
|
||||
.uin_restore = 14000,
|
||||
.ubat_full = 13300,
|
||||
.ubat_low = 12000,
|
||||
.ubat_critical = 10800,
|
||||
.ibat_full = 150,
|
||||
.crc16 = 0x0000,
|
||||
};
|
||||
|
||||
// write (fd, &wrbuf, sizeof(wrbuf));
|
||||
write (fd, &wrbuf, 1);
|
||||
}
|
||||
}
|
||||
close(fd);
|
||||
|
||||
return 0;
|
||||
}
|
48
Makefile
Normal file
48
Makefile
Normal file
@ -0,0 +1,48 @@
|
||||
PRG = alix-usv
|
||||
OBJ = alix-usv.o eeprom.o usi-i2c-slave.o
|
||||
MCU_TARGET = attiny84
|
||||
OPTIMIZE = -Os
|
||||
|
||||
DEFS =
|
||||
LIBS =
|
||||
|
||||
# Override is only needed by avr-lib build system.
|
||||
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
|
||||
|
||||
all: $(PRG).elf lst text
|
||||
$(SIZE) -x -A $(PRG).elf
|
||||
|
||||
$(PRG).elf: $(OBJ)
|
||||
$(CC) $(CFLAGS) $(LDFLAGS) -o $@ $^ $(LIBS)
|
||||
|
||||
clean:
|
||||
rm -rf *.o *.lst *.map $(PRG).elf *.hex *.bin
|
||||
|
||||
lst: $(PRG).lst
|
||||
|
||||
%.lst: %.elf
|
||||
$(OBJDUMP) -h -S $< > $@
|
||||
|
||||
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
|
||||
avrdude -c dragon_isp -P usb -p t84 -U flash:w:$(PRG).hex
|
||||
|
||||
# no self programming, 2.7V BOD, 8MHz internal RC Osz.
|
||||
fuses:
|
||||
avrdude -c dragon_isp -P usb -p t84 -U lfuse:w:0xc2:m -U hfuse:w:0xdd:m -U efuse:w:0xff:m
|
249
alix-usv.c
Normal file
249
alix-usv.c
Normal file
@ -0,0 +1,249 @@
|
||||
/***************************************************************************
|
||||
* Copyright (C) 01/2009 by Olaf Rempel *
|
||||
* razzor@kopf-tisch.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 "alix-usv.h"
|
||||
#include "eeprom.h"
|
||||
#include "usi-i2c-slave.h"
|
||||
|
||||
extern volatile struct ee_param params;
|
||||
|
||||
static const uint8_t adc_mux[] = {
|
||||
CH_CURRENT_P, CH_CURRENT_N,
|
||||
CH_VOLTAGE_BAT, CH_VOLTAGE_SUP,
|
||||
};
|
||||
|
||||
static volatile uint8_t adc_update;
|
||||
static volatile int16_t adc_value[3];
|
||||
|
||||
enum {
|
||||
ADC_CURRENT = 0,
|
||||
ADC_UBAT = 1,
|
||||
ADC_UIN = 2,
|
||||
};
|
||||
|
||||
static volatile uint8_t sys_state;
|
||||
enum {
|
||||
STATE_IDLE = 0x01,
|
||||
STATE_TEST = 0x02,
|
||||
STATE_CHARGE = 0x04,
|
||||
STATE_DISCHARGE = 0x08,
|
||||
STATE_POWEROFF = 0x10,
|
||||
};
|
||||
|
||||
static uint32_t adc_buf[4];
|
||||
ISR(ADC_vect)
|
||||
{
|
||||
static uint8_t cnt;
|
||||
|
||||
/* use result of second conversion (switching ADC-gain needs time..) */
|
||||
if (cnt & 0x01) {
|
||||
/* moving average filter */
|
||||
uint8_t ch = (cnt >> 1);
|
||||
adc_buf[ch] = ((adc_buf[ch] * 7) + ((uint32_t)ADC << 8)) /8;
|
||||
uint16_t value = (adc_buf[ch] >> 8) + ((adc_buf[ch] & 0x80) ? 1 : 0);
|
||||
|
||||
if (ch == 0 && (adc_buf[0] >= adc_buf[1])) {
|
||||
/* charging: positive current = ADC * 1.25 */
|
||||
adc_value[ADC_CURRENT] = value + (value >> 2);
|
||||
|
||||
} else if (ch == 1 && (adc_buf[0] < adc_buf[1])) {
|
||||
/* discharging: negative current = ADC * -1.25 */
|
||||
adc_value[ADC_CURRENT] = -(value + (value >> 2));
|
||||
|
||||
} else if (ch == 2) {
|
||||
/* Ubat = (ADC * 21.28) - (Ishunt * 0.1) */
|
||||
adc_value[ADC_UBAT] = (value * 21) + ((value * 9) >> 5) - (adc_value[ADC_CURRENT] / 10);
|
||||
|
||||
} else if (ch == 3) {
|
||||
/* Uin = ADC * 21.28 */
|
||||
adc_value[ADC_UIN] = (value * 21) + ((value * 9) >> 5);
|
||||
|
||||
/* all values updated */
|
||||
adc_update = 1;
|
||||
}
|
||||
}
|
||||
|
||||
/* trigger next conversion */
|
||||
cnt = (cnt +1) & 0x07;
|
||||
ADMUX = adc_mux[cnt >> 1];
|
||||
ADCSRA |= (1<<ADSC);
|
||||
}
|
||||
|
||||
void usi_write(uint8_t data, uint8_t bcnt)
|
||||
{
|
||||
if (bcnt == 0) {
|
||||
/* poweroff is always allowed */
|
||||
if (data & STATE_POWEROFF)
|
||||
sys_state = data;
|
||||
|
||||
/* discharge cmd is never allowed */
|
||||
else if (data & STATE_DISCHARGE)
|
||||
return;
|
||||
|
||||
/* during discharge nothing is allowed */
|
||||
else if (sys_state != STATE_DISCHARGE)
|
||||
sys_state = data;
|
||||
|
||||
} else {
|
||||
uint8_t index = (bcnt -1);
|
||||
uint8_t *ptr = (uint8_t *)¶ms;
|
||||
if (index < sizeof(params))
|
||||
ptr[index] = data;
|
||||
|
||||
if (index == (sizeof(params) -1))
|
||||
write_parameters();
|
||||
}
|
||||
}
|
||||
|
||||
uint8_t usi_read(uint8_t bcnt)
|
||||
{
|
||||
static int16_t adc_copy[3];
|
||||
|
||||
/* first byte read is sys_state */
|
||||
if (bcnt == 0) {
|
||||
/* take a snapshot in interrupt-mode */
|
||||
adc_copy[ADC_CURRENT] = adc_value[ADC_CURRENT];
|
||||
adc_copy[ADC_UBAT] = adc_value[ADC_UBAT];
|
||||
adc_copy[ADC_UIN] = adc_value[ADC_UIN];
|
||||
return sys_state;
|
||||
}
|
||||
|
||||
uint8_t index = (bcnt -1);
|
||||
uint8_t *ptr = (uint8_t *)adc_copy;
|
||||
|
||||
/* Current and Voltages (in mA/mV) */
|
||||
if (index < sizeof(adc_copy))
|
||||
return ptr[index];
|
||||
|
||||
index -= sizeof(adc_copy);
|
||||
ptr = (uint8_t *)¶ms;
|
||||
|
||||
/* eeprom parameters (no snapshot needed, changed only in usi_write) */
|
||||
if (index < sizeof(params))
|
||||
return ptr[index];
|
||||
|
||||
return 0xFF;
|
||||
}
|
||||
|
||||
/*
|
||||
* the watchdog timer remains active even after a
|
||||
* system reset. So disable it as soon as possible.
|
||||
* automagically called on startup
|
||||
*/
|
||||
void disable_wdt_timer(void) __attribute__((naked, section(".init3")));
|
||||
void disable_wdt_timer(void)
|
||||
{
|
||||
MCUSR = 0;
|
||||
WDTCSR = (1<<WDCE) | (1<<WDE);
|
||||
WDTCSR = (0<<WDE);
|
||||
}
|
||||
|
||||
int main(void)
|
||||
{
|
||||
PORTA = I2C_SCL | I2C_SDA;
|
||||
DDRA = I2C_SCL | LED_GN;
|
||||
|
||||
DDRB = EN_POWER | EN_CHARGER | EN_TEST;
|
||||
|
||||
/* Disable Digital Inputs */
|
||||
DIDR0 = AIN_REF | AIN_CURRENT_N | AIN_CURRENT_P | AIN_VOLTAGE_BAT | AIN_VOLTAGE_SUP;
|
||||
|
||||
/* ADC: freerunning with F_CPU/128 */
|
||||
ADMUX = adc_mux[0];
|
||||
ADCSRA = (1<<ADEN) | (1<<ADSC) | (1<<ADIF) | (1<<ADIE) | (1<<ADPS2) | (1<<ADPS1) | (1<<ADPS0);
|
||||
|
||||
/* init TWI statemachine */
|
||||
usi_statemachine();
|
||||
|
||||
/* read statemachine parameters from eeprom */
|
||||
read_parameters();
|
||||
|
||||
sei();
|
||||
|
||||
/* enable power */
|
||||
sys_state = STATE_IDLE;
|
||||
PORTB = EN_POWER;
|
||||
|
||||
/* wait 1s for moving average filters */
|
||||
uint8_t i;
|
||||
for (i = 0; i < 50; i++)
|
||||
_delay_ms(20);
|
||||
|
||||
while (1) {
|
||||
while (!adc_update);
|
||||
adc_update = 0;
|
||||
|
||||
/* disable interrupts while using adc_value and params */
|
||||
cli();
|
||||
|
||||
/* loss of external power => discharge */
|
||||
if (sys_state & (STATE_IDLE | STATE_TEST | STATE_CHARGE))
|
||||
if (adc_value[ADC_UIN] < params.uin_loss)
|
||||
sys_state = STATE_DISCHARGE;
|
||||
|
||||
/* external power restored => charge */
|
||||
if (sys_state & (STATE_DISCHARGE | STATE_POWEROFF))
|
||||
if (adc_value[ADC_UIN] > params.uin_restore)
|
||||
sys_state = STATE_CHARGE;
|
||||
|
||||
/* battery is low => charge */
|
||||
if (sys_state & (STATE_IDLE | STATE_TEST))
|
||||
if (adc_value[ADC_UBAT] < params.ubat_low)
|
||||
sys_state = STATE_CHARGE;
|
||||
|
||||
switch (sys_state) {
|
||||
case STATE_IDLE:
|
||||
PORTB = EN_POWER;
|
||||
break;
|
||||
|
||||
case STATE_TEST:
|
||||
PORTB = EN_POWER | EN_TEST;
|
||||
break;
|
||||
|
||||
case STATE_CHARGE:
|
||||
PORTB = EN_POWER | EN_CHARGER;
|
||||
|
||||
/* battery is full => idle */
|
||||
if (adc_value[ADC_UBAT] > params.ubat_full && adc_value[ADC_CURRENT] < params.ibat_full)
|
||||
sys_state = STATE_IDLE;
|
||||
break;
|
||||
|
||||
case STATE_DISCHARGE:
|
||||
PORTB = EN_POWER;
|
||||
|
||||
/* battery is critical low => poweroff */
|
||||
if (adc_value[ADC_UBAT] < params.ubat_critical)
|
||||
sys_state = STATE_POWEROFF;
|
||||
break;
|
||||
|
||||
case STATE_POWEROFF:
|
||||
PORTB = 0x00;
|
||||
break;
|
||||
|
||||
default:
|
||||
sys_state = STATE_IDLE;
|
||||
break;
|
||||
}
|
||||
|
||||
/* re-enable interrupts */
|
||||
sei();
|
||||
}
|
||||
}
|
32
alix-usv.h
Normal file
32
alix-usv.h
Normal file
@ -0,0 +1,32 @@
|
||||
#ifndef _MAIN_H_
|
||||
#define _MAIN_H_
|
||||
|
||||
#include <avr/io.h>
|
||||
|
||||
#define F_CPU 8000000
|
||||
#include <util/delay.h>
|
||||
|
||||
#define EN_POWER (1<<PORTB0)
|
||||
#define EN_CHARGER (1<<PORTB1)
|
||||
#define EN_TEST (1<<PORTB2)
|
||||
|
||||
#define AIN_REF (1<<PINA0)
|
||||
#define AIN_CURRENT_N (1<<PINA1)
|
||||
#define AIN_CURRENT_P (1<<PINA2)
|
||||
#define AIN_VOLTAGE_BAT (1<<PINA3)
|
||||
#define I2C_SCL (1<<PORTA4)
|
||||
#define LED_GN (1<<PORTA5)
|
||||
#define I2C_SDA (1<<PORTA6)
|
||||
#define AIN_VOLTAGE_SUP (1<<PINA7)
|
||||
|
||||
#define I2C_ADDRESS (0x10 << 1)
|
||||
|
||||
#define CH_CURRENT_P ((1<<REFS0) | 0x0d) /* current A1->A2, 20x gain */
|
||||
#define CH_CURRENT_N ((1<<REFS0) | 0x2d) /* current A2->A1, 20x gain */
|
||||
#define CH_VOLTAGE_BAT ((1<<REFS0) | 0x03) /* voltage A3->gnd, 1x gain */
|
||||
#define CH_VOLTAGE_SUP ((1<<REFS0) | 0x07) /* voltage A7->gnd, 1x gain */
|
||||
|
||||
void usi_write(uint8_t data, uint8_t bcnt);
|
||||
uint8_t usi_read(uint8_t bcnt);
|
||||
|
||||
#endif // _USI_I2C_SLAVE_H_
|
61
eeprom.c
Normal file
61
eeprom.c
Normal file
@ -0,0 +1,61 @@
|
||||
/***************************************************************************
|
||||
* Copyright (C) 02/2008 by Olaf Rempel *
|
||||
* razzor@kopf-tisch.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/eeprom.h>
|
||||
#include <util/crc16.h>
|
||||
#include "eeprom.h"
|
||||
|
||||
static const struct ee_param defaults = DEFAULT_PARAMETERS;
|
||||
|
||||
struct ee_param params;
|
||||
struct ee_param params_in_eeprom EEMEM = DEFAULT_PARAMETERS;
|
||||
|
||||
void write_parameters(void)
|
||||
{
|
||||
uint8_t i;
|
||||
uint16_t crc = 0x0000;
|
||||
uint8_t *tmp = (uint8_t *)¶ms;
|
||||
for (i = 0; i < sizeof(struct ee_param) -2; i++)
|
||||
crc = _crc_ccitt_update(crc, *tmp++);
|
||||
|
||||
params.crc16 = crc;
|
||||
eeprom_write_block(¶ms, ¶ms_in_eeprom, sizeof(struct ee_param));
|
||||
}
|
||||
|
||||
uint8_t read_parameters(void)
|
||||
{
|
||||
eeprom_read_block(¶ms, ¶ms_in_eeprom, sizeof(struct ee_param));
|
||||
|
||||
uint8_t i;
|
||||
uint16_t crc = 0x0000;
|
||||
uint8_t *tmp = (uint8_t *)¶ms;
|
||||
for (i = 0; i < sizeof(struct ee_param); i++)
|
||||
crc = _crc_ccitt_update(crc, *tmp++);
|
||||
|
||||
if (crc != 0x0000) {
|
||||
i = sizeof(struct ee_param);
|
||||
uint8_t *src = (uint8_t *)&defaults;
|
||||
uint8_t *dst = (uint8_t *)¶ms;
|
||||
while (i--)
|
||||
*dst++ = *src++;
|
||||
|
||||
write_parameters();
|
||||
return 1;
|
||||
}
|
||||
return 0;
|
||||
}
|
27
eeprom.h
Normal file
27
eeprom.h
Normal file
@ -0,0 +1,27 @@
|
||||
#ifndef _EEPROM_PARAMETERS_H_
|
||||
#define _EEPROM_PARAMETERS_H_
|
||||
|
||||
struct ee_param {
|
||||
int16_t uin_loss;
|
||||
int16_t uin_restore;
|
||||
int16_t ubat_full;
|
||||
int16_t ubat_low;
|
||||
int16_t ubat_critical;
|
||||
int16_t ibat_full;
|
||||
|
||||
uint16_t crc16;
|
||||
};
|
||||
|
||||
#define DEFAULT_PARAMETERS { \
|
||||
.uin_loss = 12000, \
|
||||
.uin_restore = 14000, \
|
||||
.ubat_full = 13300, \
|
||||
.ubat_low = 12000, \
|
||||
.ubat_critical = 11000, \
|
||||
.ibat_full = 150, \
|
||||
};
|
||||
|
||||
uint8_t read_parameters(void);
|
||||
void write_parameters(void);
|
||||
|
||||
#endif
|
141
usi-i2c-slave.c
Normal file
141
usi-i2c-slave.c
Normal file
@ -0,0 +1,141 @@
|
||||
/***************************************************************************
|
||||
* Copyright (C) 01/2009 by Olaf Rempel *
|
||||
* razzor@kopf-tisch.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 "alix-usv.h"
|
||||
#include "usi-i2c-slave.h"
|
||||
|
||||
#define USI_MASK 0x0F
|
||||
#define USI_MASK_ACKBIT 0x10 /* one (ack)bit / 8bits */
|
||||
#define USI_MASK_OUTPUT 0x20 /* SDA is output / input */
|
||||
|
||||
#define USI_RESET 0x00 /* wait for Start Condition */
|
||||
#define USI_START 0x01 /* Start detected */
|
||||
#define USI_SLA 0x02 /* wait for Slave Address */
|
||||
#define USI_SLAW_ACK 0x03 /* ACK Slave Address + Write (Master writes) */
|
||||
#define USI_SLAR_ACK 0x04 /* ACK Slave Address + Read (Master reads) */
|
||||
#define USI_DATW 0x05 /* receive Data */
|
||||
#define USI_DATW_ACK 0x06 /* transmit ACK for received Data */
|
||||
#define USI_DATR 0x07 /* transmit Data */
|
||||
#define USI_DATR_ACK 0x08 /* receive ACK for transmitted Data */
|
||||
|
||||
static uint8_t usi_state;
|
||||
|
||||
void usi_statemachine(void)
|
||||
{
|
||||
static uint8_t bcnt;
|
||||
|
||||
uint8_t tmp = USIDR;
|
||||
uint8_t state = usi_state & USI_MASK;
|
||||
|
||||
/* Start Condition detected */
|
||||
if (state == USI_START) {
|
||||
usi_state = USI_SLA;
|
||||
|
||||
/* Slave Address received => prepare ACK/NACK */
|
||||
} else if (state == USI_SLA) {
|
||||
bcnt = 0;
|
||||
if (tmp == (I2C_ADDRESS | 0x00))
|
||||
usi_state = USI_SLAW_ACK | USI_MASK_ACKBIT | USI_MASK_OUTPUT;
|
||||
|
||||
else if (tmp == (I2C_ADDRESS | 0x01))
|
||||
usi_state = USI_SLAR_ACK | USI_MASK_ACKBIT | USI_MASK_OUTPUT;
|
||||
|
||||
else
|
||||
usi_state = USI_RESET;
|
||||
|
||||
/* ACK after SLA+W / Data received => prepare data receive */
|
||||
} else if (state == USI_SLAW_ACK || state == USI_DATW_ACK) {
|
||||
usi_state = USI_DATW;
|
||||
|
||||
/* Data received => prepare ACK transmit */
|
||||
} else if (state == USI_DATW) {
|
||||
usi_write(tmp, bcnt++);
|
||||
usi_state = USI_DATW_ACK | USI_MASK_ACKBIT | USI_MASK_OUTPUT;
|
||||
|
||||
/* ACK after SLA+R transmitted / ACK after Data received => prepare data transmit */
|
||||
} else if (state == USI_SLAR_ACK || (state == USI_DATR_ACK && tmp == 0x00)) {
|
||||
USIDR = usi_read(bcnt++);
|
||||
usi_state = USI_DATR | USI_MASK_OUTPUT;
|
||||
|
||||
/* Data transmitted => prepare ACK receive */
|
||||
} else if (state == USI_DATR) {
|
||||
usi_state = USI_DATR_ACK | USI_MASK_ACKBIT;
|
||||
|
||||
/* NACK after Data received / default => go idle */
|
||||
} else {
|
||||
usi_state = USI_RESET;
|
||||
}
|
||||
|
||||
state = usi_state & USI_MASK;
|
||||
if (state == USI_RESET) {
|
||||
/* input */
|
||||
DDRA &= ~I2C_SDA;
|
||||
|
||||
/* Enable StartCondition Interrupt, TWI Mode, count both edges */
|
||||
USICR = (1<<USISIE) | (1<<USIWM1) | (1<<USICS1);
|
||||
|
||||
/* Clear Interrupt Flags, Clear Stop Condition Flag, wait for 2 edges */
|
||||
USISR = (1<<USISIF) | (1<<USIOIF) | (1<<USIPF) | ((16 -2)<<USICNT0);
|
||||
|
||||
} else if (state == USI_SLA) {
|
||||
/* Enable Overflow Interrupt, TWI Mode, extend SCL on Overflow */
|
||||
USICR = (1<<USISIE) | (1<<USIOIE) | (1<<USIWM1) | (1<<USIWM0) | (1<<USICS1);
|
||||
|
||||
/* Clear Interrupt Flags, Clear Stop Condition Flag, wait for 16 edges */
|
||||
USISR = (1<<USISIF) | (1<<USIOIF) | (1<<USIPF) | ((16 -16)<<USICNT0);
|
||||
|
||||
} else {
|
||||
if (usi_state & USI_MASK_OUTPUT) {
|
||||
DDRA |= I2C_SDA;
|
||||
|
||||
} else {
|
||||
DDRA &= ~I2C_SDA;
|
||||
}
|
||||
|
||||
if (usi_state & USI_MASK_ACKBIT) {
|
||||
USIDR = 0x00;
|
||||
USISR = (1<<USIOIF) | ((16 -2)<<USICNT0);
|
||||
|
||||
} else {
|
||||
USISR = (1<<USIOIF) | ((16 -16)<<USICNT0);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
ISR(USI_START_vect)
|
||||
{
|
||||
usi_state = USI_START;
|
||||
|
||||
/* check for STOP Condition */
|
||||
while (PINA & I2C_SCL) {
|
||||
if (PINA & I2C_SDA) {
|
||||
usi_state = USI_RESET;
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
usi_statemachine();
|
||||
}
|
||||
|
||||
ISR(USI_OVF_vect)
|
||||
{
|
||||
usi_statemachine();
|
||||
}
|
6
usi-i2c-slave.h
Normal file
6
usi-i2c-slave.h
Normal file
@ -0,0 +1,6 @@
|
||||
#ifndef _USI_I2C_SLAVE_H_
|
||||
#define _USI_I2C_SLAVE_H_
|
||||
|
||||
void usi_statemachine(void);
|
||||
|
||||
#endif // _USI_I2C_SLAVE_H_
|
Loading…
Reference in New Issue
Block a user