From 02f7024898547acfb884d64a0c583997d82faba5 Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Antoni=20Gab=C3=A1s?= <agabas@iri.upc.edu>
Date: Thu, 31 Mar 2016 15:03:43 +0000
Subject: [PATCH] [bioloid_robot] Added the expansion board firmware for
 completeness

---
 Makefile                    |  81 -----
 README                      |   6 +
 a2d.c                       | 188 ++++++++++
 a2d.h                       | 147 ++++++++
 avrlibdefs.h                |  83 +++++
 avrlibtypes.h               |  84 +++++
 buffer.c                    | 163 +++++++++
 buffer.h                    |  76 ++++
 compass.c                   | 136 +++++++
 compass.h                   |  20 ++
 default/Makefile            | 101 ++++++
 default/NUL                 |   1 +
 default/expansion_board.aps |   1 +
 default/expansion_board.aws |   1 +
 default/expansion_board.c   | 352 ++++++++++++++++++
 dynamixel.c                 | 245 +++++++++++++
 dynamixel.h                 |  66 ++++
 expansion_board.aps         |   1 +
 expansion_board.aws         |   1 +
 expansion_board.c           | 352 ++++++++++++++++++
 global.h                    |  40 +++
 i2c.c                       | 606 +++++++++++++++++++++++++++++++
 i2c.h                       | 178 ++++++++++
 i2cconf.h                   |  28 ++
 include/adc.h               |  14 -
 include/compass.h           |  23 --
 include/dac.h               |  16 -
 include/dyn_common.h        |  32 --
 include/dyn_slave_diff.h    |  15 -
 include/dyn_slave_se.h      |  15 -
 include/i2c.h               |  44 ---
 include/mem.h               |  13 -
 include/memory_map.h        | 188 ----------
 include/ports.h             |  28 --
 include/pwm.h               |  17 -
 include/uart_ttl.h          |  14 -
 include/uart_usb.h          |  14 -
 legacy/expansion_board.hex  | 614 ++++++++++++++++++++++++++++++++
 memory_map.h                |  86 +++++
 patches/chipdef.h.patch     |  18 -
 patches/main.c.patch        | 169 ---------
 patches/makefile.patch      |  77 ----
 patches/uart_usb.c          | 241 -------------
 port128.h                   |  98 +++++
 ports.c                     | 105 ++++++
 ports.h                     |  24 ++
 src/adc.c                   | 181 ----------
 src/compass.c               | 252 -------------
 src/dac.c                   | 102 ------
 src/dyn_common.c            | 226 ------------
 src/dyn_slave_diff.c        | 427 ----------------------
 src/dyn_slave_se.c          | 431 ----------------------
 src/i2c.c                   | 217 ------------
 src/main.c                  |  52 ---
 src/mem.c                   |  48 ---
 src/ports.c                 | 136 -------
 src/pwm.c                   | 162 ---------
 src/uart_ttl.c              | 246 -------------
 src/uart_usb.c              | 246 -------------
 timer128.c                  | 687 ++++++++++++++++++++++++++++++++++++
 timer128.h                  | 300 ++++++++++++++++
 uartsw.c                    | 375 ++++++++++++++++++++
 uartsw.h                    |  78 ++++
 uartswconf.h                |  69 ++++
 utils.h                     |   6 +
 65 files changed, 5318 insertions(+), 3745 deletions(-)
 delete mode 100644 Makefile
 create mode 100755 README
 create mode 100755 a2d.c
 create mode 100755 a2d.h
 create mode 100755 avrlibdefs.h
 create mode 100755 avrlibtypes.h
 create mode 100755 buffer.c
 create mode 100755 buffer.h
 create mode 100755 compass.c
 create mode 100755 compass.h
 create mode 100755 default/Makefile
 create mode 100644 default/NUL
 create mode 100755 default/expansion_board.aps
 create mode 100755 default/expansion_board.aws
 create mode 100755 default/expansion_board.c
 create mode 100755 dynamixel.c
 create mode 100755 dynamixel.h
 create mode 100755 expansion_board.aps
 create mode 100755 expansion_board.aws
 create mode 100755 expansion_board.c
 create mode 100755 global.h
 create mode 100755 i2c.c
 create mode 100755 i2c.h
 create mode 100755 i2cconf.h
 delete mode 100644 include/adc.h
 delete mode 100644 include/compass.h
 delete mode 100644 include/dac.h
 delete mode 100644 include/dyn_common.h
 delete mode 100644 include/dyn_slave_diff.h
 delete mode 100644 include/dyn_slave_se.h
 delete mode 100644 include/i2c.h
 delete mode 100644 include/mem.h
 delete mode 100644 include/memory_map.h
 delete mode 100644 include/ports.h
 delete mode 100644 include/pwm.h
 delete mode 100644 include/uart_ttl.h
 delete mode 100644 include/uart_usb.h
 create mode 100755 legacy/expansion_board.hex
 create mode 100755 memory_map.h
 delete mode 100644 patches/chipdef.h.patch
 delete mode 100644 patches/main.c.patch
 delete mode 100644 patches/makefile.patch
 delete mode 100644 patches/uart_usb.c
 create mode 100755 port128.h
 create mode 100755 ports.c
 create mode 100755 ports.h
 delete mode 100644 src/adc.c
 delete mode 100644 src/compass.c
 delete mode 100644 src/dac.c
 delete mode 100644 src/dyn_common.c
 delete mode 100644 src/dyn_slave_diff.c
 delete mode 100644 src/dyn_slave_se.c
 delete mode 100644 src/i2c.c
 delete mode 100755 src/main.c
 delete mode 100644 src/mem.c
 delete mode 100644 src/ports.c
 delete mode 100644 src/pwm.c
 delete mode 100644 src/uart_ttl.c
 delete mode 100644 src/uart_usb.c
 create mode 100755 timer128.c
 create mode 100755 timer128.h
 create mode 100755 uartsw.c
 create mode 100755 uartsw.h
 create mode 100755 uartswconf.h
 create mode 100755 utils.h

diff --git a/Makefile b/Makefile
deleted file mode 100644
index 66571b3..0000000
--- a/Makefile
+++ /dev/null
@@ -1,81 +0,0 @@
-PROJECT=bioloid_exp
-########################################################
-# afegir tots els fitxers que s'han de compilar aquí
-########################################################
-SOURCES=src/main.c src/dyn_slave_se.c src/dyn_slave_diff.c src/mem.c src/dyn_common.c src/ports.c src/adc.c src/i2c.c src/compass.c
-
-timer1_use=uart_usb#possible values are dac or uart_usb
-timer3_use=uart_ttl#possible values are pwm or uart_ttl
-
-defines=
-
-ifeq ($(timer1_use),dac)
-  SOURCES+=src/dac.c
-  defines+=-D_DAC
-else
-  SOURCES+=src/uart_usb.c
-  defines+=-D_UART_USB
-endif
-
-ifeq ($(timer3_use),pwm)
-  SOURCES+=src/pwm.c
-  defines+=-D_PWM
-else
-  SOURCES+=src/uart_ttl.c
-  defines+=-D_UART_TTL
-endif
-
-OBJS=$(SOURCES:.c=.o)
-SRC_DIR=./src/
-INCLUDE_DIR=./include/
-BUILD_DIR=./build/
-BIN_DIR=./bin/
-CC=avr-gcc
-OBJCOPY=avr-objcopy
-MMCU=atmega128
-
-CFLAGS=-mmcu=$(MMCU) -Wall -Os $(defines) -DF_CPU=16000000UL -gdwarf-2 -std=gnu99 -funsigned-char -funsigned-bitfields -fpack-struct -fshort-enums -Wstrict-prototypes
-
-LDFLAGS=-mmcu=$(MMCU) -Wl,-Map=$(PROJECT).map -DF_CPU=16000000UL
-#LDFLAGS=-mmcu=$(MMCU) -Wl,-Map=$(PROJECT).map,--section-start,.eeprom=810000 -DF_CPU=16000000UL
-
-HEX_FLASH_FLAGS = -R .eeprom -R .fuse -R .lock -R .signature
-HEX_EEPROM_FLAGS = -j .eeprom --change-section-lma .eeprom=0
-
-.PHONY: all
-
-all: $(PROJECT).hex $(PROJECT)_eeprom.hex
-
-$(PROJECT).hex: $(PROJECT).elf
-	$(OBJCOPY) -O ihex $(HEX_FLASH_FLAGS)  $< $@
-$(PROJECT)_eeprom.hex: $(PROJECT).elf
-	$(OBJCOPY) -O ihex $(HEX_EEPROM_FLAGS)  $< $@
-$(PROJECT).elf: $(OBJS)
-	$(CC) $(LDFLAGS) $(OBJS) $(LIB_DIRS) $(LIBS) -o $(PROJECT).elf
-%.o:%.c
-	$(CC) -c $(CFLAGS) -I$(INCLUDE_DIR) -o $@ $<
-
-download: $(MAIN_OUT_HEX)
-	avrdude -c avr109 -P /dev/ttyUSB0 -b 19200 -p m128 -U flash:w:$(PROJECT).hex
-	avrdude -c avr109 -P /dev/ttyUSB0 -b 19200 -p m128 -U eeprom:w:$(PROJECT)_eeprom.hex
-
-bootloader: bootloader_hex
-	-$(MAKE) -C remote-controlled-socket/uc/avrprog_boot_v0_85/ program
-
-bootloader_hex:
-	@if [ ! -d "./remote-controlled-socket" ] ; then \
-	echo "AVR bootloader not found"; \
-	hg clone https://bitbucket.org/befi/remote-controlled-socket; \
-	patch remote-controlled-socket/uc/avrprog_boot_v0_85/main.c < patches/main.c.patch;  \
-	patch remote-controlled-socket/uc/avrprog_boot_v0_85/makefile < patches/makefile.patch; \
-	patch remote-controlled-socket/uc/avrprog_boot_v0_85/chipdef.h < patches/chipdef.h.patch; \
-	cp patches/uart_usb.c remote-controlled-socket/uc/avrprog_boot_v0_85/; \
-	fi
-	$(MAKE) -C remote-controlled-socket/uc/avrprog_boot_v0_85/ 
-
-clean:
-	-rm $(PROJECT).*
-	-rm $(PROJECT)_eeprom.*
-	-rm $(OBJS)
-	-rm src/*.lst
-	-rm -rf remote-controlled-socket 
diff --git a/README b/README
new file mode 100755
index 0000000..fb24089
--- /dev/null
+++ b/README
@@ -0,0 +1,6 @@
+Biloid expansion board
+ by Sergi Hernandez Juan
+
+http://apollo.upc.es/humanoide/trac/wiki/BioloidPremiumSensorExtensionBoard
+
+The Humanoid Lab <humanoide@iri.upc.edu>
diff --git a/a2d.c b/a2d.c
new file mode 100755
index 0000000..6102288
--- /dev/null
+++ b/a2d.c
@@ -0,0 +1,188 @@
+/*! \file a2d.c \brief Analog-to-Digital converter function library. */
+//*****************************************************************************
+//
+// File Name	: 'a2d.c'
+// Title		: Analog-to-digital converter functions
+// Author		: Pascal Stang - Copyright (C) 2002
+// Created		: 2002-04-08
+// Revised		: 2002-09-30
+// Version		: 1.1
+// Target MCU	: Atmel AVR series
+// Editor Tabs	: 4
+//
+// This code is distributed under the GNU Public License
+//		which can be found at http://www.gnu.org/licenses/gpl.txt
+//
+//*****************************************************************************
+
+#include <avr/io.h>
+#include <avr/interrupt.h>
+
+#include "global.h"
+#include "a2d.h"
+
+// global variables
+
+// number of channels to convert
+#define NUM_CH 8
+
+// number of samples to average
+#define NUM_SAMPLES 16
+
+// current channel
+volatile unsigned char current_ch;
+// list of channels to convert
+const unsigned char list_ch[NUM_CH]={0,1,2,3,4,5,6,7};
+// channel data
+volatile short int adc_data[NUM_CH];
+// averaged channel data
+volatile short int ch1_data[NUM_SAMPLES];
+volatile short int ch2_data[NUM_SAMPLES];
+volatile short int ch3_data[NUM_SAMPLES];
+volatile short int ch4_data[NUM_SAMPLES];
+volatile short int ch5_data[NUM_SAMPLES];
+volatile short int ch6_data[NUM_SAMPLES];
+volatile short int ch7_data[NUM_SAMPLES];
+volatile short int ch8_data[NUM_SAMPLES];
+volatile unsigned char current_sample;
+
+// functions
+
+// initialize a2d converter
+void a2dInit(void)
+{
+  // configure the analog inputs
+  DDRF = 0x00;
+  PORTF = 0x00;  
+
+  sbi(ADCSR, ADEN);				// enable ADC (turn on ADC power)
+  cbi(ADCSR, ADFR);				// default to single sample convert mode
+  a2dSetPrescaler(ADC_PRESCALE);	// set default prescaler
+  a2dSetReference(ADC_REFERENCE);	// set default reference
+  cbi(ADMUX, ADLAR);				// set to right-adjusted result
+
+  // set the initial channel to convert
+  current_ch=0;
+  current_sample=0;
+  a2dSetChannel(list_ch[current_ch]);
+  
+  // start conversion
+  a2dStartConvert();
+
+  sbi(ADCSR, ADIE);				// enable ADC interrupts
+}
+
+// turn off a2d converter
+void a2dOff(void)
+{
+	cbi(ADCSR, ADIE);				// disable ADC interrupts
+	cbi(ADCSR, ADEN);				// disable ADC (turn off ADC power)
+}
+
+// configure A2D converter clock division (prescaling)
+void a2dSetPrescaler(unsigned char prescale)
+{
+	outb(ADCSR, ((inb(ADCSR) & ~ADC_PRESCALE_MASK) | prescale));
+}
+
+// configure A2D converter voltage reference
+void a2dSetReference(unsigned char ref)
+{
+	outb(ADMUX, ((inb(ADMUX) & ~ADC_REFERENCE_MASK) | (ref<<6)));
+}
+
+// sets the a2d input channel
+void a2dSetChannel(unsigned char ch)
+{
+	outb(ADMUX, (inb(ADMUX) & ~ADC_MUX_MASK) | (ch & ADC_MUX_MASK));	// set channel
+}
+
+// start a conversion on the current a2d input channel
+void a2dStartConvert(void)
+{
+	sbi(ADCSR, ADIF);	// clear hardware "conversion complete" flag 
+	sbi(ADCSR, ADSC);	// start conversion
+}
+
+// return TRUE if conversion is complete
+u08 a2dIsComplete(void)
+{
+	return bit_is_set(ADCSR, ADSC);
+}
+
+//! Interrupt handler for ADC complete interrupt.
+SIGNAL(ADC_vect)
+{
+  short int data;
+
+  // save data
+  data=(inb(ADCL) | (inb(ADCH)<<8));
+  adc_data[current_ch]=data;
+  switch(current_ch)
+  {
+    case 0: ch1_data[current_sample]=data;
+	        break;
+    case 1: ch2_data[current_sample]=data;
+	        break;
+    case 2: ch3_data[current_sample]=data;
+	        break;
+    case 3: ch4_data[current_sample]=data;
+	        break;
+    case 4: ch5_data[current_sample]=data;
+	        break;
+    case 5: ch6_data[current_sample]=data;
+	        break;
+    case 6: ch7_data[current_sample]=data;
+	        break;
+    case 7: ch8_data[current_sample]=data;
+	        break;
+  }
+  // prepare for next channel
+  if(current_ch==(NUM_CH-1))
+    current_sample=(current_sample+1)%NUM_SAMPLES;
+  current_ch=(current_ch+1)%NUM_CH;
+  a2dSetChannel(list_ch[current_ch]);
+  a2dStartConvert();
+}
+
+unsigned short int adc_get_channel(unsigned char ch_id)
+{
+  if(ch_id>=0 && ch_id<=7)
+     return adc_data[ch_id];
+  else
+     return 0xFFFF;
+}
+
+unsigned short int adc_get_averaged_channel(unsigned char ch_id)
+{
+  short int *data_pointer;
+  short int average=0;
+  unsigned char i;
+
+  switch(ch_id)
+  {
+    case 0: data_pointer=ch1_data;
+	        break;
+    case 1: data_pointer=ch2_data;
+	        break;
+    case 2: data_pointer=ch3_data;
+	        break;
+    case 3: data_pointer=ch4_data;
+	        break;
+    case 4: data_pointer=ch5_data;
+	        break;
+    case 5: data_pointer=ch6_data;
+	        break;
+    case 6: data_pointer=ch7_data;
+	        break;
+    case 7: data_pointer=ch8_data;
+	        break;
+	default: return 0xFFFF;
+	         break;
+  }
+  for(i=0;i<NUM_SAMPLES;i++)
+    average=average+data_pointer[i];
+  average=average/NUM_SAMPLES;
+
+  return average;
+}
diff --git a/a2d.h b/a2d.h
new file mode 100755
index 0000000..076a654
--- /dev/null
+++ b/a2d.h
@@ -0,0 +1,147 @@
+/*! \file a2d.h \brief Analog-to-Digital converter function library. */
+//*****************************************************************************
+//
+// File Name	: 'a2d.h'
+// Title		: Analog-to-digital converter functions
+// Author		: Pascal Stang - Copyright (C) 2002
+// Created		: 4/08/2002
+// Revised		: 4/30/2002
+// Version		: 1.1
+// Target MCU	: Atmel AVR series
+// Editor Tabs	: 4
+//
+// This code is distributed under the GNU Public License
+//		which can be found at http://www.gnu.org/licenses/gpl.txt
+//
+///	\ingroup driver_avr
+/// \defgroup a2d A/D Converter Function Library (a2d.c)
+/// \code #include "a2d.h" \endcode
+/// \par Overview
+///		This library provides an easy interface to the analog-to-digital
+///		converter available on many AVR processors.  Updated to support
+///		the ATmega128.
+//
+//****************************************************************************
+//@{
+
+#ifndef A2D_H
+#define A2D_H
+
+// defines
+
+// A2D clock prescaler select
+//		*selects how much the CPU clock frequency is divided
+//		to create the A2D clock frequency
+//		*lower division ratios make conversion go faster
+//		*higher division ratios make conversions more accurate
+#define ADC_PRESCALE_DIV2		0x00	///< 0x01,0x00 -> CPU clk/2
+#define ADC_PRESCALE_DIV4		0x02	///< 0x02 -> CPU clk/4
+#define ADC_PRESCALE_DIV8		0x03	///< 0x03 -> CPU clk/8
+#define ADC_PRESCALE_DIV16		0x04	///< 0x04 -> CPU clk/16
+#define ADC_PRESCALE_DIV32		0x05	///< 0x05 -> CPU clk/32
+#define ADC_PRESCALE_DIV64		0x06	///< 0x06 -> CPU clk/64
+#define ADC_PRESCALE_DIV128		0x07	///< 0x07 -> CPU clk/128
+// default value
+#define ADC_PRESCALE			ADC_PRESCALE_DIV64
+// do not change the mask value
+#define ADC_PRESCALE_MASK		0x07
+
+// A2D voltage reference select
+//		*this determines what is used as the
+//		full-scale voltage point for A2D conversions
+#define ADC_REFERENCE_AREF		0x00	///< 0x00 -> AREF pin, internal VREF turned off
+#define ADC_REFERENCE_AVCC		0x01	///< 0x01 -> AVCC pin, internal VREF turned off
+#define ADC_REFERENCE_RSVD		0x02	///< 0x02 -> Reserved
+#define ADC_REFERENCE_256V		0x03	///< 0x03 -> Internal 2.56V VREF
+// default value
+#define ADC_REFERENCE			ADC_REFERENCE_AVCC
+// do not change the mask value
+#define ADC_REFERENCE_MASK		0xC0
+
+// bit mask for A2D channel multiplexer
+#define ADC_MUX_MASK			0x1F
+
+// channel defines (for reference and use in code)
+// these channels supported by all AVRs with A2D
+#define ADC_CH_ADC0				0x00
+#define ADC_CH_ADC1				0x01
+#define ADC_CH_ADC2				0x02
+#define ADC_CH_ADC3				0x03
+#define ADC_CH_ADC4				0x04
+#define ADC_CH_ADC5				0x05
+#define ADC_CH_ADC6				0x06
+#define ADC_CH_ADC7				0x07
+#define ADC_CH_122V				0x1E	///< 1.22V voltage reference
+#define ADC_CH_AGND				0x1F	///< AGND
+// these channels supported only in ATmega128
+// differential with gain
+#define ADC_CH_0_0_DIFF10X		0x08
+#define ADC_CH_1_0_DIFF10X		0x09
+#define ADC_CH_0_0_DIFF200X		0x0A
+#define ADC_CH_1_0_DIFF200X		0x0B
+#define ADC_CH_2_2_DIFF10X		0x0C
+#define ADC_CH_3_2_DIFF10X		0x0D
+#define ADC_CH_2_2_DIFF200X		0x0E
+#define ADC_CH_3_2_DIFF200X		0x0F
+// differential
+#define ADC_CH_0_1_DIFF1X		0x10
+#define ADC_CH_1_1_DIFF1X		0x11
+#define ADC_CH_2_1_DIFF1X		0x12
+#define ADC_CH_3_1_DIFF1X		0x13
+#define ADC_CH_4_1_DIFF1X		0x14
+#define ADC_CH_5_1_DIFF1X		0x15
+#define ADC_CH_6_1_DIFF1X		0x16
+#define ADC_CH_7_1_DIFF1X		0x17
+
+#define ADC_CH_0_2_DIFF1X		0x18
+#define ADC_CH_1_2_DIFF1X		0x19
+#define ADC_CH_2_2_DIFF1X		0x1A
+#define ADC_CH_3_2_DIFF1X		0x1B
+#define ADC_CH_4_2_DIFF1X		0x1C
+#define ADC_CH_5_2_DIFF1X		0x1D
+
+// compatibility for new Mega processors
+// ADCSR hack apparently no longer necessary in new AVR-GCC
+#ifdef ADCSRA
+#ifndef ADCSR
+	#define ADCSR	ADCSRA
+#endif
+#endif
+#ifdef ADATE
+	#define ADFR	ADATE
+#endif
+
+// function prototypes
+
+//! Initializes the A/D converter.
+/// Turns ADC on and prepares it for use.
+void a2dInit(void);
+
+//! Turn off A/D converter
+void a2dOff(void);
+
+//! Sets the division ratio of the A/D converter clock.
+/// This function is automatically called from a2dInit()
+/// with a default value.
+void a2dSetPrescaler(unsigned char prescale);
+
+//! Configures which voltage reference the A/D converter uses.
+/// This function is automatically called from a2dInit()
+/// with a default value.
+void a2dSetReference(unsigned char ref);
+
+//! sets the a2d input channel
+void a2dSetChannel(unsigned char ch);
+
+//! start a conversion on the current a2d input channel
+void a2dStartConvert(void);
+
+//! return TRUE if conversion is complete
+u08 a2dIsComplete(void);
+
+unsigned short int adc_get_channel(unsigned char ch_id);
+
+unsigned short int adc_get_averaged_channel(unsigned char ch_id);
+
+#endif
+//@}
diff --git a/avrlibdefs.h b/avrlibdefs.h
new file mode 100755
index 0000000..a8dea50
--- /dev/null
+++ b/avrlibdefs.h
@@ -0,0 +1,83 @@
+/*! \file avrlibdefs.h \brief AVRlib global defines and macros. */
+//*****************************************************************************
+//
+// File Name	: 'avrlibdefs.h'
+// Title		: AVRlib global defines and macros include file
+// Author		: Pascal Stang
+// Created		: 7/12/2001
+// Revised		: 9/30/2002
+// Version		: 1.1
+// Target MCU	: Atmel AVR series
+// Editor Tabs	: 4
+//
+//	Description : This include file is designed to contain items useful to all
+//					code files and projects, regardless of specific implementation.
+//
+// This code is distributed under the GNU Public License
+//		which can be found at http://www.gnu.org/licenses/gpl.txt
+//
+//*****************************************************************************
+
+
+#ifndef AVRLIBDEFS_H
+#define AVRLIBDEFS_H
+
+// Code compatibility to new AVR-libc
+// outb(), inb(), inw(), outw(), BV(), sbi(), cbi(), sei(), cli()
+#ifndef outb
+	#define	outb(addr, data)	addr = (data)
+#endif
+#ifndef inb
+	#define	inb(addr)			(addr)
+#endif
+#ifndef outw
+	#define	outw(addr, data)	addr = (data)
+#endif
+#ifndef inw
+	#define	inw(addr)			(addr)
+#endif
+#ifndef BV
+	#define BV(bit)			(1<<(bit))
+#endif
+#ifndef cbi
+	#define cbi(reg,bit)	reg &= ~(BV(bit))
+#endif
+#ifndef sbi
+	#define sbi(reg,bit)	reg |= (BV(bit))
+#endif
+#ifndef cli
+	#define cli()			__asm__ __volatile__ ("cli" ::)
+#endif
+#ifndef sei
+	#define sei()			__asm__ __volatile__ ("sei" ::)
+#endif
+
+// support for individual port pin naming in the mega128
+// see port128.h for details
+#ifdef __AVR_ATmega128__
+// not currently necessary due to inclusion
+// of these defines in newest AVR-GCC
+// do a quick test to see if include is needed
+#ifndef PD0
+	#include "port128.h"
+#endif
+#endif
+
+// use this for packed structures
+// (this is seldom necessary on an 8-bit architecture like AVR,
+//  but can assist in code portability to AVR)
+#define GNUC_PACKED __attribute__((packed)) 
+
+// port address helpers
+#define DDR(x) ((x)-1)    // address of data direction register of port x
+#define PIN(x) ((x)-2)    // address of input register of port x
+
+// MIN/MAX/ABS macros
+#define MIN(a,b)			((a<b)?(a):(b))
+#define MAX(a,b)			((a>b)?(a):(b))
+#define ABS(x)				((x>0)?(x):(-x))
+
+// constants
+#define PI		3.14159265359
+
+#endif
diff --git a/avrlibtypes.h b/avrlibtypes.h
new file mode 100755
index 0000000..4d44ac5
--- /dev/null
+++ b/avrlibtypes.h
@@ -0,0 +1,84 @@
+/*! \file avrlibtypes.h \brief AVRlib global types and typedefines. */
+//*****************************************************************************
+//
+// File Name	: 'avrlibtypes.h'
+// Title		: AVRlib global types and typedefines include file
+// Author		: Pascal Stang
+// Created		: 7/12/2001
+// Revised		: 9/30/2002
+// Version		: 1.0
+// Target MCU	: Atmel AVR series
+// Editor Tabs	: 4
+//
+//	Description : Type-defines required and used by AVRlib.  Most types are also
+//						generally useful.
+//
+// This code is distributed under the GNU Public License
+//		which can be found at http://www.gnu.org/licenses/gpl.txt
+//
+//*****************************************************************************
+
+
+#ifndef AVRLIBTYPES_H
+#define AVRLIBTYPES_H
+
+#ifndef WIN32
+	// true/false defines
+	#define FALSE	0
+	#define TRUE	-1
+#endif
+
+// datatype definitions macros
+typedef unsigned char  u08;
+typedef   signed char  s08;
+typedef unsigned short u16;
+typedef   signed short s16;
+typedef unsigned long  u32;
+typedef   signed long  s32;
+typedef unsigned long long u64;
+typedef   signed long long s64;
+
+/* use inttypes.h instead
+// C99 standard integer type definitions
+typedef unsigned char	uint8_t;
+typedef   signed char	int8_t;
+typedef unsigned short	uint16_t;
+typedef   signed short	int16_t;
+typedef unsigned long	uint32_t;
+typedef   signed long	int32_t;
+typedef unsigned long	uint64_t;
+typedef   signed long	int64_t;
+*/
+// maximum value that can be held
+// by unsigned data types (8,16,32bits)
+#define MAX_U08	255
+#define MAX_U16	65535
+#define MAX_U32	4294967295
+
+// maximum values that can be held
+// by signed data types (8,16,32bits)
+#define MIN_S08	-128
+#define MAX_S08	127
+#define MIN_S16	-32768
+#define MAX_S16	32767
+#define MIN_S32	-2147483648
+#define MAX_S32	2147483647
+
+#ifndef WIN32
+	// more type redefinitions
+	typedef unsigned char   BOOL;
+	typedef unsigned char	BYTE;
+	typedef unsigned int	WORD;
+	typedef unsigned long	DWORD;
+
+	typedef unsigned char	UCHAR;
+	typedef unsigned int	UINT;
+	typedef unsigned short  USHORT;
+	typedef unsigned long	ULONG;
+
+	typedef char			CHAR;
+	typedef int				INT;
+	typedef long			LONG;
+#endif
+
+#endif
diff --git a/buffer.c b/buffer.c
new file mode 100755
index 0000000..304221f
--- /dev/null
+++ b/buffer.c
@@ -0,0 +1,163 @@
+/*! \file buffer.c \brief Multipurpose byte buffer structure and methods. */
+//*****************************************************************************
+//
+// File Name	: 'buffer.c'
+// Title		: Multipurpose byte buffer structure and methods
+// Author		: Pascal Stang - Copyright (C) 2001-2002
+// Created		: 9/23/2001
+// Revised		: 9/23/2001
+// Version		: 1.0
+// Target MCU	: any
+// Editor Tabs	: 4
+//
+// This code is distributed under the GNU Public License
+//		which can be found at http://www.gnu.org/licenses/gpl.txt
+//
+//*****************************************************************************
+
+#include "buffer.h"
+#include "global.h"
+#include "avr/io.h"
+
+#ifndef CRITICAL_SECTION_START
+#define CRITICAL_SECTION_START	unsigned char _sreg = SREG; cli()
+#define CRITICAL_SECTION_END	SREG = _sreg
+#endif
+
+// global variables
+
+// initialization
+
+void bufferInit(cBuffer* buffer, unsigned char *start, unsigned short size)
+{
+	// begin critical section
+	CRITICAL_SECTION_START;
+	// set start pointer of the buffer
+	buffer->dataptr = start;
+	buffer->size = size;
+	// initialize index and length
+	buffer->dataindex = 0;
+	buffer->datalength = 0;
+	// end critical section
+	CRITICAL_SECTION_END;
+}
+
+// access routines
+unsigned char  bufferGetFromFront(cBuffer* buffer)
+{
+	unsigned char data = 0;
+	// begin critical section
+	CRITICAL_SECTION_START;
+	// check to see if there's data in the buffer
+	if(buffer->datalength)
+	{
+		// get the first character from buffer
+		data = buffer->dataptr[buffer->dataindex];
+		// move index down and decrement length
+		buffer->dataindex++;
+		if(buffer->dataindex >= buffer->size)
+		{
+			buffer->dataindex -= buffer->size;
+		}
+		buffer->datalength--;
+	}
+	// end critical section
+	CRITICAL_SECTION_END;
+	// return
+	return data;
+}
+
+void bufferDumpFromFront(cBuffer* buffer, unsigned short numbytes)
+{
+	// begin critical section
+	CRITICAL_SECTION_START;
+	// dump numbytes from the front of the buffer
+	// are we dumping less than the entire buffer?
+	if(numbytes < buffer->datalength)
+	{
+		// move index down by numbytes and decrement length by numbytes
+		buffer->dataindex += numbytes;
+		if(buffer->dataindex >= buffer->size)
+		{
+			buffer->dataindex -= buffer->size;
+		}
+		buffer->datalength -= numbytes;
+	}
+	else
+	{
+		// flush the whole buffer
+		buffer->datalength = 0;
+	}
+	// end critical section
+	CRITICAL_SECTION_END;
+}
+
+unsigned char bufferGetAtIndex(cBuffer* buffer, unsigned short index)
+{
+	// begin critical section
+	CRITICAL_SECTION_START;
+	// return character at index in buffer
+	unsigned char data = buffer->dataptr[(buffer->dataindex+index)%(buffer->size)];
+	// end critical section
+	CRITICAL_SECTION_END;
+	return data;
+}
+
+unsigned char bufferAddToEnd(cBuffer* buffer, unsigned char data)
+{
+	// begin critical section
+	CRITICAL_SECTION_START;
+	// make sure the buffer has room
+	if(buffer->datalength < buffer->size)
+	{
+		// save data byte at end of buffer
+		buffer->dataptr[(buffer->dataindex + buffer->datalength) % buffer->size] = data;
+		// increment the length
+		buffer->datalength++;
+		// end critical section
+		CRITICAL_SECTION_END;
+		// return success
+		return -1;
+	}
+	// end critical section
+	CRITICAL_SECTION_END;
+	// return failure
+	return 0;
+}
+
+unsigned short bufferIsNotFull(cBuffer* buffer)
+{
+	// begin critical section
+	CRITICAL_SECTION_START;
+	// check to see if the buffer has room
+	// return true if there is room
+	unsigned short bytesleft = (buffer->size - buffer->datalength);
+	// end critical section
+	CRITICAL_SECTION_END;
+	return bytesleft;
+}
+
+unsigned short bufferIsEmpty(cBuffer *buffer)
+{
+	// begin critical section
+	CRITICAL_SECTION_START;
+	// check to see if the buffer has room
+	// return true if there is room
+	unsigned short bytes = buffer->datalength;
+	// end critical section
+	CRITICAL_SECTION_END;
+	if(bytes==0) return TRUE;
+	else return FALSE;
+  
+}
+
+void bufferFlush(cBuffer* buffer)
+{
+	// begin critical section
+	CRITICAL_SECTION_START;
+	// flush contents of the buffer
+	buffer->datalength = 0;
+	// end critical section
+	CRITICAL_SECTION_END;
+}
+
diff --git a/buffer.h b/buffer.h
new file mode 100755
index 0000000..40b35d1
--- /dev/null
+++ b/buffer.h
@@ -0,0 +1,76 @@
+/*! \file buffer.h \brief Multipurpose byte buffer structure and methods. */
+//*****************************************************************************
+//
+// File Name	: 'buffer.h'
+// Title		: Multipurpose byte buffer structure and methods
+// Author		: Pascal Stang - Copyright (C) 2001-2002
+// Created		: 9/23/2001
+// Revised		: 11/16/2002
+// Version		: 1.1
+// Target MCU	: any
+// Editor Tabs	: 4
+//
+///	\ingroup general
+/// \defgroup buffer Circular Byte-Buffer Structure and Function Library (buffer.c)
+/// \code #include "buffer.h" \endcode
+/// \par Overview
+///		This byte-buffer structure provides an easy and efficient way to store
+///		and process a stream of bytes.  You can create as many buffers as you
+///		like (within memory limits), and then use this common set of functions to
+///		access each buffer.  The buffers are designed for FIFO operation (first
+///		in, first out).  This means that the first byte you put in the buffer
+///		will be the first one you get when you read out the buffer.  Supported
+///		functions include buffer initialize, get byte from front of buffer, add
+///		byte to end of buffer, check if buffer is full, and flush buffer.  The
+///		buffer uses a circular design so no copying of data is ever necessary.
+///		This buffer is not dynamically allocated, it has a user-defined fixed
+///		maximum size.  This buffer is used in many places in the avrlib code.
+//
+// This code is distributed under the GNU Public License
+//		which can be found at http://www.gnu.org/licenses/gpl.txt
+//
+//*****************************************************************************
+//@{
+
+#ifndef BUFFER_H
+#define BUFFER_H
+
+// structure/typdefs
+
+//! cBuffer structure
+typedef struct struct_cBuffer
+{
+	unsigned char *dataptr;			///< the physical memory address where the buffer is stored
+	unsigned short size;			///< the allocated size of the buffer
+	unsigned short datalength;		///< the length of the data currently in the buffer
+	unsigned short dataindex;		///< the index into the buffer where the data starts
+} cBuffer;
+
+// function prototypes
+
+//! initialize a buffer to start at a given address and have given size
+void			bufferInit(cBuffer* buffer, unsigned char *start, unsigned short size);
+
+//! get the first byte from the front of the buffer
+unsigned char	bufferGetFromFront(cBuffer* buffer);
+
+//! dump (discard) the first numbytes from the front of the buffer
+void bufferDumpFromFront(cBuffer* buffer, unsigned short numbytes);
+
+//! get a byte at the specified index in the buffer (kind of like array access)
+// ** note: this does not remove the byte that was read from the buffer
+unsigned char	bufferGetAtIndex(cBuffer* buffer, unsigned short index);
+
+//! add a byte to the end of the buffer
+unsigned char	bufferAddToEnd(cBuffer* buffer, unsigned char data);
+
+//! check if the buffer is full/not full (returns zero value if full)
+unsigned short	bufferIsNotFull(cBuffer* buffer);
+
+//! flush (clear) the contents of the buffer
+void			bufferFlush(cBuffer* buffer);
+
+unsigned short bufferIsEmpty(cBuffer *buffer);
+
+#endif
+//@}
diff --git a/compass.c b/compass.c
new file mode 100755
index 0000000..973d8d5
--- /dev/null
+++ b/compass.c
@@ -0,0 +1,136 @@
+#include "compass.h"
+#include "avr/io.h"
+#include "i2c.h"
+
+volatile unsigned short int compass_heading;
+volatile unsigned short int compass_heading_averaged;
+volatile unsigned char waiting_data;
+
+void CompassInit(void)
+{
+  unsigned char cmd=COMPASS_HEADING;
+
+  calibrate=FALSE;
+  calibrating=FALSE;
+  compass_heading=0;
+  compass_heading_averaged=0;
+  // the I2C peripheral must be initialized before calling this function
+  i2cMasterSend(COMPASS_ADDR, 1, &cmd);
+  waiting_data=FALSE;
+}
+
+void compass_avrg(unsigned short int heading)
+{
+  static unsigned long int new_average,first_value;
+  static unsigned char num_data=0;
+  unsigned long int diff=0;
+  
+  if(num_data==0)
+  {
+    num_data=num_data+1;
+    first_value=(long int)heading;
+  }  
+  else
+  {
+    diff=heading+3600-first_value;
+    if(diff<1800)
+	  diff=diff+3600;
+    else if(diff>5400) 
+	  diff=diff-3600;
+    new_average=new_average+diff;
+    num_data=num_data+1;
+    if(num_data==17)
+    {
+	  new_average=new_average/16;
+	  new_average=new_average+first_value;
+      compass_heading_averaged=(unsigned short int)new_average;
+      if(compass_heading_averaged>3600)
+        compass_heading_averaged=compass_heading_averaged-3600;
+      new_average=0;
+      num_data=0; 
+    }
+  }
+}
+
+void compass_periodic_call(void)
+{
+  unsigned char cmd,heading[2];
+  static int count=0;
+
+  if(i2cGetState()==I2C_IDLE)
+  {
+    if(waiting_data)
+	{
+	  if(calibrate)
+	  {
+		calibrating=TRUE;
+		calibrate=FALSE;
+		count=100;
+	  }
+	  else if(calibrating)
+	  {
+	    if(count>0)
+		  count--;
+        else
+		{
+    	  cmd=COMPASS_START_CAL;
+		  i2cMasterSend(COMPASS_ADDR, 1, &cmd);
+          waiting_data=FALSE;
+        }
+	  }
+	  else
+	  {
+	    if(count>0)
+		  count--;
+        else
+		{
+          i2c_get_data(2,heading);
+	      compass_heading=heading[1]+(heading[0]<<8);
+	      compass_avrg(compass_heading);
+	      cmd=COMPASS_HEADING;
+          i2cMasterSend(COMPASS_ADDR, 1, &cmd);
+          waiting_data=FALSE;
+		  count = 10;
+        }
+	  }
+	}
+	else
+	{
+	  if(calibrating)
+	  {
+	     count++;
+		 if(count==30000)
+		 {
+ 	       cmd=COMPASS_STOP_CAL;
+		   i2cMasterSend(COMPASS_ADDR, 1, &cmd);
+		   waiting_data=TRUE;
+		   calibrate=FALSE;
+		   calibrating=FALSE;
+		   count = 100;
+		 }
+	  }
+	  else
+	  {
+	    if(count>0)
+		  count--;
+        else
+		{
+	      i2cMasterReceive(COMPASS_ADDR,2);
+	      waiting_data=TRUE;	
+        }
+	  }
+	}
+  }
+}
+
+unsigned short int compass_get_heading(void)
+{
+  return compass_heading;
+}
+
+unsigned short int compass_get_averaged_heading(void)
+{
+  return compass_heading_averaged;
+}
+
+
diff --git a/compass.h b/compass.h
new file mode 100755
index 0000000..85a2856
--- /dev/null
+++ b/compass.h
@@ -0,0 +1,20 @@
+#ifndef _COMPASS_H
+#define _COMPASS_H
+
+// compass address
+#define COMPASS_ADDR 0x42
+
+// compass commands
+#define COMPASS_HEADING 0x41
+#define COMPASS_START_CAL 0x43
+#define COMPASS_STOP_CAL 0x45
+
+volatile unsigned char calibrate;
+volatile unsigned char calibrating;
+
+void CompassInit(void);
+void compass_periodic_call(void);
+unsigned short int compass_get_heading(void);
+unsigned short int compass_get_averaged_heading(void);
+
+#endif
diff --git a/default/Makefile b/default/Makefile
new file mode 100755
index 0000000..ab0cc84
--- /dev/null
+++ b/default/Makefile
@@ -0,0 +1,101 @@
+###############################################################################
+# Makefile for the project expansion_board
+###############################################################################
+
+## General Flags
+PROJECT = expansion_board
+MCU = atmega128
+TARGET = expansion_board.elf
+CC = avr-gcc
+
+CPP = avr-g++
+
+## Options common to compile, link and assembly rules
+COMMON = -mmcu=$(MCU)
+
+## Compile options common for all C compilation units.
+CFLAGS = $(COMMON)
+CFLAGS += -Wall -gdwarf-2 -std=gnu99   -Os -funsigned-char -funsigned-bitfields -fpack-struct -fshort-enums
+CFLAGS += -MD -MP -MT $(*F).o -MF dep/$(@F).d 
+
+## Assembly specific flags
+ASMFLAGS = $(COMMON)
+ASMFLAGS += $(CFLAGS)
+ASMFLAGS += -x assembler-with-cpp -Wa,-gdwarf2
+
+## Linker flags
+LDFLAGS = $(COMMON)
+LDFLAGS +=  -Wl,-Map=expansion_board.map
+
+
+## Intel Hex file production flags
+HEX_FLASH_FLAGS = -R .eeprom -R .fuse -R .lock -R .signature
+
+HEX_EEPROM_FLAGS = -j .eeprom
+HEX_EEPROM_FLAGS += --set-section-flags=.eeprom="alloc,load"
+HEX_EEPROM_FLAGS += --change-section-lma .eeprom=0 --no-change-warnings
+
+
+## Objects that must be built in order to link
+OBJECTS = expansion_board.o dynamixel.o timer128.o compass.o i2c.o a2d.o buffer.o uartsw.o ports.o 
+
+## Objects explicitly added by the user
+LINKONLYOBJECTS = 
+
+## Build
+all: $(TARGET) expansion_board.hex expansion_board.eep expansion_board.lss size
+
+## Compile
+expansion_board.o: ../expansion_board.c
+	$(CC) $(INCLUDES) $(CFLAGS) -c  $<
+
+dynamixel.o: ../dynamixel.c
+	$(CC) $(INCLUDES) $(CFLAGS) -c  $<
+
+timer128.o: ../timer128.c
+	$(CC) $(INCLUDES) $(CFLAGS) -c  $<
+
+compass.o: ../compass.c
+	$(CC) $(INCLUDES) $(CFLAGS) -c  $<
+
+i2c.o: ../i2c.c
+	$(CC) $(INCLUDES) $(CFLAGS) -c  $<
+
+a2d.o: ../a2d.c
+	$(CC) $(INCLUDES) $(CFLAGS) -c  $<
+
+buffer.o: ../buffer.c
+	$(CC) $(INCLUDES) $(CFLAGS) -c  $<
+
+uartsw.o: ../uartsw.c
+	$(CC) $(INCLUDES) $(CFLAGS) -c  $<
+
+ports.o: ../ports.c
+	$(CC) $(INCLUDES) $(CFLAGS) -c  $<
+
+##Link
+$(TARGET): $(OBJECTS)
+	 $(CC) $(LDFLAGS) $(OBJECTS) $(LINKONLYOBJECTS) $(LIBDIRS) $(LIBS) -o $(TARGET)
+
+%.hex: $(TARGET)
+	avr-objcopy -O ihex $(HEX_FLASH_FLAGS)  $< $@
+
+%.eep: $(TARGET)
+	-avr-objcopy $(HEX_EEPROM_FLAGS) -O ihex $< $@ || exit 0
+
+%.lss: $(TARGET)
+	avr-objdump -h -S $< > $@
+
+size: ${TARGET}
+	@echo
+	@avr-size -C --mcu=${MCU} ${TARGET}
+
+## Clean target
+.PHONY: clean
+clean:
+	-rm -rf $(OBJECTS) expansion_board.elf dep/* expansion_board.hex expansion_board.eep expansion_board.lss expansion_board.map
+
+
+## Other dependencies
+-include $(shell mkdir dep 2>NUL) $(wildcard dep/*)
+
diff --git a/default/NUL b/default/NUL
new file mode 100644
index 0000000..1b1fbad
--- /dev/null
+++ b/default/NUL
@@ -0,0 +1 @@
+mkdir: cannot create directory ‘dep’: File exists
diff --git a/default/expansion_board.aps b/default/expansion_board.aps
new file mode 100755
index 0000000..b5a5f59
--- /dev/null
+++ b/default/expansion_board.aps
@@ -0,0 +1 @@
+<AVRStudio><MANAGEMENT><ProjectName>expansion_board</ProjectName><Created>21-Jan-2011 15:23:22</Created><LastEdit>18-Jul-2011 12:33:48</LastEdit><ICON>241</ICON><ProjectType>0</ProjectType><Created>21-Jan-2011 15:23:22</Created><Version>4</Version><Build>4, 18, 0, 685</Build><ProjectTypeName>AVR GCC</ProjectTypeName></MANAGEMENT><CODE_CREATION><ObjectFile>default\expansion_board.elf</ObjectFile><EntryFile></EntryFile><SaveFolder>\\VBOXSVR\shared\Software\</SaveFolder></CODE_CREATION><DEBUG_TARGET><CURRENT_TARGET></CURRENT_TARGET><CURRENT_PART></CURRENT_PART><BREAKPOINTS></BREAKPOINTS><IO_EXPAND><HIDE>false</HIDE></IO_EXPAND><REGISTERNAMES><Register>R00</Register><Register>R01</Register><Register>R02</Register><Register>R03</Register><Register>R04</Register><Register>R05</Register><Register>R06</Register><Register>R07</Register><Register>R08</Register><Register>R09</Register><Register>R10</Register><Register>R11</Register><Register>R12</Register><Register>R13</Register><Register>R14</Register><Register>R15</Register><Register>R16</Register><Register>R17</Register><Register>R18</Register><Register>R19</Register><Register>R20</Register><Register>R21</Register><Register>R22</Register><Register>R23</Register><Register>R24</Register><Register>R25</Register><Register>R26</Register><Register>R27</Register><Register>R28</Register><Register>R29</Register><Register>R30</Register><Register>R31</Register></REGISTERNAMES><COM></COM><COMType>0</COMType><WATCHNUM>0</WATCHNUM><WATCHNAMES><Pane0></Pane0><Pane1></Pane1><Pane2></Pane2><Pane3></Pane3></WATCHNAMES><BreakOnTrcaeFull>0</BreakOnTrcaeFull></DEBUG_TARGET><Debugger><Triggers></Triggers></Debugger><AVRGCCPLUGIN><FILES><SOURCEFILE>expansion_board.c</SOURCEFILE><SOURCEFILE>dynamixel.c</SOURCEFILE><SOURCEFILE>timer128.c</SOURCEFILE><SOURCEFILE>compass.c</SOURCEFILE><SOURCEFILE>i2c.c</SOURCEFILE><SOURCEFILE>a2d.c</SOURCEFILE><SOURCEFILE>buffer.c</SOURCEFILE><SOURCEFILE>uartsw.c</SOURCEFILE><SOURCEFILE>ports.c</SOURCEFILE><HEADERFILE>utils.h</HEADERFILE><HEADERFILE>dynamixel.h</HEADERFILE><HEADERFILE>global.h</HEADERFILE><HEADERFILE>timer128.h</HEADERFILE><HEADERFILE>avrlibtypes.h</HEADERFILE><HEADERFILE>avrlibdefs.h</HEADERFILE><HEADERFILE>port128.h</HEADERFILE><HEADERFILE>compass.h</HEADERFILE><HEADERFILE>i2c.h</HEADERFILE><HEADERFILE>i2cconf.h</HEADERFILE><HEADERFILE>memory_map.h</HEADERFILE><HEADERFILE>a2d.h</HEADERFILE><HEADERFILE>buffer.h</HEADERFILE><HEADERFILE>uartsw.h</HEADERFILE><HEADERFILE>uartswconf.h</HEADERFILE><HEADERFILE>ports.h</HEADERFILE><OTHERFILE>default\expansion_board.lss</OTHERFILE><OTHERFILE>default\expansion_board.map</OTHERFILE></FILES><CONFIGS><CONFIG><NAME>default</NAME><USESEXTERNALMAKEFILE>NO</USESEXTERNALMAKEFILE><EXTERNALMAKEFILE></EXTERNALMAKEFILE><PART>atmega128</PART><HEX>1</HEX><LIST>1</LIST><MAP>1</MAP><OUTPUTFILENAME>expansion_board.elf</OUTPUTFILENAME><OUTPUTDIR>default\</OUTPUTDIR><ISDIRTY>1</ISDIRTY><OPTIONS><OPTION><FILE>buffer.c</FILE><OPTIONLIST></OPTIONLIST></OPTION><OPTION><FILE>dynamixel.c</FILE><OPTIONLIST></OPTIONLIST></OPTION><OPTION><FILE>expansion_board.c</FILE><OPTIONLIST></OPTIONLIST></OPTION><OPTION><FILE>timer128.c</FILE><OPTIONLIST></OPTIONLIST></OPTION><OPTION><FILE>uart2.c</FILE><OPTIONLIST></OPTIONLIST></OPTION></OPTIONS><INCDIRS/><LIBDIRS/><LIBS/><LINKOBJECTS/><OPTIONSFORALL>-Wall -gdwarf-2 -std=gnu99   -Os -funsigned-char -funsigned-bitfields -fpack-struct -fshort-enums</OPTIONSFORALL><LINKEROPTIONS></LINKEROPTIONS><SEGMENTS/></CONFIG></CONFIGS><LASTCONFIG>default</LASTCONFIG><USES_WINAVR>1</USES_WINAVR><GCC_LOC>C:\WinAVR-20100110\bin\avr-gcc.exe</GCC_LOC><MAKE_LOC>C:\WinAVR-20100110\utils\bin\make.exe</MAKE_LOC></AVRGCCPLUGIN><ProjectFiles><Files><Name>\\VBOXSVR\shared\Software\utils.h</Name><Name>\\VBOXSVR\shared\Software\dynamixel.h</Name><Name>\\VBOXSVR\shared\Software\global.h</Name><Name>\\VBOXSVR\shared\Software\timer128.h</Name><Name>\\VBOXSVR\shared\Software\avrlibtypes.h</Name><Name>\\VBOXSVR\shared\Software\avrlibdefs.h</Name><Name>\\VBOXSVR\shared\Software\port128.h</Name><Name>\\VBOXSVR\shared\Software\compass.h</Name><Name>\\VBOXSVR\shared\Software\i2c.h</Name><Name>\\VBOXSVR\shared\Software\i2cconf.h</Name><Name>\\VBOXSVR\shared\Software\memory_map.h</Name><Name>\\VBOXSVR\shared\Software\a2d.h</Name><Name>\\VBOXSVR\shared\Software\buffer.h</Name><Name>\\VBOXSVR\shared\Software\uartsw.h</Name><Name>\\VBOXSVR\shared\Software\uartswconf.h</Name><Name>\\VBOXSVR\shared\Software\ports.h</Name><Name>\\VBOXSVR\shared\Software\expansion_board.c</Name><Name>\\VBOXSVR\shared\Software\dynamixel.c</Name><Name>\\VBOXSVR\shared\Software\timer128.c</Name><Name>\\VBOXSVR\shared\Software\compass.c</Name><Name>\\VBOXSVR\shared\Software\i2c.c</Name><Name>\\VBOXSVR\shared\Software\a2d.c</Name><Name>\\VBOXSVR\shared\Software\buffer.c</Name><Name>\\VBOXSVR\shared\Software\uartsw.c</Name><Name>\\VBOXSVR\shared\Software\ports.c</Name></Files></ProjectFiles><IOView><usergroups/><sort sorted="0" column="0" ordername="0" orderaddress="0" ordergroup="0"/></IOView><Files><File00000><FileId>00000</FileId><FileName>expansion_board.c</FileName><Status>1</Status></File00000><File00001><FileId>00001</FileId><FileName>uartsw.h</FileName><Status>1</Status></File00001><File00002><FileId>00002</FileId><FileName>uartsw.c</FileName><Status>1</Status></File00002><File00003><FileId>00003</FileId><FileName>uartswconf.h</FileName><Status>1</Status></File00003><File00004><FileId>00004</FileId><FileName>buffer.h</FileName><Status>1</Status></File00004><File00005><FileId>00005</FileId><FileName>compass.c</FileName><Status>1</Status></File00005><File00006><FileId>00006</FileId><FileName>dynamixel.c</FileName><Status>1</Status></File00006><File00007><FileId>00007</FileId><FileName>dynamixel.h</FileName><Status>1</Status></File00007><File00008><FileId>00008</FileId><FileName>ports.h</FileName><Status>1</Status></File00008><File00009><FileId>00009</FileId><FileName>ports.c</FileName><Status>1</Status></File00009><File00010><FileId>00010</FileId><FileName>port128.h</FileName><Status>1</Status></File00010><File00011><FileId>00011</FileId><FileName>i2c.c</FileName><Status>1</Status></File00011><File00012><FileId>00012</FileId><FileName>compass.h</FileName><Status>1</Status></File00012><File00013><FileId>00013</FileId><FileName>buffer.c</FileName><Status>1</Status></File00013><File00014><FileId>00014</FileId><FileName>a2d.c</FileName><Status>1</Status></File00014></Files><Events><Bookmarks></Bookmarks></Events><Trace><Filters></Filters></Trace></AVRStudio>
diff --git a/default/expansion_board.aws b/default/expansion_board.aws
new file mode 100755
index 0000000..351856d
--- /dev/null
+++ b/default/expansion_board.aws
@@ -0,0 +1 @@
+<AVRWorkspace><IOSettings><CurrentRegisters/></IOSettings><part name=""/><Files><File00000 Name="\\Vboxsvr\shared\Software\expansion_board.c" Position="201 89 894 404" LineCol="146 14" State="Maximized"/><File00001 Name="\\Vboxsvr\shared\Software\uartsw.h" Position="223 116 908 401" LineCol="0 0" State="Maximized"/><File00002 Name="\\Vboxsvr\shared\Software\uartsw.c" Position="245 138 930 423" LineCol="49 0" State="Maximized"/><File00003 Name="\\Vboxsvr\shared\Software\uartswconf.h" Position="267 160 952 445" LineCol="40 0" State="Maximized"/><File00004 Name="\\Vboxsvr\shared\Software\buffer.h" Position="289 182 974 467" LineCol="0 0" State="Maximized"/><File00005 Name="\\Vboxsvr\shared\Software\compass.c" Position="311 204 996 489" LineCol="19 0" State="Maximized"/><File00006 Name="\\Vboxsvr\shared\Software\dynamixel.c" Position="333 226 1018 511" LineCol="226 0" State="Maximized"/><File00007 Name="\\Vboxsvr\shared\Software\dynamixel.h" Position="201 94 886 379" LineCol="26 0" State="Maximized"/><File00008 Name="\\Vboxsvr\shared\Software\ports.h" Position="223 116 908 401" LineCol="21 0" State="Maximized"/><File00009 Name="\\Vboxsvr\shared\Software\ports.c" Position="245 138 930 423" LineCol="22 0" State="Maximized"/><File00010 Name="\\Vboxsvr\shared\Software\port128.h" Position="267 160 952 445" LineCol="0 0" State="Maximized"/><File00011 Name="\\Vboxsvr\shared\Software\i2c.c" Position="289 182 974 467" LineCol="0 0" State="Maximized"/><File00012 Name="\\Vboxsvr\shared\Software\compass.h" Position="311 204 996 489" LineCol="12 35" State="Maximized"/><File00013 Name="\\Vboxsvr\shared\Software\buffer.c" Position="333 226 1018 511" LineCol="0 0" State="Maximized"/><File00014 Name="\\Vboxsvr\shared\Software\a2d.c" Position="201 94 886 379" LineCol="0 0" State="Maximized"/><File00015 Name="\\Vboxsvr\shared\Software\memory_map.h" Position="197 71 1026 519" LineCol="0 0" State="Maximized"/></Files></AVRWorkspace>
diff --git a/default/expansion_board.c b/default/expansion_board.c
new file mode 100755
index 0000000..482b815
--- /dev/null
+++ b/default/expansion_board.c
@@ -0,0 +1,352 @@
+#include "memory_map.h"
+#include "dynamixel.h"
+#include "timer128.h"
+#include "compass.h"
+#include "uartsw.h"
+#include "avr/io.h"
+#include "ports.h"
+#include "a2d.h"
+#include "i2c.h"
+
+void periodic_calls(void)
+{
+  static short int count=0;
+
+  sei();
+  outb(TCNT0,0x7F);
+  compass_periodic_call();
+  count++;
+  if(count==1000)
+  {
+    if(PINE&0x04)
+	  cbi(PORTE,2);
+    else
+	  sbi(PORTE,2);
+	count=0;
+  }
+}
+
+int main(void)
+{
+  unsigned char data[128],id,length,instruction,answer[2],status;
+  // selected address
+  unsigned char rs485_address;
+  // adc conversion result
+  unsigned short int adc_value;
+  // heading value
+  unsigned short int compass_heading;
+  // serial port variables
+  unsigned char data_available;
+  unsigned char serial_data;
+  // gpio identifier
+  unsigned char gpio_id;
+  // pwm identifier
+  unsigned char pwm_id;
+  // pwm value
+  unsigned short int pwm_value;
+
+  // initialize the IO ports
+  init_ports();
+
+  // initialize the RS485 interface
+  init_RS485();
+  get_RS485_address(&rs485_address);
+
+  // initialize the analog to digital converter
+  a2dInit();
+
+  // initialize the i2c peripheral
+  i2cInit();
+
+  // initialize the compass
+  CompassInit();
+
+  // initialize timer to execute periodic functions
+  timer0Init();
+  // set the period to 1ms
+  timer0SetPrescaler(TIMER_CLK_DIV1024);
+  outb(TCNT0,0x7F);
+  timerAttach(TIMER0OVERFLOW_INT, periodic_calls);
+
+  // initialize the timer 3 to generate RC PWM
+  timer3Init();
+  timer3SetPrescaler(TIMER_CLK_DIV8);
+  timer3PWMInitICR(40000);// set a 50 Hz freq
+
+  // initialize the timer 1 to generate analog signals
+  timer1Init();
+  timer1SetPrescaler(TIMER_CLK_DIV1);
+  timer1PWMInitICR(16000);// set a a kHz freq
+  
+  // initialize the software serial port
+//  uartswInit();
+
+  sei();// turn on interrupts (if not already on)
+
+  while(1)
+  {
+    status=RxRS485Packet(RS485_single_ended,&id,&instruction,&length,data);
+    if(status==CHECK_ERROR)
+      TxRS485Packet(RS485_single_ended,rs485_address,CHECKSUM_ERROR,0,NULL);
+	else if(status==CORRECT)
+	{  
+      if(id==rs485_address)
+      { 
+        switch(instruction)
+        {
+	      case INST_PING: TxRS485Packet(RS485_single_ended,rs485_address,NO_ERROR,0,NULL);
+	   	                  break;
+          case INST_READ: if(data[0]>=0x00 && data[0]<=0x07)
+		                  {
+			                if(length==2)
+						    {
+						       adc_value=adc_get_channel(data[0]);	
+                               TxRS485Packet(RS485_single_ended,rs485_address,NO_ERROR,2,(unsigned char *)&adc_value);
+						    }
+						    else
+						       TxRS485Packet(RS485_single_ended,rs485_address,INSTRUCTION_ERROR,0,NULL);
+					      }
+                          if(data[0]>=0x08 && data[0]<=0x0F)
+		                  {
+			                if(length==2)
+						    {
+						       adc_value=adc_get_averaged_channel(data[0]-8);	
+                               TxRS485Packet(RS485_single_ended,rs485_address,NO_ERROR,2,(unsigned char *)&adc_value);
+						    }
+						    else
+						       TxRS485Packet(RS485_single_ended,rs485_address,INSTRUCTION_ERROR,0,NULL);
+					      }
+						  else if(data[0]==0x10)
+						  {
+			                if(length==2)
+						    {
+						       compass_heading=compass_get_heading();
+							   answer[0]=compass_heading&0xFF;
+							   answer[1]=(compass_heading>>8)&0xFF;
+                               TxRS485Packet(RS485_single_ended,rs485_address,NO_ERROR,2,answer);
+						    }
+						    else
+						       TxRS485Packet(RS485_single_ended,rs485_address,INSTRUCTION_ERROR,0,NULL);
+						  }
+						  else if(data[0]==0x11)
+						  {
+			                if(length==2)
+						    {
+						       compass_heading=compass_get_averaged_heading();
+							   answer[0]=compass_heading&0xFF;
+							   answer[1]=(compass_heading>>8)&0xFF;
+                               TxRS485Packet(RS485_single_ended,rs485_address,NO_ERROR,2,answer);
+						    }
+						    else
+						       TxRS485Packet(RS485_single_ended,rs485_address,INSTRUCTION_ERROR,0,NULL);
+						  }
+						  else if(data[0]==0x12)
+						  {
+						    if(length==2)
+							{
+							   if(!calibrate && !calibrating)
+							     answer[0]=0x00;
+							   else
+							     answer[0]=0x01;
+                               TxRS485Packet(RS485_single_ended,rs485_address,NO_ERROR,1,answer);
+							}
+						    else
+						       TxRS485Packet(RS485_single_ended,rs485_address,INSTRUCTION_ERROR,0,NULL);
+
+						  }
+						  else if(data[0]==0x21)
+						  {
+                            if(length==2)
+							{
+							  data_available=uartswReceiveByte(&serial_data);
+							  answer[0]=data_available;
+							  answer[1]=serial_data;
+                              TxRS485Packet(RS485_single_ended,rs485_address,NO_ERROR,2,answer);
+							}
+						    else
+						       TxRS485Packet(RS485_single_ended,rs485_address,INSTRUCTION_ERROR,0,NULL);
+						  }
+						  else if(data[0]>=0x30 && data[0]<=0x55)
+						  {
+						    if(length==2)
+							{
+						      gpio_id=(data[0]-0x30)>>1;
+							  if((data[0]%2)==0x00)// configuration register
+							    answer[0]=get_port_config(gpio_id);
+							  else// data register
+							  {
+                                answer[0]=read_port(gpio_id);
+								
+                              }
+                              TxRS485Packet(RS485_single_ended,rs485_address,NO_ERROR,1,answer);
+							}
+						    else
+						       TxRS485Packet(RS485_single_ended,rs485_address,INSTRUCTION_ERROR,0,NULL);
+						  }
+                          else if(data[0]==0x61 || data[0]==0x63 || data[0]==0x65 || data[0]==0x67)
+						  {
+						    if(length==2)						   
+							{
+							  pwm_id=(data[0]-0x61)>>1;
+							  answer[0]=0x00;
+							  TxRS485Packet(RS485_single_ended,rs485_address,NO_ERROR,1,answer);
+							}
+							else
+						       TxRS485Packet(RS485_single_ended,rs485_address,INSTRUCTION_ERROR,0,NULL);
+						  }
+						  else
+                            TxRS485Packet(RS485_single_ended,rs485_address,INSTRUCTION_ERROR,0,NULL);
+						  break;
+          case INST_WRITE: if(data[0]==0x12)
+		                   {
+                             if(length==2)
+							 {
+							   if(!calibrate)
+							     calibrate=TRUE;
+                               TxRS485Packet(RS485_single_ended,rs485_address,NO_ERROR,0,NULL);
+							 }						     
+							 else
+    						   TxRS485Packet(RS485_single_ended,rs485_address,INSTRUCTION_ERROR,0,NULL);
+						   }
+		                   else if(data[0]==0x20)
+		                   {
+						     if(length==2)
+							 {
+							   uartswSendByte(data[1]);
+							   TxRS485Packet(RS485_single_ended,rs485_address,NO_ERROR,0,NULL);
+							 }
+							 else
+    						   TxRS485Packet(RS485_single_ended,rs485_address,INSTRUCTION_ERROR,0,NULL);
+						   }
+						   else if(data[0]>=0x30 && data[0]<=0x55)
+						   {
+						     if(length==2)
+							 {
+						       gpio_id=(data[0]-0x30)>>1;
+						       if((data[0]%2)==0x00)// configuration register
+							   {
+							     config_port(gpio_id,data[1]);
+							     answer[0]=DDRA;
+							     TxRS485Packet(RS485_single_ended,rs485_address,NO_ERROR,0,NULL);
+							   }
+							   else// value register
+							   {
+							     if(data[1]==0x00)
+							       clear_port(gpio_id);
+                                 else
+							       set_port(gpio_id);
+							     TxRS485Packet(RS485_single_ended,rs485_address,NO_ERROR,0,NULL);
+							   }
+						     }
+							 else
+							   TxRS485Packet(RS485_single_ended,rs485_address,INSTRUCTION_ERROR,0,NULL);
+						   }
+						   else if(data[0]==0x60 || data[0]==0x62 || data[0]==0x64 || data[0]==0x66)
+						   {
+						     if(length==3)
+							 {
+							   pwm_id=(data[0]-0x60)>>1;
+							   pwm_value=data[1]+data[2]*256;
+							   if(pwm_value>40000) 
+							     pwm_value=40000;
+							   switch(pwm_id)
+							   {
+							      case 0: timer3PWMASet(pwm_value);
+								          break;
+                                  case 1: timer3PWMBSet(pwm_value);
+								          break;
+                                  case 2: timer3PWMCSet(pwm_value);
+								          break;
+                                  case 3: timer1PWMCSet(pwm_value);
+								          break;
+							   }
+							   TxRS485Packet(RS485_single_ended,rs485_address,NO_ERROR,0,NULL);
+							 }
+							 else
+							   TxRS485Packet(RS485_single_ended,rs485_address,INSTRUCTION_ERROR,0,NULL);
+						   }
+						   else if(data[0]==0x61 || data[0]==0x63 || data[0]==0x65 || data[0]==0x67)
+						   {
+						     if(length==2)
+							 {
+							   pwm_id=(data[0]-0x61)>>1;
+							   switch(pwm_id)
+							   {
+							      case 0: if(data[1]==0x00)
+								            timer3PWMAOff();
+                                          else
+										    timer3PWMAOn();
+								          break;
+                                  case 1: if(data[1]==0x00)
+								            timer3PWMBOff();
+                                          else
+										    timer3PWMBOn();
+								          break;
+                                  case 2: if(data[1]==0x00)
+								            timer3PWMCOff();
+                                          else
+										    timer3PWMCOn();
+								          break;
+                                  case 3: if(data[1]==0x00)
+								            timer1PWMCOff();
+                                          else
+										    timer1PWMCOn();
+								          break;
+							   }
+							   TxRS485Packet(RS485_single_ended,rs485_address,NO_ERROR,0,NULL);
+							 }
+							 else
+							   TxRS485Packet(RS485_single_ended,rs485_address,INSTRUCTION_ERROR,0,NULL);
+						   }
+						   else if(data[0]==0x70 || data[0]==0x72)
+						   {
+						     if(length==3)
+							 {
+							   pwm_id=(data[0]-0x70)>>1;
+							   pwm_value=data[1]+data[2]*256;
+							   if(pwm_value>16000) 
+							     pwm_value=16000;
+							   if(pwm_id==0)
+							     timer1PWMASet(pwm_value);
+                               else
+							     timer1PWMBSet(pwm_value);
+							   TxRS485Packet(RS485_single_ended,rs485_address,NO_ERROR,0,NULL);
+							 }
+							 else
+							   TxRS485Packet(RS485_single_ended,rs485_address,INSTRUCTION_ERROR,0,NULL);
+						   }
+						   else if(data[0]==0x71 || data[0]==0x73)
+						   {
+						     if(length==2)
+							 {
+							   pwm_id=(data[0]-0x71)>>1;
+							   if(pwm_id==0)
+							   {
+							     if(data[1]==0x00)
+							       timer1PWMAOff();
+                                 else
+								   timer1PWMAOn();
+                               }
+                               else
+							   {
+							     if(data[1]==0x00)
+							       timer1PWMBOff();
+                                 else
+								   timer1PWMBOn();
+                               }
+							   TxRS485Packet(RS485_single_ended,rs485_address,NO_ERROR,0,NULL);
+							 }
+							 else
+							   TxRS485Packet(RS485_single_ended,rs485_address,INSTRUCTION_ERROR,0,NULL);
+						   }
+                           else
+                             TxRS485Packet(RS485_single_ended,rs485_address,INSTRUCTION_ERROR,0,NULL);
+          case INST_SYNC_WRITE: // do nothing to avoid desynchronization with the controller
+		                        break;
+          default: //TxRS485Packet(RS485_single_ended,rs485_address,INSTRUCTION_ERROR,0,NULL);
+		           break;
+		}
+	  }	 
+    }
+  }
+}
diff --git a/dynamixel.c b/dynamixel.c
new file mode 100755
index 0000000..bd8b85f
--- /dev/null
+++ b/dynamixel.c
@@ -0,0 +1,245 @@
+#include <avr/interrupt.h>
+#include "dynamixel.h"
+#include "timer128.h"
+#include "buffer.h"
+#include <avr/io.h>
+
+// receive buffers
+volatile unsigned char rs485_se_data[RX_BUFFER_SIZE];
+volatile unsigned char rs485_se_read_ptr;
+volatile unsigned char rs485_se_write_ptr;
+volatile unsigned char rs485_se_num;
+volatile unsigned char rs485_diff_data[RX_BUFFER_SIZE];
+volatile unsigned char rs485_diff_read_ptr;
+volatile unsigned char rs485_diff_write_ptr;
+volatile unsigned char rs485_diff_num;
+
+unsigned char RS485_is_tx_ready(unsigned char nUart)
+{
+  if(nUart)
+    return (UCSR1A & (1<<UDRE));
+  else
+    return (UCSR0A & (1<<UDRE));
+}
+
+unsigned char RS485_is_rx_ready(unsigned char nUart)
+{
+  unsigned char status;
+  cli();
+  if(nUart)
+  {
+    if(rs485_se_num==0) status=FALSE;
+    else status=TRUE;
+  }
+  else
+  {
+    if(rs485_diff_num==0) status=FALSE;
+    else status=TRUE;
+  }
+  sei();
+
+  return status;
+}
+
+void RS485_set_tx_done(unsigned char nUart)
+{
+  if(nUart)
+    sbi(UCSR1A,6);
+  else
+    sbi(UCSR0A,6);
+}
+
+unsigned char RS485_is_tx_done(unsigned char nUart)
+{
+  if(nUart)
+    return bit_is_set(UCSR1A,6);
+  else
+    return bit_is_set(UCSR0A,6);
+}
+
+void RS485_send(unsigned char nUart,unsigned char data)
+{
+  RS485_set_tx_done(nUart);
+  while(!RS485_is_tx_ready(nUart));
+  if(nUart)
+	UDR1=data;
+  else
+	UDR0=data;
+}
+
+void RS485_receive(unsigned char nUart,unsigned char *data)
+{
+  while(!RS485_is_rx_ready(nUart));
+  cli();
+  if(nUart)
+  {
+    (*data) = rs485_se_data[rs485_se_read_ptr];
+    rs485_se_read_ptr=(rs485_se_read_ptr+1)%RX_BUFFER_SIZE;
+	rs485_se_num--;
+  }
+  else
+  {
+    (*data) = rs485_diff_data[rs485_diff_read_ptr];
+    rs485_diff_read_ptr=(rs485_diff_read_ptr+1)%RX_BUFFER_SIZE;
+    rs485_diff_num--;
+  }
+  sei();
+}
+
+void init_RS485(void)
+{
+  // configure the IO ports
+  DDRD=DDRD|0xC8;// RX_en, TX_en, TX are outputs
+  DDRD=DDRD&0xFB;// RX is an input
+
+  // configure the address selection bits
+  DDRG=DDRG&0xE7;// they are inputs
+  
+  // configure the ports to receive data
+  SET_RS485_RXD;
+
+  // initialize the rs485 ports
+  UCSR0A = 0;// Single (not double) the USART transmission speed
+  UBRR0H = 0;
+  UBRR0L = 0;// BAUD = 1000000bps at U2X=0, Fosc=16MHz => UBRR=0  
+  outb(UCSR0B, BV(RXCIE)|BV(RXEN)|BV(TXEN));
+  UCSR0C = 0x86; // 8 bit data, no parity (and URSEL must be 1)
+
+  UCSR1A = 0;// Single (not double) the USART transmission speed
+  UBRR1H = 0;
+  UBRR1L = 0;// BAUD = 1000000bps at U2X=0, Fosc=16MHz => UBRR=0  
+  outb(UCSR1B, BV(RXCIE)|BV(RXEN)|BV(TXEN));
+  UCSR1C = 0x86; // 8 bit data, no parity (and URSEL must be 1)
+
+  // initialize receive buffer for both interfaces
+  rs485_se_read_ptr=0;
+  rs485_se_write_ptr=0;
+  rs485_se_num=0;
+
+  rs485_diff_read_ptr=0;
+  rs485_diff_write_ptr=0;
+  rs485_diff_num=0;
+}
+
+void get_RS485_address(unsigned char *address)
+{
+  unsigned char sel;
+
+  sel=(PING&0x18);
+  switch(sel)
+  {
+    case 0x00: (*address)=0x45;
+	           break;
+	case 0x10: (*address)=0x80;
+	           break;
+	case 0x08: (*address)=0xC0;
+	           break;
+	case 0x18: (*address)=0xFD;
+	           break;
+    default: (*address)=0x45;
+	         break;
+  }
+}
+
+void TxRS485Packet(unsigned char nUart,unsigned char id, unsigned char instruction, unsigned char param_len, unsigned char *params)
+{
+  unsigned char checksum=0,i=0;
+
+  SET_RS485_TXD;
+  RS485_send(nUart,0xFF);
+  RS485_send(nUart,0xFF);
+  RS485_send(nUart,id);
+  checksum+=id;
+  RS485_send(nUart,param_len+2);
+  checksum+=param_len+2;
+  RS485_send(nUart,instruction);
+  checksum+=instruction;
+  for(i=0;i<param_len;i++)
+  {
+    RS485_send(nUart,params[i]);
+	checksum+=params[i];
+  }
+  RS485_send(nUart,~checksum);
+  while(!RS485_is_tx_done(nUart));// wait util the data is sent
+  SET_RS485_RXD;
+}
+
+unsigned char RxRS485Packet(unsigned char nUart,unsigned char *id,unsigned char *instruction, unsigned char *param_len, unsigned char *params)
+{
+  static unsigned char checksum=0,read_params=0;
+  static dyn_states state=dyn_header1;
+  unsigned char byte;
+
+  if(RS485_is_rx_ready(nUart))
+  {
+    switch(state)
+	{
+	  case dyn_header1: RS485_receive(nUart,&byte);
+	                    if(byte==0xFF) state=dyn_header2;
+						else state=dyn_header1;
+                        break;
+	  case dyn_header2: RS485_receive(nUart,&byte);
+	                    if(byte==0xFF) 
+						{
+						  state=dyn_id;
+						  checksum=0;
+						}
+						else state=dyn_header1;
+                        break;
+	  case dyn_id: RS485_receive(nUart,id);
+	               checksum+=(*id);
+	               state=dyn_length;
+                   break;
+	  case dyn_length: RS485_receive(nUart,param_len);
+	                   checksum+=(*param_len);
+	                   (*param_len)=(*param_len)-2;
+					   state=dyn_inst;
+                       break;
+	  case dyn_inst: RS485_receive(nUart,instruction);
+	                 checksum+=(*instruction);
+					 if((*param_len)==0) state=dyn_checksum;
+	                 else state=dyn_params;
+					 read_params=0;
+                     break;
+	  case dyn_params: RS485_receive(nUart,&params[read_params]);
+	                   checksum+=params[read_params];
+					   read_params++;
+					   if(read_params==(*param_len))
+					     state=dyn_checksum;
+                       else
+					     state=dyn_params;
+					   break;
+	  case dyn_checksum: RS485_receive(nUart,&byte);
+	                     checksum+=byte;
+						 state=dyn_header1;
+						 //if(checksum==0xFF)
+						   return CORRECT;
+						 //else
+						 //{
+						   //  return CHECK_ERROR;
+                         //}
+						 break;
+    }
+  }
+
+  return INCOMPLETE;
+
+}
+
+UART_INTERRUPT_HANDLER(UART0_RX_vect)      
+{
+  // service UART0 receive interrupt
+  rs485_diff_data[rs485_diff_write_ptr]=inb(UDR0);
+  rs485_diff_write_ptr=(rs485_diff_write_ptr+1)%RX_BUFFER_SIZE;
+  rs485_diff_num++;
+}
+
+UART_INTERRUPT_HANDLER(UART1_RX_vect)      
+{
+  // service UART1 receive interrupt
+  rs485_se_data[rs485_se_write_ptr]=inb(UDR1);
+  rs485_se_write_ptr=(rs485_se_write_ptr+1)%RX_BUFFER_SIZE;
+  rs485_se_num=rs485_se_num+1;
+}
+
+
diff --git a/dynamixel.h b/dynamixel.h
new file mode 100755
index 0000000..c1503e4
--- /dev/null
+++ b/dynamixel.h
@@ -0,0 +1,66 @@
+#ifndef _DYNAMIXEL_H
+#define _DYNAMIXEL_H
+
+#include "global.h"
+#include "utils.h"
+
+//! Type of interrupt handler to use for uart interrupts.
+/// Value may be SIGNAL or INTERRUPT.
+/// \warning Do not change unless you know what you're doing.
+#ifndef UART_INTERRUPT_HANDLER
+#define UART_INTERRUPT_HANDLER	SIGNAL
+#endif
+
+// receive buffers length
+#define RX_BUFFER_SIZE 128
+
+// Instruction identifiers
+#define INST_PING           0x01
+#define INST_READ           0x02
+#define INST_WRITE          0x03
+#define INST_REG_WRITE      0x04
+#define INST_ACTION         0x05
+#define INST_RESET          0x06
+#define INST_DIGITAL_RESET  0x07
+#define INST_SYSTEM_READ    0x0C
+#define INST_SYSTEM_WRITE   0x0D
+#define INST_SYNC_WRITE     0x83
+#define INST_SYNC_REG_WRITE 0x84
+
+// bus errors
+#define INSTRUCTION_ERROR   0x40
+#define OVERLOAD_ERROR      0x20
+#define CHECKSUM_ERROR      0x10
+#define RANGE_ERROR         0x08
+#define OVERHEATING_ERROR   0x04
+#define ANGLE_LIMIT_ERROR   0x02
+#define VOLTAGE_ERROR       0x01
+#define NO_ERROR            0x00
+
+#define RS485_single_ended 1 
+#define RS485_differential 0
+
+// instructions to configure the data direction on the RS485 interface
+#define SET_RS485_TXD PORTD &= ~_BV(PD7),PORTD |= _BV(PD6)
+#define SET_RS485_RXD PORTD &= ~_BV(PD6),PORTD |= _BV(PD7)
+
+// broadcasting address
+#define BROADCASTING_ID 0xFE
+
+// possible packet status
+#define CORRECT 0
+#define INCOMPLETE 1
+#define CHECK_ERROR 2
+
+typedef enum {dyn_header1,dyn_header2,dyn_id,dyn_length,dyn_inst,dyn_params,dyn_checksum} dyn_states;
+
+// function to initialize the RS485 interface
+void init_RS485(void);
+// function to set the rs485 device address
+void get_RS485_address(unsigned char *address);
+// function to send a packet through the RS485 interface
+void TxRS485Packet(unsigned char nUart,unsigned char id, unsigned char instruction, unsigned char param_len, unsigned char *params);
+// function to receive a packet through the RS485 interface using interrupts
+unsigned char RxRS485Packet(unsigned char nUart,unsigned char *id, unsigned char *instruction, unsigned char *param_len, unsigned char *params);
+
+#endif
diff --git a/expansion_board.aps b/expansion_board.aps
new file mode 100755
index 0000000..b5a5f59
--- /dev/null
+++ b/expansion_board.aps
@@ -0,0 +1 @@
+<AVRStudio><MANAGEMENT><ProjectName>expansion_board</ProjectName><Created>21-Jan-2011 15:23:22</Created><LastEdit>18-Jul-2011 12:33:48</LastEdit><ICON>241</ICON><ProjectType>0</ProjectType><Created>21-Jan-2011 15:23:22</Created><Version>4</Version><Build>4, 18, 0, 685</Build><ProjectTypeName>AVR GCC</ProjectTypeName></MANAGEMENT><CODE_CREATION><ObjectFile>default\expansion_board.elf</ObjectFile><EntryFile></EntryFile><SaveFolder>\\VBOXSVR\shared\Software\</SaveFolder></CODE_CREATION><DEBUG_TARGET><CURRENT_TARGET></CURRENT_TARGET><CURRENT_PART></CURRENT_PART><BREAKPOINTS></BREAKPOINTS><IO_EXPAND><HIDE>false</HIDE></IO_EXPAND><REGISTERNAMES><Register>R00</Register><Register>R01</Register><Register>R02</Register><Register>R03</Register><Register>R04</Register><Register>R05</Register><Register>R06</Register><Register>R07</Register><Register>R08</Register><Register>R09</Register><Register>R10</Register><Register>R11</Register><Register>R12</Register><Register>R13</Register><Register>R14</Register><Register>R15</Register><Register>R16</Register><Register>R17</Register><Register>R18</Register><Register>R19</Register><Register>R20</Register><Register>R21</Register><Register>R22</Register><Register>R23</Register><Register>R24</Register><Register>R25</Register><Register>R26</Register><Register>R27</Register><Register>R28</Register><Register>R29</Register><Register>R30</Register><Register>R31</Register></REGISTERNAMES><COM></COM><COMType>0</COMType><WATCHNUM>0</WATCHNUM><WATCHNAMES><Pane0></Pane0><Pane1></Pane1><Pane2></Pane2><Pane3></Pane3></WATCHNAMES><BreakOnTrcaeFull>0</BreakOnTrcaeFull></DEBUG_TARGET><Debugger><Triggers></Triggers></Debugger><AVRGCCPLUGIN><FILES><SOURCEFILE>expansion_board.c</SOURCEFILE><SOURCEFILE>dynamixel.c</SOURCEFILE><SOURCEFILE>timer128.c</SOURCEFILE><SOURCEFILE>compass.c</SOURCEFILE><SOURCEFILE>i2c.c</SOURCEFILE><SOURCEFILE>a2d.c</SOURCEFILE><SOURCEFILE>buffer.c</SOURCEFILE><SOURCEFILE>uartsw.c</SOURCEFILE><SOURCEFILE>ports.c</SOURCEFILE><HEADERFILE>utils.h</HEADERFILE><HEADERFILE>dynamixel.h</HEADERFILE><HEADERFILE>global.h</HEADERFILE><HEADERFILE>timer128.h</HEADERFILE><HEADERFILE>avrlibtypes.h</HEADERFILE><HEADERFILE>avrlibdefs.h</HEADERFILE><HEADERFILE>port128.h</HEADERFILE><HEADERFILE>compass.h</HEADERFILE><HEADERFILE>i2c.h</HEADERFILE><HEADERFILE>i2cconf.h</HEADERFILE><HEADERFILE>memory_map.h</HEADERFILE><HEADERFILE>a2d.h</HEADERFILE><HEADERFILE>buffer.h</HEADERFILE><HEADERFILE>uartsw.h</HEADERFILE><HEADERFILE>uartswconf.h</HEADERFILE><HEADERFILE>ports.h</HEADERFILE><OTHERFILE>default\expansion_board.lss</OTHERFILE><OTHERFILE>default\expansion_board.map</OTHERFILE></FILES><CONFIGS><CONFIG><NAME>default</NAME><USESEXTERNALMAKEFILE>NO</USESEXTERNALMAKEFILE><EXTERNALMAKEFILE></EXTERNALMAKEFILE><PART>atmega128</PART><HEX>1</HEX><LIST>1</LIST><MAP>1</MAP><OUTPUTFILENAME>expansion_board.elf</OUTPUTFILENAME><OUTPUTDIR>default\</OUTPUTDIR><ISDIRTY>1</ISDIRTY><OPTIONS><OPTION><FILE>buffer.c</FILE><OPTIONLIST></OPTIONLIST></OPTION><OPTION><FILE>dynamixel.c</FILE><OPTIONLIST></OPTIONLIST></OPTION><OPTION><FILE>expansion_board.c</FILE><OPTIONLIST></OPTIONLIST></OPTION><OPTION><FILE>timer128.c</FILE><OPTIONLIST></OPTIONLIST></OPTION><OPTION><FILE>uart2.c</FILE><OPTIONLIST></OPTIONLIST></OPTION></OPTIONS><INCDIRS/><LIBDIRS/><LIBS/><LINKOBJECTS/><OPTIONSFORALL>-Wall -gdwarf-2 -std=gnu99   -Os -funsigned-char -funsigned-bitfields -fpack-struct -fshort-enums</OPTIONSFORALL><LINKEROPTIONS></LINKEROPTIONS><SEGMENTS/></CONFIG></CONFIGS><LASTCONFIG>default</LASTCONFIG><USES_WINAVR>1</USES_WINAVR><GCC_LOC>C:\WinAVR-20100110\bin\avr-gcc.exe</GCC_LOC><MAKE_LOC>C:\WinAVR-20100110\utils\bin\make.exe</MAKE_LOC></AVRGCCPLUGIN><ProjectFiles><Files><Name>\\VBOXSVR\shared\Software\utils.h</Name><Name>\\VBOXSVR\shared\Software\dynamixel.h</Name><Name>\\VBOXSVR\shared\Software\global.h</Name><Name>\\VBOXSVR\shared\Software\timer128.h</Name><Name>\\VBOXSVR\shared\Software\avrlibtypes.h</Name><Name>\\VBOXSVR\shared\Software\avrlibdefs.h</Name><Name>\\VBOXSVR\shared\Software\port128.h</Name><Name>\\VBOXSVR\shared\Software\compass.h</Name><Name>\\VBOXSVR\shared\Software\i2c.h</Name><Name>\\VBOXSVR\shared\Software\i2cconf.h</Name><Name>\\VBOXSVR\shared\Software\memory_map.h</Name><Name>\\VBOXSVR\shared\Software\a2d.h</Name><Name>\\VBOXSVR\shared\Software\buffer.h</Name><Name>\\VBOXSVR\shared\Software\uartsw.h</Name><Name>\\VBOXSVR\shared\Software\uartswconf.h</Name><Name>\\VBOXSVR\shared\Software\ports.h</Name><Name>\\VBOXSVR\shared\Software\expansion_board.c</Name><Name>\\VBOXSVR\shared\Software\dynamixel.c</Name><Name>\\VBOXSVR\shared\Software\timer128.c</Name><Name>\\VBOXSVR\shared\Software\compass.c</Name><Name>\\VBOXSVR\shared\Software\i2c.c</Name><Name>\\VBOXSVR\shared\Software\a2d.c</Name><Name>\\VBOXSVR\shared\Software\buffer.c</Name><Name>\\VBOXSVR\shared\Software\uartsw.c</Name><Name>\\VBOXSVR\shared\Software\ports.c</Name></Files></ProjectFiles><IOView><usergroups/><sort sorted="0" column="0" ordername="0" orderaddress="0" ordergroup="0"/></IOView><Files><File00000><FileId>00000</FileId><FileName>expansion_board.c</FileName><Status>1</Status></File00000><File00001><FileId>00001</FileId><FileName>uartsw.h</FileName><Status>1</Status></File00001><File00002><FileId>00002</FileId><FileName>uartsw.c</FileName><Status>1</Status></File00002><File00003><FileId>00003</FileId><FileName>uartswconf.h</FileName><Status>1</Status></File00003><File00004><FileId>00004</FileId><FileName>buffer.h</FileName><Status>1</Status></File00004><File00005><FileId>00005</FileId><FileName>compass.c</FileName><Status>1</Status></File00005><File00006><FileId>00006</FileId><FileName>dynamixel.c</FileName><Status>1</Status></File00006><File00007><FileId>00007</FileId><FileName>dynamixel.h</FileName><Status>1</Status></File00007><File00008><FileId>00008</FileId><FileName>ports.h</FileName><Status>1</Status></File00008><File00009><FileId>00009</FileId><FileName>ports.c</FileName><Status>1</Status></File00009><File00010><FileId>00010</FileId><FileName>port128.h</FileName><Status>1</Status></File00010><File00011><FileId>00011</FileId><FileName>i2c.c</FileName><Status>1</Status></File00011><File00012><FileId>00012</FileId><FileName>compass.h</FileName><Status>1</Status></File00012><File00013><FileId>00013</FileId><FileName>buffer.c</FileName><Status>1</Status></File00013><File00014><FileId>00014</FileId><FileName>a2d.c</FileName><Status>1</Status></File00014></Files><Events><Bookmarks></Bookmarks></Events><Trace><Filters></Filters></Trace></AVRStudio>
diff --git a/expansion_board.aws b/expansion_board.aws
new file mode 100755
index 0000000..351856d
--- /dev/null
+++ b/expansion_board.aws
@@ -0,0 +1 @@
+<AVRWorkspace><IOSettings><CurrentRegisters/></IOSettings><part name=""/><Files><File00000 Name="\\Vboxsvr\shared\Software\expansion_board.c" Position="201 89 894 404" LineCol="146 14" State="Maximized"/><File00001 Name="\\Vboxsvr\shared\Software\uartsw.h" Position="223 116 908 401" LineCol="0 0" State="Maximized"/><File00002 Name="\\Vboxsvr\shared\Software\uartsw.c" Position="245 138 930 423" LineCol="49 0" State="Maximized"/><File00003 Name="\\Vboxsvr\shared\Software\uartswconf.h" Position="267 160 952 445" LineCol="40 0" State="Maximized"/><File00004 Name="\\Vboxsvr\shared\Software\buffer.h" Position="289 182 974 467" LineCol="0 0" State="Maximized"/><File00005 Name="\\Vboxsvr\shared\Software\compass.c" Position="311 204 996 489" LineCol="19 0" State="Maximized"/><File00006 Name="\\Vboxsvr\shared\Software\dynamixel.c" Position="333 226 1018 511" LineCol="226 0" State="Maximized"/><File00007 Name="\\Vboxsvr\shared\Software\dynamixel.h" Position="201 94 886 379" LineCol="26 0" State="Maximized"/><File00008 Name="\\Vboxsvr\shared\Software\ports.h" Position="223 116 908 401" LineCol="21 0" State="Maximized"/><File00009 Name="\\Vboxsvr\shared\Software\ports.c" Position="245 138 930 423" LineCol="22 0" State="Maximized"/><File00010 Name="\\Vboxsvr\shared\Software\port128.h" Position="267 160 952 445" LineCol="0 0" State="Maximized"/><File00011 Name="\\Vboxsvr\shared\Software\i2c.c" Position="289 182 974 467" LineCol="0 0" State="Maximized"/><File00012 Name="\\Vboxsvr\shared\Software\compass.h" Position="311 204 996 489" LineCol="12 35" State="Maximized"/><File00013 Name="\\Vboxsvr\shared\Software\buffer.c" Position="333 226 1018 511" LineCol="0 0" State="Maximized"/><File00014 Name="\\Vboxsvr\shared\Software\a2d.c" Position="201 94 886 379" LineCol="0 0" State="Maximized"/><File00015 Name="\\Vboxsvr\shared\Software\memory_map.h" Position="197 71 1026 519" LineCol="0 0" State="Maximized"/></Files></AVRWorkspace>
diff --git a/expansion_board.c b/expansion_board.c
new file mode 100755
index 0000000..482b815
--- /dev/null
+++ b/expansion_board.c
@@ -0,0 +1,352 @@
+#include "memory_map.h"
+#include "dynamixel.h"
+#include "timer128.h"
+#include "compass.h"
+#include "uartsw.h"
+#include "avr/io.h"
+#include "ports.h"
+#include "a2d.h"
+#include "i2c.h"
+
+void periodic_calls(void)
+{
+  static short int count=0;
+
+  sei();
+  outb(TCNT0,0x7F);
+  compass_periodic_call();
+  count++;
+  if(count==1000)
+  {
+    if(PINE&0x04)
+	  cbi(PORTE,2);
+    else
+	  sbi(PORTE,2);
+	count=0;
+  }
+}
+
+int main(void)
+{
+  unsigned char data[128],id,length,instruction,answer[2],status;
+  // selected address
+  unsigned char rs485_address;
+  // adc conversion result
+  unsigned short int adc_value;
+  // heading value
+  unsigned short int compass_heading;
+  // serial port variables
+  unsigned char data_available;
+  unsigned char serial_data;
+  // gpio identifier
+  unsigned char gpio_id;
+  // pwm identifier
+  unsigned char pwm_id;
+  // pwm value
+  unsigned short int pwm_value;
+
+  // initialize the IO ports
+  init_ports();
+
+  // initialize the RS485 interface
+  init_RS485();
+  get_RS485_address(&rs485_address);
+
+  // initialize the analog to digital converter
+  a2dInit();
+
+  // initialize the i2c peripheral
+  i2cInit();
+
+  // initialize the compass
+  CompassInit();
+
+  // initialize timer to execute periodic functions
+  timer0Init();
+  // set the period to 1ms
+  timer0SetPrescaler(TIMER_CLK_DIV1024);
+  outb(TCNT0,0x7F);
+  timerAttach(TIMER0OVERFLOW_INT, periodic_calls);
+
+  // initialize the timer 3 to generate RC PWM
+  timer3Init();
+  timer3SetPrescaler(TIMER_CLK_DIV8);
+  timer3PWMInitICR(40000);// set a 50 Hz freq
+
+  // initialize the timer 1 to generate analog signals
+  timer1Init();
+  timer1SetPrescaler(TIMER_CLK_DIV1);
+  timer1PWMInitICR(16000);// set a a kHz freq
+  
+  // initialize the software serial port
+//  uartswInit();
+
+  sei();// turn on interrupts (if not already on)
+
+  while(1)
+  {
+    status=RxRS485Packet(RS485_single_ended,&id,&instruction,&length,data);
+    if(status==CHECK_ERROR)
+      TxRS485Packet(RS485_single_ended,rs485_address,CHECKSUM_ERROR,0,NULL);
+	else if(status==CORRECT)
+	{  
+      if(id==rs485_address)
+      { 
+        switch(instruction)
+        {
+	      case INST_PING: TxRS485Packet(RS485_single_ended,rs485_address,NO_ERROR,0,NULL);
+	   	                  break;
+          case INST_READ: if(data[0]>=0x00 && data[0]<=0x07)
+		                  {
+			                if(length==2)
+						    {
+						       adc_value=adc_get_channel(data[0]);	
+                               TxRS485Packet(RS485_single_ended,rs485_address,NO_ERROR,2,(unsigned char *)&adc_value);
+						    }
+						    else
+						       TxRS485Packet(RS485_single_ended,rs485_address,INSTRUCTION_ERROR,0,NULL);
+					      }
+                          if(data[0]>=0x08 && data[0]<=0x0F)
+		                  {
+			                if(length==2)
+						    {
+						       adc_value=adc_get_averaged_channel(data[0]-8);	
+                               TxRS485Packet(RS485_single_ended,rs485_address,NO_ERROR,2,(unsigned char *)&adc_value);
+						    }
+						    else
+						       TxRS485Packet(RS485_single_ended,rs485_address,INSTRUCTION_ERROR,0,NULL);
+					      }
+						  else if(data[0]==0x10)
+						  {
+			                if(length==2)
+						    {
+						       compass_heading=compass_get_heading();
+							   answer[0]=compass_heading&0xFF;
+							   answer[1]=(compass_heading>>8)&0xFF;
+                               TxRS485Packet(RS485_single_ended,rs485_address,NO_ERROR,2,answer);
+						    }
+						    else
+						       TxRS485Packet(RS485_single_ended,rs485_address,INSTRUCTION_ERROR,0,NULL);
+						  }
+						  else if(data[0]==0x11)
+						  {
+			                if(length==2)
+						    {
+						       compass_heading=compass_get_averaged_heading();
+							   answer[0]=compass_heading&0xFF;
+							   answer[1]=(compass_heading>>8)&0xFF;
+                               TxRS485Packet(RS485_single_ended,rs485_address,NO_ERROR,2,answer);
+						    }
+						    else
+						       TxRS485Packet(RS485_single_ended,rs485_address,INSTRUCTION_ERROR,0,NULL);
+						  }
+						  else if(data[0]==0x12)
+						  {
+						    if(length==2)
+							{
+							   if(!calibrate && !calibrating)
+							     answer[0]=0x00;
+							   else
+							     answer[0]=0x01;
+                               TxRS485Packet(RS485_single_ended,rs485_address,NO_ERROR,1,answer);
+							}
+						    else
+						       TxRS485Packet(RS485_single_ended,rs485_address,INSTRUCTION_ERROR,0,NULL);
+
+						  }
+						  else if(data[0]==0x21)
+						  {
+                            if(length==2)
+							{
+							  data_available=uartswReceiveByte(&serial_data);
+							  answer[0]=data_available;
+							  answer[1]=serial_data;
+                              TxRS485Packet(RS485_single_ended,rs485_address,NO_ERROR,2,answer);
+							}
+						    else
+						       TxRS485Packet(RS485_single_ended,rs485_address,INSTRUCTION_ERROR,0,NULL);
+						  }
+						  else if(data[0]>=0x30 && data[0]<=0x55)
+						  {
+						    if(length==2)
+							{
+						      gpio_id=(data[0]-0x30)>>1;
+							  if((data[0]%2)==0x00)// configuration register
+							    answer[0]=get_port_config(gpio_id);
+							  else// data register
+							  {
+                                answer[0]=read_port(gpio_id);
+								
+                              }
+                              TxRS485Packet(RS485_single_ended,rs485_address,NO_ERROR,1,answer);
+							}
+						    else
+						       TxRS485Packet(RS485_single_ended,rs485_address,INSTRUCTION_ERROR,0,NULL);
+						  }
+                          else if(data[0]==0x61 || data[0]==0x63 || data[0]==0x65 || data[0]==0x67)
+						  {
+						    if(length==2)						   
+							{
+							  pwm_id=(data[0]-0x61)>>1;
+							  answer[0]=0x00;
+							  TxRS485Packet(RS485_single_ended,rs485_address,NO_ERROR,1,answer);
+							}
+							else
+						       TxRS485Packet(RS485_single_ended,rs485_address,INSTRUCTION_ERROR,0,NULL);
+						  }
+						  else
+                            TxRS485Packet(RS485_single_ended,rs485_address,INSTRUCTION_ERROR,0,NULL);
+						  break;
+          case INST_WRITE: if(data[0]==0x12)
+		                   {
+                             if(length==2)
+							 {
+							   if(!calibrate)
+							     calibrate=TRUE;
+                               TxRS485Packet(RS485_single_ended,rs485_address,NO_ERROR,0,NULL);
+							 }						     
+							 else
+    						   TxRS485Packet(RS485_single_ended,rs485_address,INSTRUCTION_ERROR,0,NULL);
+						   }
+		                   else if(data[0]==0x20)
+		                   {
+						     if(length==2)
+							 {
+							   uartswSendByte(data[1]);
+							   TxRS485Packet(RS485_single_ended,rs485_address,NO_ERROR,0,NULL);
+							 }
+							 else
+    						   TxRS485Packet(RS485_single_ended,rs485_address,INSTRUCTION_ERROR,0,NULL);
+						   }
+						   else if(data[0]>=0x30 && data[0]<=0x55)
+						   {
+						     if(length==2)
+							 {
+						       gpio_id=(data[0]-0x30)>>1;
+						       if((data[0]%2)==0x00)// configuration register
+							   {
+							     config_port(gpio_id,data[1]);
+							     answer[0]=DDRA;
+							     TxRS485Packet(RS485_single_ended,rs485_address,NO_ERROR,0,NULL);
+							   }
+							   else// value register
+							   {
+							     if(data[1]==0x00)
+							       clear_port(gpio_id);
+                                 else
+							       set_port(gpio_id);
+							     TxRS485Packet(RS485_single_ended,rs485_address,NO_ERROR,0,NULL);
+							   }
+						     }
+							 else
+							   TxRS485Packet(RS485_single_ended,rs485_address,INSTRUCTION_ERROR,0,NULL);
+						   }
+						   else if(data[0]==0x60 || data[0]==0x62 || data[0]==0x64 || data[0]==0x66)
+						   {
+						     if(length==3)
+							 {
+							   pwm_id=(data[0]-0x60)>>1;
+							   pwm_value=data[1]+data[2]*256;
+							   if(pwm_value>40000) 
+							     pwm_value=40000;
+							   switch(pwm_id)
+							   {
+							      case 0: timer3PWMASet(pwm_value);
+								          break;
+                                  case 1: timer3PWMBSet(pwm_value);
+								          break;
+                                  case 2: timer3PWMCSet(pwm_value);
+								          break;
+                                  case 3: timer1PWMCSet(pwm_value);
+								          break;
+							   }
+							   TxRS485Packet(RS485_single_ended,rs485_address,NO_ERROR,0,NULL);
+							 }
+							 else
+							   TxRS485Packet(RS485_single_ended,rs485_address,INSTRUCTION_ERROR,0,NULL);
+						   }
+						   else if(data[0]==0x61 || data[0]==0x63 || data[0]==0x65 || data[0]==0x67)
+						   {
+						     if(length==2)
+							 {
+							   pwm_id=(data[0]-0x61)>>1;
+							   switch(pwm_id)
+							   {
+							      case 0: if(data[1]==0x00)
+								            timer3PWMAOff();
+                                          else
+										    timer3PWMAOn();
+								          break;
+                                  case 1: if(data[1]==0x00)
+								            timer3PWMBOff();
+                                          else
+										    timer3PWMBOn();
+								          break;
+                                  case 2: if(data[1]==0x00)
+								            timer3PWMCOff();
+                                          else
+										    timer3PWMCOn();
+								          break;
+                                  case 3: if(data[1]==0x00)
+								            timer1PWMCOff();
+                                          else
+										    timer1PWMCOn();
+								          break;
+							   }
+							   TxRS485Packet(RS485_single_ended,rs485_address,NO_ERROR,0,NULL);
+							 }
+							 else
+							   TxRS485Packet(RS485_single_ended,rs485_address,INSTRUCTION_ERROR,0,NULL);
+						   }
+						   else if(data[0]==0x70 || data[0]==0x72)
+						   {
+						     if(length==3)
+							 {
+							   pwm_id=(data[0]-0x70)>>1;
+							   pwm_value=data[1]+data[2]*256;
+							   if(pwm_value>16000) 
+							     pwm_value=16000;
+							   if(pwm_id==0)
+							     timer1PWMASet(pwm_value);
+                               else
+							     timer1PWMBSet(pwm_value);
+							   TxRS485Packet(RS485_single_ended,rs485_address,NO_ERROR,0,NULL);
+							 }
+							 else
+							   TxRS485Packet(RS485_single_ended,rs485_address,INSTRUCTION_ERROR,0,NULL);
+						   }
+						   else if(data[0]==0x71 || data[0]==0x73)
+						   {
+						     if(length==2)
+							 {
+							   pwm_id=(data[0]-0x71)>>1;
+							   if(pwm_id==0)
+							   {
+							     if(data[1]==0x00)
+							       timer1PWMAOff();
+                                 else
+								   timer1PWMAOn();
+                               }
+                               else
+							   {
+							     if(data[1]==0x00)
+							       timer1PWMBOff();
+                                 else
+								   timer1PWMBOn();
+                               }
+							   TxRS485Packet(RS485_single_ended,rs485_address,NO_ERROR,0,NULL);
+							 }
+							 else
+							   TxRS485Packet(RS485_single_ended,rs485_address,INSTRUCTION_ERROR,0,NULL);
+						   }
+                           else
+                             TxRS485Packet(RS485_single_ended,rs485_address,INSTRUCTION_ERROR,0,NULL);
+          case INST_SYNC_WRITE: // do nothing to avoid desynchronization with the controller
+		                        break;
+          default: //TxRS485Packet(RS485_single_ended,rs485_address,INSTRUCTION_ERROR,0,NULL);
+		           break;
+		}
+	  }	 
+    }
+  }
+}
diff --git a/global.h b/global.h
new file mode 100755
index 0000000..075dfe6
--- /dev/null
+++ b/global.h
@@ -0,0 +1,40 @@
+/*! \file global.h \brief AVRlib project global include. */
+//*****************************************************************************
+//
+// File Name	: 'global.h'
+// Title		: AVRlib project global include 
+// Author		: Pascal Stang - Copyright (C) 2001-2002
+// Created		: 7/12/2001
+// Revised		: 9/30/2002
+// Version		: 1.1
+// Target MCU	: Atmel AVR series
+// Editor Tabs	: 4
+//
+//	Description : This include file is designed to contain items useful to all
+//					code files and projects.
+//
+// This code is distributed under the GNU Public License
+//		which can be found at http://www.gnu.org/licenses/gpl.txt
+//
+//*****************************************************************************
+
+#ifndef GLOBAL_H
+#define GLOBAL_H
+
+// global AVRLIB defines
+#include "avrlibdefs.h"
+// global AVRLIB types definitions
+#include "avrlibtypes.h"
+
+// project/system dependent defines
+
+// CPU clock speed
+#define F_CPU        16000000               		// 16MHz processor
+//#define F_CPU        14745000               		// 14.745MHz processor
+//#define F_CPU        8000000               		// 8MHz processor
+//#define F_CPU        7372800               		// 7.37MHz processor
+//#define F_CPU        4000000               		// 4MHz processor
+//#define F_CPU        3686400               		// 3.69MHz processor
+#define CYCLES_PER_US ((F_CPU+500000)/1000000) 	// cpu cycles per microsecond
+
+#endif
diff --git a/i2c.c b/i2c.c
new file mode 100755
index 0000000..1ca4b20
--- /dev/null
+++ b/i2c.c
@@ -0,0 +1,606 @@
+/*! \file i2c.c \brief I2C interface using AVR Two-Wire Interface (TWI) hardware. */
+//*****************************************************************************
+//
+// File Name	: 'i2c.c'
+// Title		: I2C interface using AVR Two-Wire Interface (TWI) hardware
+// Author		: Pascal Stang - Copyright (C) 2002-2003
+// Created		: 2002.06.25
+// Revised		: 2003.03.02
+// Version		: 0.9
+// Target MCU	: Atmel AVR series
+// Editor Tabs	: 4
+//
+// This code is distributed under the GNU Public License
+//		which can be found at http://www.gnu.org/licenses/gpl.txt
+//
+//*****************************************************************************
+
+#include <avr/io.h>
+#include <avr/interrupt.h>
+
+#include "i2c.h"
+
+// Standard I2C bit rates are:
+// 100KHz for slow speed
+// 400KHz for high speed
+
+//#define I2C_DEBUG
+
+// I2C state and address variables
+static volatile eI2cStateType I2cState;
+static u08 I2cDeviceAddrRW;
+// send/transmit buffer (outgoing data)
+static u08 I2cSendData[I2C_SEND_DATA_BUFFER_SIZE];
+static u08 I2cSendDataIndex;
+static u08 I2cSendDataLength;
+// receive buffer (incoming data)
+static u08 I2cReceiveData[I2C_RECEIVE_DATA_BUFFER_SIZE];
+static u08 I2cReceiveDataIndex;
+static u08 I2cReceiveDataLength;
+
+// function pointer to i2c receive routine
+//! I2cSlaveReceive is called when this processor
+// is addressed as a slave for writing
+static void (*i2cSlaveReceive)(u08 receiveDataLength, u08* recieveData);
+//! I2cSlaveTransmit is called when this processor
+// is addressed as a slave for reading
+static u08 (*i2cSlaveTransmit)(u08 transmitDataLengthMax, u08* transmitData);
+
+// functions
+void i2cInit(void)
+{
+	// set pull-up resistors on I2C bus pins
+	// TODO: should #ifdef these
+//	sbi(PORTC, 5);	// i2c SCL on ATmega163,323,16,32,etc
+//	sbi(PORTC, 4);	// i2c SDA on ATmega163,323,16,32,etc
+//	sbi(PORTD, 0);	// i2c SCL on ATmega128,64
+//	sbi(PORTD, 1);	// i2c SDA on ATmega128,64
+
+	// clear SlaveReceive and SlaveTransmit handler to null
+	i2cSlaveReceive = 0;
+	i2cSlaveTransmit = 0;
+	// set i2c bit rate to 100KHz
+	i2cSetBitrate(100);
+	// enable TWI (two-wire interface)
+	sbi(TWCR, TWEN);
+	// set state
+	I2cState = I2C_IDLE;
+	// enable TWI interrupt and slave address ACK
+	sbi(TWCR, TWIE);
+	sbi(TWCR, TWEA);
+	//outb(TWCR, (inb(TWCR)&TWCR_CMD_MASK)|BV(TWINT)|BV(TWEA));
+}
+
+void i2cSetBitrate(u16 bitrateKHz)
+{
+	u08 bitrate_div;
+	// set i2c bitrate
+	// SCL freq = F_CPU/(16+2*TWBR))
+	#ifdef TWPS0
+		// for processors with additional bitrate division (mega128)
+		// SCL freq = F_CPU/(16+2*TWBR*4^TWPS)
+		// set TWPS to zero
+		cbi(TWSR, TWPS0);
+		cbi(TWSR, TWPS1);
+	#endif
+	// calculate bitrate division	
+	bitrate_div = ((F_CPU/1000l)/bitrateKHz);
+	if(bitrate_div >= 16)
+		bitrate_div = (bitrate_div-16)/2;
+	outb(TWBR, bitrate_div);
+}
+
+void i2cSetLocalDeviceAddr(u08 deviceAddr, u08 genCallEn)
+{
+	// set local device address (used in slave mode only)
+	outb(TWAR, ((deviceAddr&0xFE) | (genCallEn?1:0)) );
+}
+
+void i2cSetSlaveReceiveHandler(void (*i2cSlaveRx_func)(u08 receiveDataLength, u08* recieveData))
+{
+	i2cSlaveReceive = i2cSlaveRx_func;
+}
+
+void i2cSetSlaveTransmitHandler(u08 (*i2cSlaveTx_func)(u08 transmitDataLengthMax, u08* transmitData))
+{
+	i2cSlaveTransmit = i2cSlaveTx_func;
+}
+
+inline void i2cSendStart(void)
+{
+	// send start condition
+	outb(TWCR, (inb(TWCR)&TWCR_CMD_MASK)|BV(TWINT)|BV(TWSTA));
+}
+
+inline void i2cSendStop(void)
+{
+	// transmit stop condition
+	// leave with TWEA on for slave receiving
+	outb(TWCR, (inb(TWCR)&TWCR_CMD_MASK)|BV(TWINT)|BV(TWEA)|BV(TWSTO));
+}
+
+inline void i2cWaitForComplete(void)
+{
+	// wait for i2c interface to complete operation
+	while( !(inb(TWCR) & BV(TWINT)) );
+}
+
+inline void i2cSendByte(u08 data)
+{
+	// save data to the TWDR
+	outb(TWDR, data);
+	// begin send
+	outb(TWCR, (inb(TWCR)&TWCR_CMD_MASK)|BV(TWINT));
+}
+
+inline void i2cReceiveByte(u08 ackFlag)
+{
+	// begin receive over i2c
+	if( ackFlag )
+	{
+		// ackFlag = TRUE: ACK the recevied data
+		outb(TWCR, (inb(TWCR)&TWCR_CMD_MASK)|BV(TWINT)|BV(TWEA));
+	}
+	else
+	{
+		// ackFlag = FALSE: NACK the recevied data
+		outb(TWCR, (inb(TWCR)&TWCR_CMD_MASK)|BV(TWINT));
+	}
+}
+
+inline u08 i2cGetReceivedByte(void)
+{
+	// retieve received data byte from i2c TWDR
+	return( inb(TWDR) );
+}
+
+inline u08 i2cGetStatus(void)
+{
+	// retieve current i2c status from i2c TWSR
+	return( inb(TWSR) );
+}
+
+void i2cMasterSend(u08 deviceAddr, u08 length, u08* data)
+{
+	u08 i;
+	// wait for interface to be ready
+	while(I2cState);
+	// set state
+	I2cState = I2C_MASTER_TX;
+	// save data
+	I2cDeviceAddrRW = (deviceAddr & 0xFE);	// RW cleared: write operation
+	for(i=0; i<length; i++)
+		I2cSendData[i] = *data++;
+	I2cSendDataIndex = 0;
+	I2cSendDataLength = length;
+	// send start condition
+	i2cSendStart();
+}
+
+void i2cMasterReceive(u08 deviceAddr, u08 length)//, u08* data)
+{
+//	u08 i;
+	// wait for interface to be ready
+	while(I2cState);
+	// set state
+	I2cState = I2C_MASTER_RX;
+	// save data
+	I2cDeviceAddrRW = (deviceAddr|0x01);	// RW set: read operation
+	I2cReceiveDataIndex = 0;
+	I2cReceiveDataLength = length;
+	// send start condition
+	i2cSendStart();
+	// wait for data
+//	while(I2cState);
+	// return data
+//	for(i=0; i<length; i++)
+//		*data++ = I2cReceiveData[i];
+}
+
+u08 i2cMasterSendNI(u08 deviceAddr, u08 length, u08* data)
+{
+	u08 retval = I2C_OK;
+
+	// disable TWI interrupt
+	cbi(TWCR, TWIE);
+
+	// send start condition
+	i2cSendStart();
+	i2cWaitForComplete();
+
+	// send device address with write
+	i2cSendByte( deviceAddr & 0xFE );
+	i2cWaitForComplete();
+
+	// check if device is present and live
+	if( inb(TWSR) == TW_MT_SLA_ACK)
+	{
+		// send data
+		while(length)
+		{
+			i2cSendByte( *data++ );
+			i2cWaitForComplete();
+			length--;
+		}
+	}
+	else
+	{
+		// device did not ACK it's address,
+		// data will not be transferred
+		// return error
+		retval = I2C_ERROR_NODEV;
+	}
+
+	// transmit stop condition
+	// leave with TWEA on for slave receiving
+	i2cSendStop();
+	while( !(inb(TWCR) & BV(TWSTO)) );
+
+	// enable TWI interrupt
+	sbi(TWCR, TWIE);
+
+	return retval;
+}
+
+u08 i2cMasterReceiveNI(u08 deviceAddr, u08 length, u08 *data)
+{
+	u08 retval = I2C_OK;
+
+	// disable TWI interrupt
+	cbi(TWCR, TWIE);
+
+	// send start condition
+	i2cSendStart();
+	i2cWaitForComplete();
+
+	// send device address with read
+	i2cSendByte( deviceAddr | 0x01 );
+	i2cWaitForComplete();
+
+	// check if device is present and live
+	if( inb(TWSR) == TW_MR_SLA_ACK)
+	{
+		// accept receive data and ack it
+		while(length > 1)
+		{
+			i2cReceiveByte(TRUE);
+			i2cWaitForComplete();
+			*data++ = i2cGetReceivedByte();
+			// decrement length
+			length--;
+		}
+
+		// accept receive data and nack it (last-byte signal)
+		i2cReceiveByte(FALSE);
+		i2cWaitForComplete();
+		*data++ = i2cGetReceivedByte();
+	}
+	else
+	{
+		// device did not ACK it's address,
+		// data will not be transferred
+		// return error
+		retval = I2C_ERROR_NODEV;
+	}
+
+	// transmit stop condition
+	// leave with TWEA on for slave receiving
+	i2cSendStop();
+
+	// enable TWI interrupt
+	sbi(TWCR, TWIE);
+
+	return retval;
+}
+/*
+void i2cMasterTransferNI(u08 deviceAddr, u08 sendlength, u08* senddata, u08 receivelength, u08* receivedata)
+{
+	// disable TWI interrupt
+	cbi(TWCR, TWIE);
+
+	// send start condition
+	i2cSendStart();
+	i2cWaitForComplete();
+
+	// if there's data to be sent, do it
+	if(sendlength)
+	{
+		// send device address with write
+		i2cSendByte( deviceAddr & 0xFE );
+		i2cWaitForComplete();
+		
+		// send data
+		while(sendlength)
+		{
+			i2cSendByte( *senddata++ );
+			i2cWaitForComplete();
+			sendlength--;
+		}
+	}
+
+	// if there's data to be received, do it
+	if(receivelength)
+	{
+		// send repeated start condition
+		i2cSendStart();
+		i2cWaitForComplete();
+
+		// send device address with read
+		i2cSendByte( deviceAddr | 0x01 );
+		i2cWaitForComplete();
+
+		// accept receive data and ack it
+		while(receivelength > 1)
+		{
+			i2cReceiveByte(TRUE);
+			i2cWaitForComplete();
+			*receivedata++ = i2cGetReceivedByte();
+			// decrement length
+			receivelength--;
+		}
+
+		// accept receive data and nack it (last-byte signal)
+		i2cReceiveByte(TRUE);
+		i2cWaitForComplete();
+		*receivedata++ = i2cGetReceivedByte();
+	}
+	
+	// transmit stop condition
+	// leave with TWEA on for slave receiving
+	i2cSendStop();
+	while( !(inb(TWCR) & BV(TWSTO)) );
+
+	// enable TWI interrupt
+	sbi(TWCR, TWIE);
+}
+*/
+
+//! I2C (TWI) interrupt service routine
+SIGNAL(TWI_vect)
+{
+	// read status bits
+	u08 status = inb(TWSR) & TWSR_STATUS_MASK;
+
+	switch(status)
+	{
+	// Master General
+	case TW_START:						// 0x08: Sent start condition
+	case TW_REP_START:					// 0x10: Sent repeated start condition
+		#ifdef I2C_DEBUG
+		rprintfInit(uart1AddToTxBuffer);
+		rprintf("I2C: M->START\r\n");
+		rprintfInit(uart1SendByte);
+		#endif
+		// send device address
+		i2cSendByte(I2cDeviceAddrRW);
+		break;
+	
+	// Master Transmitter & Receiver status codes
+	case TW_MT_SLA_ACK:					// 0x18: Slave address acknowledged
+	case TW_MT_DATA_ACK:				// 0x28: Data acknowledged
+		#ifdef I2C_DEBUG
+		rprintfInit(uart1AddToTxBuffer);
+		rprintf("I2C: MT->SLA_ACK or DATA_ACK\r\n");
+		rprintfInit(uart1SendByte);
+		#endif
+		if(I2cSendDataIndex < I2cSendDataLength)
+		{
+			// send data
+			i2cSendByte( I2cSendData[I2cSendDataIndex++] );
+		}
+		else
+		{
+			// transmit stop condition, enable SLA ACK
+			i2cSendStop();
+			// set state
+			I2cState = I2C_IDLE;
+		}
+		break;
+	case TW_MR_DATA_NACK:				// 0x58: Data received, NACK reply issued
+		#ifdef I2C_DEBUG
+		rprintfInit(uart1AddToTxBuffer);
+		rprintf("I2C: MR->DATA_NACK\r\n");
+		rprintfInit(uart1SendByte);
+		#endif
+		// store final received data byte
+		I2cReceiveData[I2cReceiveDataIndex++] = inb(TWDR);
+		// continue to transmit STOP condition
+	case TW_MR_SLA_NACK:				// 0x48: Slave address not acknowledged
+	case TW_MT_SLA_NACK:				// 0x20: Slave address not acknowledged
+	case TW_MT_DATA_NACK:				// 0x30: Data not acknowledged
+		#ifdef I2C_DEBUG
+		rprintfInit(uart1AddToTxBuffer);
+		rprintf("I2C: MTR->SLA_NACK or MT->DATA_NACK\r\n");
+		rprintfInit(uart1SendByte);
+		#endif
+		// transmit stop condition, enable SLA ACK
+		i2cSendStop();
+		// set state
+		I2cState = I2C_IDLE;
+		break;
+	case TW_MT_ARB_LOST:				// 0x38: Bus arbitration lost
+	//case TW_MR_ARB_LOST:				// 0x38: Bus arbitration lost
+		#ifdef I2C_DEBUG
+		rprintfInit(uart1AddToTxBuffer);
+		rprintf("I2C: MT->ARB_LOST\r\n");
+		rprintfInit(uart1SendByte);
+		#endif
+		// release bus
+		outb(TWCR, (inb(TWCR)&TWCR_CMD_MASK)|BV(TWINT));
+		// set state
+		I2cState = I2C_IDLE;
+		// release bus and transmit start when bus is free
+		//outb(TWCR, (inb(TWCR)&TWCR_CMD_MASK)|BV(TWINT)|BV(TWSTA));
+		break;
+	case TW_MR_DATA_ACK:				// 0x50: Data acknowledged
+		#ifdef I2C_DEBUG
+		rprintfInit(uart1AddToTxBuffer);
+		rprintf("I2C: MR->DATA_ACK\r\n");
+		rprintfInit(uart1SendByte);
+		#endif
+		// store received data byte
+		I2cReceiveData[I2cReceiveDataIndex++] = inb(TWDR);
+		// fall-through to see if more bytes will be received
+	case TW_MR_SLA_ACK:					// 0x40: Slave address acknowledged
+		#ifdef I2C_DEBUG
+		rprintfInit(uart1AddToTxBuffer);
+		rprintf("I2C: MR->SLA_ACK\r\n");
+		rprintfInit(uart1SendByte);
+		#endif
+		if(I2cReceiveDataIndex < (I2cReceiveDataLength-1))
+			// data byte will be received, reply with ACK (more bytes in transfer)
+			i2cReceiveByte(TRUE);
+		else
+			// data byte will be received, reply with NACK (final byte in transfer)
+			i2cReceiveByte(FALSE);
+		break;
+
+	// Slave Receiver status codes
+	case TW_SR_SLA_ACK:					// 0x60: own SLA+W has been received, ACK has been returned
+	case TW_SR_ARB_LOST_SLA_ACK:		// 0x68: own SLA+W has been received, ACK has been returned
+	case TW_SR_GCALL_ACK:				// 0x70:     GCA+W has been received, ACK has been returned
+	case TW_SR_ARB_LOST_GCALL_ACK:		// 0x78:     GCA+W has been received, ACK has been returned
+		#ifdef I2C_DEBUG
+		rprintfInit(uart1AddToTxBuffer);
+		rprintf("I2C: SR->SLA_ACK\r\n");
+		rprintfInit(uart1SendByte);
+		#endif
+		// we are being addressed as slave for writing (data will be received from master)
+		// set state
+		I2cState = I2C_SLAVE_RX;
+		// prepare buffer
+		I2cReceiveDataIndex = 0;
+		// receive data byte and return ACK
+		outb(TWCR, (inb(TWCR)&TWCR_CMD_MASK)|BV(TWINT)|BV(TWEA));
+		break;
+	case TW_SR_DATA_ACK:				// 0x80: data byte has been received, ACK has been returned
+	case TW_SR_GCALL_DATA_ACK:			// 0x90: data byte has been received, ACK has been returned
+		#ifdef I2C_DEBUG
+		rprintfInit(uart1AddToTxBuffer);
+		rprintf("I2C: SR->DATA_ACK\r\n");
+		rprintfInit(uart1SendByte);
+		#endif
+		// get previously received data byte
+		I2cReceiveData[I2cReceiveDataIndex++] = inb(TWDR);
+		// check receive buffer status
+		if(I2cReceiveDataIndex < I2C_RECEIVE_DATA_BUFFER_SIZE)
+		{
+			// receive data byte and return ACK
+			i2cReceiveByte(TRUE);
+			//outb(TWCR, (inb(TWCR)&TWCR_CMD_MASK)|BV(TWINT)|BV(TWEA));
+		}
+		else
+		{
+			// receive data byte and return NACK
+			i2cReceiveByte(FALSE);
+			//outb(TWCR, (inb(TWCR)&TWCR_CMD_MASK)|BV(TWINT));
+		}
+		break;
+	case TW_SR_DATA_NACK:				// 0x88: data byte has been received, NACK has been returned
+	case TW_SR_GCALL_DATA_NACK:			// 0x98: data byte has been received, NACK has been returned
+		#ifdef I2C_DEBUG
+		rprintfInit(uart1AddToTxBuffer);
+		rprintf("I2C: SR->DATA_NACK\r\n");
+		rprintfInit(uart1SendByte);
+		#endif
+		// receive data byte and return NACK
+		i2cReceiveByte(FALSE);
+		//outb(TWCR, (inb(TWCR)&TWCR_CMD_MASK)|BV(TWINT));
+		break;
+	case TW_SR_STOP:					// 0xA0: STOP or REPEATED START has been received while addressed as slave
+		#ifdef I2C_DEBUG
+		rprintfInit(uart1AddToTxBuffer);
+		rprintf("I2C: SR->SR_STOP\r\n");
+		rprintfInit(uart1SendByte);
+		#endif
+		// switch to SR mode with SLA ACK
+		outb(TWCR, (inb(TWCR)&TWCR_CMD_MASK)|BV(TWINT)|BV(TWEA));
+		// i2c receive is complete, call i2cSlaveReceive
+		if(i2cSlaveReceive) i2cSlaveReceive(I2cReceiveDataIndex, I2cReceiveData);
+		// set state
+		I2cState = I2C_IDLE;
+		break;
+
+	// Slave Transmitter
+	case TW_ST_SLA_ACK:					// 0xA8: own SLA+R has been received, ACK has been returned
+	case TW_ST_ARB_LOST_SLA_ACK:		// 0xB0:     GCA+R has been received, ACK has been returned
+		#ifdef I2C_DEBUG
+		rprintfInit(uart1AddToTxBuffer);
+		rprintf("I2C: ST->SLA_ACK\r\n");
+		rprintfInit(uart1SendByte);
+		#endif
+		// we are being addressed as slave for reading (data must be transmitted back to master)
+		// set state
+		I2cState = I2C_SLAVE_TX;
+		// request data from application
+		if(i2cSlaveTransmit) I2cSendDataLength = i2cSlaveTransmit(I2C_SEND_DATA_BUFFER_SIZE, I2cSendData);
+		// reset data index
+		I2cSendDataIndex = 0;
+		// fall-through to transmit first data byte
+	case TW_ST_DATA_ACK:				// 0xB8: data byte has been transmitted, ACK has been received
+		#ifdef I2C_DEBUG
+		rprintfInit(uart1AddToTxBuffer);
+		rprintf("I2C: ST->DATA_ACK\r\n");
+		rprintfInit(uart1SendByte);
+		#endif
+		// transmit data byte
+		outb(TWDR, I2cSendData[I2cSendDataIndex++]);
+		if(I2cSendDataIndex < I2cSendDataLength)
+			// expect ACK to data byte
+			outb(TWCR, (inb(TWCR)&TWCR_CMD_MASK)|BV(TWINT)|BV(TWEA));
+		else
+			// expect NACK to data byte
+			outb(TWCR, (inb(TWCR)&TWCR_CMD_MASK)|BV(TWINT));
+		break;
+	case TW_ST_DATA_NACK:				// 0xC0: data byte has been transmitted, NACK has been received
+	case TW_ST_LAST_DATA:				// 0xC8:
+		#ifdef I2C_DEBUG
+		rprintfInit(uart1AddToTxBuffer);
+		rprintf("I2C: ST->DATA_NACK or LAST_DATA\r\n");
+		rprintfInit(uart1SendByte);
+		#endif
+		// all done
+		// switch to open slave
+		outb(TWCR, (inb(TWCR)&TWCR_CMD_MASK)|BV(TWINT)|BV(TWEA));
+		// set state
+		I2cState = I2C_IDLE;
+		break;
+
+	// Misc
+	case TW_NO_INFO:					// 0xF8: No relevant state information
+		// do nothing
+		#ifdef I2C_DEBUG
+		rprintfInit(uart1AddToTxBuffer);
+		rprintf("I2C: NO_INFO\r\n");
+		rprintfInit(uart1SendByte);
+		#endif
+		break;
+	case TW_BUS_ERROR:					// 0x00: Bus error due to illegal start or stop condition
+		#ifdef I2C_DEBUG
+		rprintfInit(uart1AddToTxBuffer);
+		rprintf("I2C: BUS_ERROR\r\n");
+		rprintfInit(uart1SendByte);
+		#endif
+		// reset internal hardware and release bus
+		outb(TWCR, (inb(TWCR)&TWCR_CMD_MASK)|BV(TWINT)|BV(TWSTO)|BV(TWEA));
+		// set state
+		I2cState = I2C_IDLE;
+		break;
+	}
+}
+
+eI2cStateType i2cGetState(void)
+{
+	return I2cState;
+}
+
+void i2c_get_data(unsigned char length, unsigned char *data)
+{
+  unsigned char i;
+
+  for(i=0;i<length;i++)
+  { 
+    data[i]=I2cReceiveData[i];
+  }
+}
+
diff --git a/i2c.h b/i2c.h
new file mode 100755
index 0000000..21b68e3
--- /dev/null
+++ b/i2c.h
@@ -0,0 +1,178 @@
+/*! \file i2c.h \brief I2C interface using AVR Two-Wire Interface (TWI) hardware. */
+//*****************************************************************************
+//
+// File Name	: 'i2c.h'
+// Title		: I2C interface using AVR Two-Wire Interface (TWI) hardware
+// Author		: Pascal Stang - Copyright (C) 2002-2003
+// Created		: 2002.06.25
+// Revised		: 2003.03.03
+// Version		: 0.9
+// Target MCU	: Atmel AVR series
+// Editor Tabs	: 4
+//
+///	\ingroup driver_avr
+/// \defgroup i2c I2C Serial Interface Function Library (i2c.c)
+/// \code #include "i2c.h" \endcode
+/// \par Overview
+///		This library provides the high-level functions needed to use the I2C
+///	serial interface supported by the hardware of several AVR processors.
+/// The library is functional but has not been exhaustively tested yet and is
+/// still expanding.  Thanks to the standardization of the I2C protocol and
+///	register access, the send and receive commands are everything you need to
+/// talk to thousands of different I2C devices including: EEPROMS, Flash memory,
+/// MP3 players, A/D and D/A converters, electronic potentiometers, etc.
+///
+/// \par About I2C
+///			I2C (pronounced "eye-squared-see") is a two-wire bidirectional
+///		network designed for easy transfer of information between a wide variety
+///		of intelligent devices.  Many of the Atmel AVR series processors have
+///		hardware support for transmitting and receiving using an I2C-type bus.
+///		In addition to the AVRs, there are thousands of other parts made by
+///		manufacturers like Philips, Maxim, National, TI, etc that use I2C as
+///		their primary means of communication and control.  Common device types
+///		are A/D & D/A converters, temp sensors, intelligent battery monitors,
+///		MP3 decoder chips, EEPROM chips, multiplexing switches, etc.
+///
+///		I2C uses only two wires (SDA and SCL) to communicate bidirectionally
+///		between devices.  I2C is a multidrop network, meaning that you can have
+///		several devices on a single bus.  Because I2C uses a 7-bit number to
+///		identify which device it wants to talk to, you cannot have more than
+///		127 devices on a single bus.
+///
+///		I2C ordinarily requires two 4.7K pull-up resistors to power (one each on
+///		SDA and SCL), but for small numbers of devices (maybe 1-4), it is enough
+///		to activate the internal pull-up resistors in the AVR processor.  To do
+///		this, set the port pins, which correspond to the I2C pins SDA/SCL, high.
+///		For example, on the mega163, sbi(PORTC, 0); sbi(PORTC, 1);.
+///
+///		For complete information about I2C, see the Philips Semiconductor
+///		website.  They created I2C and have the largest family of devices that
+///		work with I2C.
+///
+/// \Note: Many manufacturers market I2C bus devices under a different or generic
+///		bus name like "Two-Wire Interface".  This is because Philips still holds
+///		"I2C" as a trademark.  For example, SMBus and SMBus devices are hardware
+///		compatible and closely related to I2C.  They can be directly connected
+///		to an I2C bus along with other I2C devices are are generally accessed in
+///		the same way as I2C devices.  SMBus is often found on modern motherboards
+///		for temp sensing and other low-level control tasks.
+//
+// This code is distributed under the GNU Public License
+//		which can be found at http://www.gnu.org/licenses/gpl.txt
+//
+//*****************************************************************************
+
+#ifndef I2C_H
+#define I2C_H
+
+#include "global.h"
+
+// include project-specific configuration
+#include "i2cconf.h"
+
+// TWSR values (not bits)
+// (taken from avr-libc twi.h - thank you Marek Michalkiewicz)
+// Master
+#define TW_START					0x08
+#define TW_REP_START				0x10
+// Master Transmitter
+#define TW_MT_SLA_ACK				0x18
+#define TW_MT_SLA_NACK				0x20
+#define TW_MT_DATA_ACK				0x28
+#define TW_MT_DATA_NACK				0x30
+#define TW_MT_ARB_LOST				0x38
+// Master Receiver
+#define TW_MR_ARB_LOST				0x38
+#define TW_MR_SLA_ACK				0x40
+#define TW_MR_SLA_NACK				0x48
+#define TW_MR_DATA_ACK				0x50
+#define TW_MR_DATA_NACK				0x58
+// Slave Transmitter
+#define TW_ST_SLA_ACK				0xA8
+#define TW_ST_ARB_LOST_SLA_ACK		0xB0
+#define TW_ST_DATA_ACK				0xB8
+#define TW_ST_DATA_NACK				0xC0
+#define TW_ST_LAST_DATA				0xC8
+// Slave Receiver
+#define TW_SR_SLA_ACK				0x60
+#define TW_SR_ARB_LOST_SLA_ACK		0x68
+#define TW_SR_GCALL_ACK				0x70
+#define TW_SR_ARB_LOST_GCALL_ACK	0x78
+#define TW_SR_DATA_ACK				0x80
+#define TW_SR_DATA_NACK				0x88
+#define TW_SR_GCALL_DATA_ACK		0x90
+#define TW_SR_GCALL_DATA_NACK		0x98
+#define TW_SR_STOP					0xA0
+// Misc
+#define TW_NO_INFO					0xF8
+#define TW_BUS_ERROR				0x00
+
+// defines and constants
+#define TWCR_CMD_MASK		0x0F
+#define TWSR_STATUS_MASK	0xF8
+
+// return values
+#define I2C_OK				0x00
+#define I2C_ERROR_NODEV		0x01
+
+// types
+typedef enum
+{
+	I2C_IDLE = 0, I2C_BUSY = 1,
+	I2C_MASTER_TX = 2, I2C_MASTER_RX = 3,
+	I2C_SLAVE_TX = 4, I2C_SLAVE_RX = 5
+} eI2cStateType;
+
+// functions
+
+//! Initialize I2C (TWI) interface
+void i2cInit(void);
+
+//! Set the I2C transaction bitrate (in KHz)
+void i2cSetBitrate(u16 bitrateKHz);
+
+// I2C setup and configurations commands
+//! Set the local (AVR processor's) I2C device address
+void i2cSetLocalDeviceAddr(u08 deviceAddr, u08 genCallEn);
+
+//! Set the user function which handles receiving (incoming) data as a slave
+void i2cSetSlaveReceiveHandler(void (*i2cSlaveRx_func)(u08 receiveDataLength, u08* recieveData));
+//! Set the user function which handles transmitting (outgoing) data as a slave
+void i2cSetSlaveTransmitHandler(u08 (*i2cSlaveTx_func)(u08 transmitDataLengthMax, u08* transmitData));
+
+// Low-level I2C transaction commands 
+//! Send an I2C start condition in Master mode
+void i2cSendStart(void);
+//! Send an I2C stop condition in Master mode
+void i2cSendStop(void);
+//! Wait for current I2C operation to complete
+void i2cWaitForComplete(void);
+//! Send an (address|R/W) combination or a data byte over I2C
+void i2cSendByte(u08 data);
+//! Receive a data byte over I2C  
+// ackFlag = TRUE if recevied data should be ACK'ed
+// ackFlag = FALSE if recevied data should be NACK'ed
+void i2cReceiveByte(u08 ackFlag);
+//! Pick up the data that was received with i2cReceiveByte()
+u08 i2cGetReceivedByte(void);
+//! Get current I2c bus status from TWSR
+u08 i2cGetStatus(void);
+
+// high-level I2C transaction commands
+
+//! send I2C data to a device on the bus
+void i2cMasterSend(u08 deviceAddr, u08 length, u08 *data);
+//! receive I2C data from a device on the bus
+void i2cMasterReceive(u08 deviceAddr, u08 length);//, u08* data);
+
+//! send I2C data to a device on the bus (non-interrupt based)
+u08 i2cMasterSendNI(u08 deviceAddr, u08 length, u08* data);
+//! receive I2C data from a device on the bus (non-interrupt based)
+u08 i2cMasterReceiveNI(u08 deviceAddr, u08 length, u08 *data);
+
+//! Get the current high-level state of the I2C interface
+eI2cStateType i2cGetState(void);
+
+void i2c_get_data(unsigned char length, unsigned char *data);
+
+#endif
diff --git a/i2cconf.h b/i2cconf.h
new file mode 100755
index 0000000..8152167
--- /dev/null
+++ b/i2cconf.h
@@ -0,0 +1,28 @@
+/*! \file i2cconf.h \brief I2C (TWI) interface configuration. */
+//*****************************************************************************
+//
+// File Name	: 'i2cconf.h'
+// Title		: I2C (TWI) interface configuration
+// Author		: Pascal Stang - Copyright (C) 2002-2003
+// Created		: 2002.06.25
+// Revised		: 2003.03.02
+// Version		: 0.7
+// Target MCU	: Atmel AVR series
+// Editor Tabs	: 4
+//
+// This code is distributed under the GNU Public License
+//		which can be found at http://www.gnu.org/licenses/gpl.txt
+//
+//*****************************************************************************
+
+#ifndef I2CCONF_H
+#define I2CCONF_H
+
+// define I2C data buffer sizes
+// These buffers are used in interrupt-driven Master sending and receiving,
+// and in slave sending and receiving.  They must be large enough to store
+// the largest I2C packet you expect to send and receive, respectively.
+#define I2C_SEND_DATA_BUFFER_SIZE		0x20
+#define I2C_RECEIVE_DATA_BUFFER_SIZE	0x20
+
+#endif
diff --git a/include/adc.h b/include/adc.h
deleted file mode 100644
index c79e8cb..0000000
--- a/include/adc.h
+++ /dev/null
@@ -1,14 +0,0 @@
-#ifndef _ADC_H
-#define _ADC_H
-
-#include <avr/io.h>
-#include <avr/interrupt.h>
-
-void adc_init(void);
-void adc_start(void);
-void adc_stop(void);
-void adc_set_num_samples(uint8_t num);
-void adc_set_sample_period(uint8_t time_ms);
-void adc_loop(void);
-
-#endif
diff --git a/include/compass.h b/include/compass.h
deleted file mode 100644
index 8a739de..0000000
--- a/include/compass.h
+++ /dev/null
@@ -1,23 +0,0 @@
-#ifndef _COMPASS_H
-#define _COMPASS_H
-
-#include <avr/io.h>
-#include <avr/interrupt.h>
-
-// compass address
-#define COMPASS_ADDR           0x42
-
-// compass commands
-#define COMPASS_HEADING        0x41
-#define COMPASS_START_CAL      0x43
-#define COMPASS_STOP_CAL       0x45
-
-void compass_init(void);
-void compass_start(void);
-void compass_stop(void);
-void compass_start_calibration(void);
-void compass_stop_calibration(void);
-void compass_set_num_samples(uint8_t num);
-void compass_loop(void);
-
-#endif
diff --git a/include/dac.h b/include/dac.h
deleted file mode 100644
index 45b7f3b..0000000
--- a/include/dac.h
+++ /dev/null
@@ -1,16 +0,0 @@
-#ifndef _DAC_H
-#define _DAC_H
-
-#include <avr/io.h>
-#include <avr/interrupt.h>
-
-typedef enum {dac0=0,dac1=1} dac_ch_t;
-
-void dac_init(void);
-void dac_start(void);
-void dac_stop(void);
-void dac_enable_channel(dac_ch_t ch);
-void dac_disable_channel(dac_ch_t ch);
-void dac_set_voltage(dac_ch_t ch,uint16_t voltage);
-
-#endif
diff --git a/include/dyn_common.h b/include/dyn_common.h
deleted file mode 100644
index 72a1d88..0000000
--- a/include/dyn_common.h
+++ /dev/null
@@ -1,32 +0,0 @@
-#ifndef _DYN_COMMON_H
-#define _DYN_COMMON_H
-
-#include <avr/io.h>
-#include <avr/interrupt.h>
-
-// Instruction identifiers
-#define INST_PING           0x01
-#define INST_READ           0x02
-#define INST_WRITE          0x03
-#define INST_REG_WRITE      0x04
-#define INST_ACTION         0x05
-#define INST_RESET          0x06
-#define INST_SYNC_READ      0x82
-#define INST_SYNC_WRITE     0x83
-#define INST_BULK_READ      0x92
-#define INST_BULK_WRITE     0x93
-
-// bus errors
-#define INSTRUCTION_ERROR   0x40
-#define OVERLOAD_ERROR      0x20
-#define CHECKSUM_ERROR      0x10
-#define RANGE_ERROR         0x08
-#define OVERHEATING_ERROR   0x04
-#define ANGLE_LIMIT_ERROR   0x02
-#define VOLTAGE_ERROR       0x01
-#define NO_ERROR            0x00
-
-uint8_t do_write(uint8_t address,uint8_t length,uint8_t *data);
-uint8_t do_read(uint8_t address,uint8_t length,uint8_t **data);
-
-#endif
diff --git a/include/dyn_slave_diff.h b/include/dyn_slave_diff.h
deleted file mode 100644
index c3978a5..0000000
--- a/include/dyn_slave_diff.h
+++ /dev/null
@@ -1,15 +0,0 @@
-#ifndef DYN_SLAVE_DIFF_H
-#define DYN_SLAVE_DIFF_H
-
-#include <avr/interrupt.h>
-#include <avr/io.h>
-#include "dyn_common.h"
-
-void dyn_slave_diff_init(uint8_t baudrate,uint8_t id);
-void dyn_slave_diff_set_baudrate(uint8_t baudrate);
-void dyn_slave_diff_set_id(uint8_t id);
-void dyn_slave_diff_loop(void);
-void dyn_slave_diff_set_error(uint8_t error);
-void dyn_slave_diff_clear_error(void);
-
-#endif
diff --git a/include/dyn_slave_se.h b/include/dyn_slave_se.h
deleted file mode 100644
index 3c29692..0000000
--- a/include/dyn_slave_se.h
+++ /dev/null
@@ -1,15 +0,0 @@
-#ifndef DYN_SLAVE_SE_H
-#define DYN_SLAVE_SE_H
-
-#include <avr/interrupt.h>
-#include <avr/io.h>
-#include "dyn_common.h"
-
-void dyn_slave_se_init(uint8_t baudrate,uint8_t id);
-void dyn_slave_se_set_baudrate(uint8_t baudrate);
-void dyn_slave_se_set_id(uint8_t id);
-void dyn_slave_se_loop(void);
-void dyn_slave_se_set_error(uint8_t error);
-void dyn_slave_se_clear_error(void);
-
-#endif
diff --git a/include/i2c.h b/include/i2c.h
deleted file mode 100644
index 923ceb8..0000000
--- a/include/i2c.h
+++ /dev/null
@@ -1,44 +0,0 @@
-#ifndef I2C_H
-#define I2C_H
-
-// TWSR values (not bits)
-// (taken from avr-libc twi.h - thank you Marek Michalkiewicz)
-// Master
-#define TW_START				0x08
-#define TW_REP_START				0x10
-// Master Transmitter
-#define TW_MT_SLA_ACK				0x18
-#define TW_MT_SLA_NACK				0x20
-#define TW_MT_DATA_ACK				0x28
-#define TW_MT_DATA_NACK				0x30
-#define TW_MT_ARB_LOST				0x38
-// Master Receiver
-#define TW_MR_ARB_LOST				0x38
-#define TW_MR_SLA_ACK				0x40
-#define TW_MR_SLA_NACK				0x48
-#define TW_MR_DATA_ACK				0x50
-#define TW_MR_DATA_NACK				0x58
-// Misc
-#define TW_NO_INFO				0xF8
-#define TW_BUS_ERROR				0x00
-
-// defines and constants
-#define TWCR_CMD_MASK		                0x0F
-#define TWSR_STATUS_MASK	                0xF8
-
-// return values
-#define I2C_OK				        0x00
-#define I2C_ERROR_NODEV		                0x01
-
-// types
-typedef enum {I2C_IDLE=0,I2C_BUSY=1,I2C_MASTER_TX=2,I2C_MASTER_RX=3} i2c_states_t;
-
-/* public functions */
-void i2c_init(uint16_t bitrate_khz);
-void i2c_set_bitrate(uint16_t bitrate_khz);
-void i2c_master_send(uint8_t deviceAddr, uint8_t length, uint8_t *data);
-void i2c_master_receive(uint8_t deviceAddr, uint8_t length);
-void i2c_get_data(unsigned char length, unsigned char *data);
-i2c_states_t i2c_get_state(void);
-
-#endif
diff --git a/include/mem.h b/include/mem.h
deleted file mode 100644
index 54b80f5..0000000
--- a/include/mem.h
+++ /dev/null
@@ -1,13 +0,0 @@
-#ifndef _MEM_H
-#define _MEM_H
-
-#include <avr/io.h>
-#include "memory_map.h"
-
-extern uint8_t ram_data[RAM_SIZE];
-
-void ram_init(void);
-uint8_t ram_read(uint8_t address, uint8_t length, uint8_t **data);
-uint8_t ram_write(uint8_t address, uint8_t length, uint8_t *data);
-
-#endif
diff --git a/include/memory_map.h b/include/memory_map.h
deleted file mode 100644
index 015a029..0000000
--- a/include/memory_map.h
+++ /dev/null
@@ -1,188 +0,0 @@
-#ifndef _MEMORY_MAP_H
-#define _MEMORY_MAP_H
-
-// Register Id  EEPROM - declared in dynamixel
-#define Model_Number_L            0X00   //0 - 0X0C R - Lowest byte of model number 
-#define Model_Number_H            0X01   //1 - 0X00 R - Highest byte of model number  
-#define Version_Firmware          0X02   //2 - 0X00 R - Information on the version of firmware    
-#define ID                        0X03   //3 - 0X03 R/W - ID of Dynamixel
-#define Baud_Rate                 0X04   //4 - 0X01 R/W - Baud Rate of Dynamixel  
-#define Return_Delay_Time         0X05   //5 - 0XFA R/W - Return Delay Time (value*2us) currently not implemented
-#define Status_Return_Level       0X10   //16 - 0x10 R/W - Level os reply information 
-// EEPROM end at 0x1F
-// RAM starts at 0x20
-#define ADC_CONTROL               0x20   //32 - 0x20 R/W  ADC control  bit 7 | bit 6 | bit 5 | bit 4 | bit 3 |  bit 2  | bit 1 | bit 0
-                                         //                                                                    running   stop    start
-#define ADC_NUM_SAMPLES           0x21   //33 - 0x21 R/W  Number of sample to average
-#define ADC_SAMPLE_PERIOD         0x22   //33 - 0x22 R/W  ADC sample period in ms
-#define GPIO0_config              0x30   //48 - 0x30 R/W  GPIO 0 configuration bit 7 | bit 6 | bit 5 | bit 4 | bit 3 | bit 2 | bit 1 | bit 0
-                                         //                                                                                            mode (0 -> input, 1 -> output)
-#define GPIO0_data                0x31   //49 - 0x31 R/W  GPIO 0 data bit 7 | bit 6 | bit 5 | bit 4 | bit 3 | bit 2 | bit 1 | bit 0
-                                         //                                                                                   current input value (input mode)
-                                         //                                                                                   output value (output mode)
-#define GPIO1_config              0x32   //50 - 0x32 R/W  GPIO 0 configuration bit 7 | bit 6 | bit 5 | bit 4 | bit 3 | bit 2 | bit 1 | bit 0
-                                         //                                                                                            mode (0 -> input, 1 -> output)
-#define GPIO1_data                0x33   //51 - 0x33 R/W  GPIO 0 data bit 7 | bit 6 | bit 5 | bit 4 | bit 3 | bit 2 | bit 1 | bit 0
-                                         //                                                                                   current input value (input mode)
-                                         //                                                                                   output value (output mode)
-#define GPIO2_config              0x34   //52 - 0x34 R/W  GPIO 0 configuration bit 7 | bit 6 | bit 5 | bit 4 | bit 3 | bit 2 | bit 1 | bit 0
-                                         //                                                                                            mode (0 -> input, 1 -> output)
-#define GPIO2_data                0x35   //53 - 0x35 R/W  GPIO 0 data bit 7 | bit 6 | bit 5 | bit 4 | bit 3 | bit 2 | bit 1 | bit 0
-                                         //                                                                                   current input value (input mode)
-                                         //                                                                                   output value (output mode) 
-#define GPIO3_config              0x36   //54 - 0x36 R/W  GPIO 0 configuration bit 7 | bit 6 | bit 5 | bit 4 | bit 3 | bit 2 | bit 1 | bit 0
-                                         //                                                                                            mode (0 -> input, 1 -> output)
-#define GPIO3_data                0x37   //55 - 0x37 R/W  GPIO 0 data bit 7 | bit 6 | bit 5 | bit 4 | bit 3 | bit 2 | bit 1 | bit 0
-                                         //                                                                                   current input value (input mode)
-                                         //                                                                                   output value (output mode)
-#define GPIO4_config              0x38   //56 - 0x38 R/W  GPIO 0 configuration bit 7 | bit 6 | bit 5 | bit 4 | bit 3 | bit 2 | bit 1 | bit 0
-                                         //                                                                                            mode (0 -> input, 1 -> output)
-#define GPIO4_data                0x39   //57 - 0x39 R/W  GPIO 0 data bit 7 | bit 6 | bit 5 | bit 4 | bit 3 | bit 2 | bit 1 | bit 0
-                                         //                                                                                   current input value (input mode)
-                                         //                                                                                   output value (output mode) 
-#define GPIO5_config              0x3A   //58 - 0x3A R/W  GPIO 0 configuration bit 7 | bit 6 | bit 5 | bit 4 | bit 3 | bit 2 | bit 1 | bit 0
-                                         //                                                                                            mode (0 -> input, 1 -> output)
-#define GPIO5_data                0x3B   //59 - 0x3B R/W  GPIO 0 data bit 7 | bit 6 | bit 5 | bit 4 | bit 3 | bit 2 | bit 1 | bit 0
-                                         //                                                                                   current input value (input mode)
-                                         //                                                                                   output value (output mode) 
-#define GPIO6_config              0x3C   //60 - 0x3C R/W  GPIO 0 configuration bit 7 | bit 6 | bit 5 | bit 4 | bit 3 | bit 2 | bit 1 | bit 0
-                                         //                                                                                            mode (0 -> input, 1 -> output)
-#define GPIO6_data                0x3D   //61 - 0x3D R/W  GPIO 0 data bit 7 | bit 6 | bit 5 | bit 4 | bit 3 | bit 2 | bit 1 | bit 0
-                                         //                                                                                   current input value (input mode)
-                                         //                                                                                   output value (output mode) 
-#define GPIO7_config              0x3E   //62 - 0x3E R/W  GPIO 0 configuration bit 7 | bit 6 | bit 5 | bit 4 | bit 3 | bit 2 | bit 1 | bit 0
-                                         //                                                                                            mode (0 -> input, 1 -> output)
-#define GPIO7_data                0x3F   //63 - 0x3F R/W  GPIO 0 data bit 7 | bit 6 | bit 5 | bit 4 | bit 3 | bit 2 | bit 1 | bit 0
-                                         //                                                                                   current input value (input mode)
-                                         //                                                                                   output value (output mode) 
-#define GPIO8_config              0x40   //64 - 0x40 R/W  GPIO 0 configuration bit 7 | bit 6 | bit 5 | bit 4 | bit 3 | bit 2 | bit 1 | bit 0
-                                         //                                                                                            mode (0 -> input, 1 -> output)
-#define GPIO8_data                0x41   //65 - 0x41 R/W  GPIO 0 data bit 7 | bit 6 | bit 5 | bit 4 | bit 3 | bit 2 | bit 1 | bit 0
-                                         //                                                                                   current input value (input mode)
-                                         //                                                                                   output value (output mode) 
-#define GPIO9_config              0x41   //66 - 0x42 R/W  GPIO 0 configuration bit 7 | bit 6 | bit 5 | bit 4 | bit 3 | bit 2 | bit 1 | bit 0
-                                         //                                                                                            mode (0 -> input, 1 -> output)
-#define GPIO9_data                0x43   //67 - 0x43 R/W  GPIO 0 data bit 7 | bit 6 | bit 5 | bit 4 | bit 3 | bit 2 | bit 1 | bit 0
-                                         //                                                                                   current input value (input mode)
-                                         //                                                                                   output value (output mode) 
-#define GPIO10_config             0x44   //68 - 0x44 R/W  GPIO 0 configuration bit 7 | bit 6 | bit 5 | bit 4 | bit 3 | bit 2 | bit 1 | bit 0
-                                         //                                                                                            mode (0 -> input, 1 -> output)
-#define GPIO10_data               0x45   //69 - 0x45 R/W  GPIO 0 data bit 7 | bit 6 | bit 5 | bit 4 | bit 3 | bit 2 | bit 1 | bit 0
-                                         //                                                                                   current input value (input mode)
-                                         //                                                                                   output value (output mode) 
-#define GPIO11_config             0x46   //70 - 0x46 R/W  GPIO 0 configuration bit 7 | bit 6 | bit 5 | bit 4 | bit 3 | bit 2 | bit 1 | bit 0
-                                         //                                                                                            mode (0 -> input, 1 -> output)
-#define GPIO11_data               0x47   //71 - 0x47 R/W  GPIO 0 data bit 7 | bit 6 | bit 5 | bit 4 | bit 3 | bit 2 | bit 1 | bit 0
-                                         //                                                                                   current input value (input mode)
-                                         //                                                                                   output value (output mode) 
-#define GPIO12_config             0x48   //72 - 0x48 R/W  GPIO 0 configuration bit 7 | bit 6 | bit 5 | bit 4 | bit 3 | bit 2 | bit 1 | bit 0
-                                         //                                                                                            mode (0 -> input, 1 -> output)
-#define GPIO12_data               0x49   //73 - 0x49 R/W  GPIO 0 data bit 7 | bit 6 | bit 5 | bit 4 | bit 3 | bit 2 | bit 1 | bit 0
-                                         //                                                                                   current input value (input mode)
-                                         //                                                                                   output value (output mode) 
-#define GPIO13_config             0x4A   //74 - 0x4A R/W  GPIO 0 configuration bit 7 | bit 6 | bit 5 | bit 4 | bit 3 | bit 2 | bit 1 | bit 0
-                                         //                                                                                            mode (0 -> input, 1 -> output)
-#define GPIO13_data               0x4B   //75 - 0x4B R/W  GPIO 0 data bit 7 | bit 6 | bit 5 | bit 4 | bit 3 | bit 2 | bit 1 | bit 0
-                                         //                                                                                   current input value (input mode)
-                                         //                                                                                   output value (output mode)
-#define GPIO14_config             0x4C   //76 - 0x4C R/W  GPIO 0 configuration bit 7 | bit 6 | bit 5 | bit 4 | bit 3 | bit 2 | bit 1 | bit 0
-                                         //                                                                                            mode (0 -> input, 1 -> output)
-#define GPIO14_data               0x4D   //77 - 0x4D R/W  GPIO 0 data bit 7 | bit 6 | bit 5 | bit 4 | bit 3 | bit 2 | bit 1 | bit 0
-                                         //                                                                                   current input value (input mode)
-                                         //                                                                                   output value (output mode) 
-#define GPIO15_config             0x4E   //78 - 0x4E R/W  GPIO 0 configuration bit 7 | bit 6 | bit 5 | bit 4 | bit 3 | bit 2 | bit 1 | bit 0
-                                         //                                                                                            mode (0 -> input, 1 -> output)
-#define GPIO15_data               0x4F   //79 - 0x4F R/W  GPIO 0 data bit 7 | bit 6 | bit 5 | bit 4 | bit 3 | bit 2 | bit 1 | bit 0
-                                         //                                                                                   current input value (input mode)
-                                         //                                                                                   output value (output mode) 
-#define GPIO16_config             0x50   //80 - 0x50 R/W  GPIO 0 configuration bit 7 | bit 6 | bit 5 | bit 4 | bit 3 | bit 2 | bit 1 | bit 0
-                                         //                                                                                            mode (0 -> input, 1 -> output)
-#define GPIO16_data               0x51   //81 - 0x51 R/W  GPIO 0 data bit 7 | bit 6 | bit 5 | bit 4 | bit 3 | bit 2 | bit 1 | bit 0
-                                         //                                                                                   current input value (input mode)
-                                         //                                                                                   output value (output mode) 
-#define GPIO17_config             0x52   //82 - 0x52 R/W  GPIO 0 configuration bit 7 | bit 6 | bit 5 | bit 4 | bit 3 | bit 2 | bit 1 | bit 0
-                                         //                                                                                            mode (0 -> input, 1 -> output)
-#define GPIO17_data               0x53   //83 - 0x53 R/W  GPIO 0 data bit 7 | bit 6 | bit 5 | bit 4 | bit 3 | bit 2 | bit 1 | bit 0
-                                         //                                                                                   current input value (input mode)
-                                         //                                                                                   output value (output mode) 
-#define GPIO18_config             0x54   //84 - 0x54 R/W  GPIO 0 configuration bit 7 | bit 6 | bit 5 | bit 4 | bit 3 | bit 2 | bit 1 | bit 0
-                                         //                                                                                            mode (0 -> input, 1 -> output)
-#define GPIO18_data               0x55   //85 - 0x55 R/W  GPIO 0 data bit 7 | bit 6 | bit 5 | bit 4 | bit 3 | bit 2 | bit 1 | bit 0
-                                         //                                                                                   current input value (input mode)
-                                         //                                                                                   output value (output mode) 
-#define LED                       0x56   //86 - 0x56 R/W  Auxiliary LED bit 7 | bit 6 | bit 5 | bit 4 | bit 3 | bit 2 | bit 1 | bit 0
-                                         //                                                                                     current value
-#define SWITCHES                  0x57   //87 - 0x57 R    Auxiliary Switches bit 7 | bit 6 | bit 5 | bit 4 | bit 3 | bit 2 | bit 1 | bit 0
-                                         //                                                                                  current switches value
-#define ADC_CHANNEL0_L            0x58
-#define ADC_CHANNEL0_H            0x59
-#define ADC_CHANNEL1_L            0x5A
-#define ADC_CHANNEL1_H            0x5B
-#define ADC_CHANNEL2_L            0x5C
-#define ADC_CHANNEL2_H            0x5D
-#define ADC_CHANNEL3_L            0x5E
-#define ADC_CHANNEL3_H            0x5F
-#define ADC_CHANNEL4_L            0x60
-#define ADC_CHANNEL4_H            0x61
-#define ADC_CHANNEL5_L            0x62
-#define ADC_CHANNEL5_H            0x63
-#define ADC_CHANNEL6_L            0x64
-#define ADC_CHANNEL6_H            0x65
-#define ADC_CHANNEL7_L            0x66
-#define ADC_CHANNEL7_H            0x67
-#define ADC_AVG_CHANNEL0_L        0x68
-#define ADC_AVG_CHANNEL0_H        0x69
-#define ADC_AVG_CHANNEL1_L        0x6A
-#define ADC_AVG_CHANNEL1_H        0x6B
-#define ADC_AVG_CHANNEL2_L        0x6C
-#define ADC_AVG_CHANNEL2_H        0x6D
-#define ADC_AVG_CHANNEL3_L        0x6E
-#define ADC_AVG_CHANNEL3_H        0x6F
-#define ADC_AVG_CHANNEL4_L        0x70
-#define ADC_AVG_CHANNEL4_H        0x71
-#define ADC_AVG_CHANNEL5_L        0x72
-#define ADC_AVG_CHANNEL5_H        0x73
-#define ADC_AVG_CHANNEL6_L        0x74
-#define ADC_AVG_CHANNEL6_H        0x75
-#define ADC_AVG_CHANNEL7_L        0x76
-#define ADC_AVG_CHANNEL7_H        0x77
-#define PWM_CONTROL               0x78   //     bit 7   |    bit 6    |    bit 5    |     bit 4   | bit 3  | bit 2   | bit 1  | bit 0
-                                         // ch3_enabled   ch2_enabled   ch1_enabled   ch0_enabled            running   stop     start
-#define PWM_ENABLE                0x79   //  bit 7  |  bit 6  |  bit 5  |  bit 4  | bit 3  | bit 2  | bit 1  | bit 0
-                                         // dis_ch3   dis_ch2   dis_ch1   dis_ch0   en_ch3   en_ch2   en_ch1   en_ch0
-#define PWM_FREQ_L                0x7A
-#define PWM_FREQ_H                0x7B
-#define PWM_CH0_DUTY              0x7C
-#define PWM_CH1_DUTY              0x7D
-#define PWM_CH2_DUTY              0x7E
-#define PWM_CH3_DUTY              0x7F
-#define DAC_CONTROL               0x80   //    bit 7    |    bit 6    | bit 5 |  bit 4  | bit 3  | bit 2  | bit 1 | bit 0
-                                         // ch1_enabled   ch0_enabled           running                     stop    start
-#define DAC_ENABLE                0x81   //    bit 7    |    bit 6    | bit 5 |  bit 4  | bit 3   | bit 2   | bit 1  | bit 0
-#define DAC_CH0_VOLTAGE_L         0x82   //                                               dis_ch1   dis_ch0   en_ch1   en_ch0      
-#define DAC_CH0_VOLTAGE_H         0x83
-#define DAC_CH1_VOLTAGE_L         0x84
-#define DAC_CH1_VOLTAGE_H         0x85
-#define COMPASS_CONTROL           0x86   //     bit 7   |  bit 6  | bit 5 | bit 4  |  bit 3   |   bit 2   | bit 1 | bit 0
-                                         // calibrating   running                    stop cal   start cal   stop    start
-#define COMPASS_HEADING_VAL_L     0x87
-#define COMPASS_HEADING_VAL_H     0x88
-#define COMPASS_AVG_HEADING_VAL_L 0x89
-#define COMPASS_AVG_HEADING_VAL_H 0x8A
-#define COMPASS_NUM_SAMPLES       0x8B
-#define UART_TTL_CONTROL          0x8C   //      bit 7     |  bit 6  |  bit 5  | bit 4  |  bit 3   |   bit 2   | bit 1 | bit 0
-                                         // data_available   sending   running                         send      stop    start
-#define UART_TTL_TX_DATA          0x8D
-#define UART_TTL_RX_DATA          0x8E
-#define UART_TTL_BAUDRATE_L       0x8F
-#define UART_TTL_BAUDRATE_H       0x90
-#define UART_USB_CONTROL          0x91   //      bit 7     |  bit 6  |  bit 5  | bit 4  |  bit 3   |   bit 2   | bit 1 | bit 0
-                                         // data_available   sending   running                         send      stop    start
-#define UART_USB_TX_DATA          0x92
-#define UART_USB_RX_DATA          0x93
-#define UART_USB_BAUDRATE_L       0x94
-#define UART_USB_BAUDRATE_H       0x95
-
-#define RAM_SIZE                  150
-
-#endif
diff --git a/include/ports.h b/include/ports.h
deleted file mode 100644
index ed792f7..0000000
--- a/include/ports.h
+++ /dev/null
@@ -1,28 +0,0 @@
-#ifndef _PORTS_H
-#define _PORTS_H
-
-#define NUM_GPIO 19
-
-#define INPUT 0x00
-#define OUTPUT 0x01
-
-typedef struct
-{
-  volatile uint8_t *dir_reg;
-  volatile uint8_t *write_reg;
-  volatile uint8_t *read_reg;
-  uint8_t bit;
-}TGPIO;
-
-void init_ports(void);
-void config_port(uint8_t port_id,uint8_t dir);
-uint8_t get_port_config(uint8_t port_id);
-void set_port(uint8_t port_id);
-void clear_port(uint8_t port_id);
-uint8_t read_port(uint8_t port_id);
-void set_led(void);
-void clear_led(void);
-void toggle_led(void);
-uint8_t get_selector_value(void);
-
-#endif
diff --git a/include/pwm.h b/include/pwm.h
deleted file mode 100644
index f63ca7b..0000000
--- a/include/pwm.h
+++ /dev/null
@@ -1,17 +0,0 @@
-#ifndef _PWM_H
-#define _PWM_H
-
-#include <avr/io.h>
-#include <avr/interrupt.h>
-
-typedef enum {pwm0=0,pwm1=1,pwm2=2,pwm3=3} pwm_id_t;
-
-void pwm_init(void);
-void pwm_start(void);
-void pwm_stop(void);
-void pwm_enable_ch(pwm_id_t id);
-void pwm_disable_ch(pwm_id_t id);
-void pwm_set_frequency(uint16_t freq_hz);
-void pwm_set_duty_cycle(pwm_id_t id,uint8_t duty);
-
-#endif
diff --git a/include/uart_ttl.h b/include/uart_ttl.h
deleted file mode 100644
index cd9d613..0000000
--- a/include/uart_ttl.h
+++ /dev/null
@@ -1,14 +0,0 @@
-#ifndef UART_TTL_H
-#define UART_TTL_H
-
-/* public functions */
-void uart_ttl_init(void);
-void uart_ttl_start(void);
-void uart_ttl_stop(void);
-void uart_ttl_set_baudrate(uint32_t baudrate);
-void uart_ttl_send_byte(uint8_t data);
-uint8_t uart_ttl_is_sending(void);
-uint8_t uart_ttl_receive_byte(uint8_t* data);
-uint8_t uart_ttl_is_data_available(void);
-
-#endif
diff --git a/include/uart_usb.h b/include/uart_usb.h
deleted file mode 100644
index 069b63f..0000000
--- a/include/uart_usb.h
+++ /dev/null
@@ -1,14 +0,0 @@
-#ifndef UART_USB_H
-#define UART_USB_H
-
-/* public functions */
-void uart_usb_init(void);
-void uart_usb_start(void);
-void uart_usb_stop(void);
-void uart_usb_set_baudrate(uint32_t baudrate);
-void uart_usb_send_byte(uint8_t data);
-uint8_t uart_usb_is_sending(void);
-uint8_t uart_usb_receive_byte(uint8_t* data);
-uint8_t uart_usb_is_data_available(void);
-
-#endif
diff --git a/legacy/expansion_board.hex b/legacy/expansion_board.hex
new file mode 100755
index 0000000..dfb655c
--- /dev/null
+++ b/legacy/expansion_board.hex
@@ -0,0 +1,614 @@
+:100000000C9454000C9473000C9473000C947300C3
+:100010000C9473000C9473000C9473000C94730094
+:100020000C9473000C94A2090C9406080C947109AA
+:100030000C94DE080C940F090C94D5070C94AD08B1
+:100040000C9472070C9473000C946B040C94730062
+:100050000C9473000C94B20E0C9473000C94730007
+:100060000C9440090C94660A0C94D3090C94040A6D
+:100070000C94350A0C947C080C9496040C94730030
+:100080000C9473000C942D0D0C947300000001006F
+:1000900008004000000100040000010008002000EA
+:1000A000400080000001000411241FBECFEFD0E10A
+:1000B000DEBFCDBF11E0A0E0B1E0EAEBF5E200E089
+:1000C0000BBF02C007900D92AE38B107D9F714E00C
+:1000D000AEE8B1E001C01D92A736B107E1F70E947A
+:1000E00075000C94DB120C9400002F923F924F92FB
+:1000F0005F926F927F928F929F92AF92BF92CF92B8
+:10010000DF92EF92FF920F931F93DF93CF93CDB7C0
+:10011000DEB7C958D0400FB6F894DEBF0FBECDBFD2
+:100120000E949B110E941E03CE0104960E94490367
+:100130000E94720E0E94040C0E942E0B0E94C304A7
+:1001400085E00E9425058FE782BF80E064E872E0C9
+:100150000E9470050E94FF0482E00E94340580E442
+:100160009CE90E94F1060E94DC0481E00E942A05BD
+:1001700080E89EE30E946406789413E0412E512C9F
+:100180004C0E5D1EB2E02B2E312C2C0E3D1EA6E037
+:10019000AA2EB12CAC0EBD1EF5E06F2E712C6C0E8C
+:1001A0007D1EE8E08E2E912C8C0E9D1E81E0BE01FE
+:1001B0006F5F7F4FA20191018E01065F1F4F0E946A
+:1001C000A903823021F481E06C8140E197C188234A
+:1001D00069F739816C81361749F78B81823041F09C
+:1001E000833009F494C0813009F781E0632F82C124
+:1001F0009A859830B0F48A81823059F4892F0E9410
+:10020000540F9987888781E06C8140E022E0840167
+:1002100006C081E0632F40E420E000E010E00E948F
+:100220005F039A85292F2850283078F48A818230FC
+:1002300009F06AC0822F0E94640F9987888781E045
+:100240006C8140E022E084015CC1903139F48A8104
+:10025000823009F059C00E94220B08C0913169F424
+:100260008A81823009F050C00E94280B8E839F83C0
+:1002700081E06C8140E022E045C0923171F48A81D6
+:10028000823009F041C080913502882321F48091A9
+:100290003402882391F181E023C0913251F48A81A4
+:1002A000823091F5C3010E9406118E838D818F8368
+:1002B000DFCF892F80538632A8F48A81823021F5DE
+:1002C000892F90E0C0979C0135952795C09680FDB9
+:1002D00004C0822F0E94E11103C0822F0E943812B5
+:1002E0008E830CC0913631F0933621F0953611F0A3
+:1002F000973651F48A81823039F41E8281E06C8114
+:1003000040E021E08501FDC081E06C81F6C02A85D6
+:10031000223161F48A81823091F5809135028823FF
+:1003200019F43FEF3093350281E0E4C0203239F414
+:100330008A81823021F58B850E946910D9C0822F75
+:1003400080538632F8F48A818230C9F430E0C901E2
+:10035000C09795958795982F20FD06C06B850E94C4
+:10036000AB118AB38E83C4C08B85882321F4892F77
+:100370000E941C12BDC0892F0E940112B9C081E0E9
+:10038000632FBBC0203631F0223621F0243611F025
+:10039000263661F58A81833009F0AEC0FC84EE24F4
+:1003A0008B85A701480F511DCA015CE9813495076F
+:1003B00010F080E49CE930E02056304035952795D8
+:1003C000213059F0213030F0223051F0233009F043
+:1003D0008FC009C00E9463078BC00E94680788C055
+:1003E0000E946D0785C00E94C40682C0213631F08C
+:1003F000233621F0253611F02736B9F58A8182306F
+:1004000009F07AC030E021563040359527952130EB
+:1004100089F0213030F02230B1F0233009F068C08B
+:100420001BC08B85882319F40E94480761C00E9475
+:100430002D075EC08B85882319F40E94510758C090
+:100440000E94360755C08B85882319F40E945A07ED
+:100450004FC00E943F074CC08B85882319F40E942F
+:10046000B70646C00E94A20643C0203711F02237CB
+:1004700001F58A81833009F03FC0DC84CC248B8570
+:10048000A601480F511D8EE34138580710F040E88F
+:100490005EE3822F90E08057904095958795882362
+:1004A00021F4CA010E94BE0623C0CA010E94C106EF
+:1004B0001FC0213711F02337F9F48A818230E1F42B
+:1004C000822F90E081579040959587959B85882352
+:1004D00041F4992319F40E94A9060AC00E949406C7
+:1004E00007C0992319F40E94B00602C00E949B061F
+:1004F00081E06C8140E002C081E040E420E000E067
+:1005000010E00E945F0352CE78948FE782BF0E9472
+:100510004E0B80918E0190918F01019690938F01E7
+:1005200080938E01885E934049F40A9B02C01A981A
+:1005300001C01A9A10928F0110928E01089588239B
+:1005400021F080919B00807208958BB18072089594
+:10055000F894882319F080913A0302C08091360202
+:10056000882311F08FEF01C080E0789408958823EC
+:1005700031F080919B00806480939B0008955E9A87
+:100580000895882321F080919B00807408958BB199
+:1005900080740895982F882331F080919B008064A7
+:1005A00080939B0001C05E9A992319F080919B0073
+:1005B00001C08BB18072C1F3992319F060939C0044
+:1005C00008956CB908951F93CF93DF93182FEB0113
+:1005D000812F0E94A8028823D9F3F8941123A9F04F
+:1005E000E0913903F0E0E754FD4F808188838091EA
+:1005F000390390E001968F77907080933903809152
+:100600003A03815080933A0314C0E091B802F0E0BD
+:10061000E95CFD4F808188838091B80290E001966B
+:100620008F7790708093B8028091360281508093CA
+:1006300036027894DF91CF911F91089581B3886C31
+:1006400081BB8A98E4E6F0E08081877E808396987B
+:10065000979A1BB81092900019B898E99AB986E851
+:100660008093950010929B00109298001092990030
+:1006700090939A0080939D001092390310923B034F
+:1006800010923A031092B8021092B70210923602FA
+:100690000895FC01809163008871883049F08930A9
+:1006A00058F0803119F0883139F404C080E805C071
+:1006B00080EC03C08DEF01C085E480830895CF9264
+:1006C000DF92EF92FF920F931F93CF93DF93D82E79
+:1006D000F62EE42EC22E9798969A6FEF0E94CA02C9
+:1006E0008D2D6FEF0E94CA028D2D6F2D0E94CA02C0
+:1006F0006C2D6E5F8D2D0E94CA028D2D6E2D0E9475
+:10070000CA0282E0F80EFE0CFC0CE80110E007C003
+:100710008D2D68810E94CA028991F80E1F5F1C15F9
+:10072000B8F3F0948D2D6F2D0E94CA02DD2019F0D0
+:1007300080919B0001C08BB18074C1F39698979A09
+:10074000DF91CF911F910F91FF90EF90DF90CF90AD
+:1007500008956F927F928F929F92AF92BF92DF9295
+:10076000EF92FF920F931F93DF93CF930F92CDB72A
+:10077000DEB7D82E3B014A0159010E94A802882306
+:1007800009F499C0E090900183E0E81609F440C0B4
+:100790008E1530F0E1E0EE16E1F0EE1560F10CC0E0
+:1007A000F5E0EF1609F45AC0EF1608F440C086E0F1
+:1007B000E81609F080C06FC08D2DBE016F5F7F4FBE
+:1007C0000E94E30289818F3F99F481E08093900138
+:1007D00073C08D2DBE016F5F7F4F0E94E302898140
+:1007E0008F3F31F482E0809390011092920163C0B8
+:1007F0001092900160C08D2DB3010E94E3028091A0
+:100800009201F3019081890F8093920183E03DC0B2
+:100810008D2DB5010E94E302F50180819091920136
+:10082000980F909392018250808384E02EC08D2D8A
+:10083000B4010E94E30280919201F4019081890F3A
+:1008400080939201F5018081882311F486E001C034
+:1008500085E080939001109291012DC0F09091015C
+:100860000F0D111D8D2DB8010E94E30280919201A0
+:10087000F8019081890F80939201F394F092910195
+:10088000F5018081F81621F486E08093900113C071
+:10089000E092900110C08D2DBE016F5F7F4F0E94CE
+:1008A000E302809192019981890F809392011092C5
+:1008B000900180E001C081E00F90CF91DF911F9106
+:1008C0000F91FF90EF90DF90BF90AF909F908F902F
+:1008D0007F906F9008951F920F920FB60F920BB6F4
+:1008E0000F9211248F939F93EF93FF938091B70200
+:1008F0009CB1E7E3F2E0E80FF11D90838091B7022D
+:1009000090E001968F7790708093B70280913602C5
+:100910008F5F80933602FF91EF919F918F910F909F
+:100920000BBE0F900FBE0F901F9018951F920F9245
+:100930000FB60F920BB60F9211248F939F93EF93E4
+:10094000FF9380913B0390919C00E9EBF2E0E80F6C
+:10095000F11D908380913B0390E001968F7790701A
+:1009600080933B0380913A038F5F80933A03FF911A
+:10097000EF919F918F910F900BBE0F900FBE0F9034
+:100980001F901895089583B7887F836083BF12BE38
+:1009900087B7816087BF10923C0310923D0310928D
+:1009A0003E0310923F0310924C0310924D0310929D
+:1009B0004E0310924F0308958EB5887F83608EBDDD
+:1009C0001DBC1CBC87B7846087BF089585B5887F30
+:1009D000826085BD14BC87B7806487BF10924803CE
+:1009E0001092490310924A0310924B031092400355
+:1009F0001092410310924203109243030895EAE8D3
+:100A0000F0E08081887F836080831092890010925B
+:100A10008800EDE7F0E0808184608083089580E0C5
+:100A200090E0FC01EE0FFF1FED56FE4F1182108289
+:100A300001968E309105A9F70E94C3040E94DC0440
+:100A40000E94E6040E94FF04089593B7987F982BB4
+:100A500093BF08959EB5987F982B9EBD089595B538
+:100A6000987F982B95BD0895EAE8F0E09081987FF3
+:100A7000982B9083089583B7E82FF0E0E770F0702B
+:100A8000EE0FFF1FE457FF4F25913491C9010895E0
+:100A90008EB5E82FF0E0E770F070EE0FFF1FE4571F
+:100AA000FF4F25913491C901089585B5E82FF0E0F5
+:100AB000E770F070EE0FFF1FE457FF4F2591349160
+:100AC000C901089580918A00E82FF0E0E770F07086
+:100AD000EE0FFF1FE457FF4F25913491C901089590
+:100AE0008E3040F4E82FF0E0EE0FFF1FED56FE4F82
+:100AF0007183608308958E3040F4E82FF0E0EE0FAC
+:100B0000FF1FED56FE4F118210820895EF92FF9263
+:100B10000F931F93CF93DF93EC0114B5109244030E
+:100B200010924503109246031092470385B5E82FB3
+:100B3000F0E0E770F070EE0FFF1FE457FF4F2591D4
+:100B4000349140E050E060E074E284EF90E00E9475
+:100B5000C012B901CA01693B2DE8720726E082077D
+:100B600020E09207A0F437E2C131D30780F49E0160
+:100B700040E050E00E94581228EE33E040E050E0A0
+:100B80000E949E12C901DA01BC01CD0121C028EEEC
+:100B900033E040E050E00E949E12CA01B9019E017C
+:100BA00040E050E00E94581213C08091440390919D
+:100BB0004503A0914603B091470385B7837E85BF67
+:100BC00085B7806285BF889585B78F7D85BF08C052
+:100BD0009B01AC01210F311D411D511D79018A017D
+:100BE00020914403309145034091460350914703BF
+:100BF00084B590E0A0E0B0E0542F432F322F22279D
+:100C0000822B932BA42BB52B8E159F05A007B10724
+:100C100060F2DF91CF911F910F91FF90EF900895B7
+:100C200010923C0310923D0310923E0310923F033A
+:100C300010924C0310924D0310924E0310924F03EA
+:100C4000089520913C0330913D0340913E03509123
+:100C50003F03B901CA010895109248031092490355
+:100C600010924A0310924B031092400310924103DA
+:100C7000109242031092430308952091480330914B
+:100C8000490340914A0350914B03B901CA010895A9
+:100C9000893031F48FB582608FBD8FB58E7F0AC0E9
+:100CA0008A3019F48FB5826002C08FB58D7F8FBDF9
+:100CB0008FB581608FBD1BBC1ABC19BC18BC1092CB
+:100CC00079001092780008952FB52E7F2FBD2FB593
+:100CD00022602FBD2EB528602EBD2EB520612EBD01
+:100CE00097BD86BD1BBC1ABC19BC18BC10927900FC
+:100CF0001092780008958FB58D7F8FBD8FB58E7F50
+:100D00008FBD8FB58F778FBD8FB58F7B8FBD8FB523
+:100D10008F7D8FBD8FB58F7E8FBD8FB5877F8FBD48
+:100D20008FB58B7F8FBD08958FB580688FBD8FB5D0
+:100D30008F7B8FBD08958FB580628FBD8FB58F7EFD
+:100D40008FBD08958FB588608FBD8FB58B7F8FBDA8
+:100D500008958FB58F778FBD8FB58F7B8FBD089529
+:100D60008FB58F7D8FBD8FB58F7E8FBD08958FB569
+:100D7000877F8FBD8FB58B7F8FBD08959BBD8ABD4B
+:100D8000089599BD88BD0895909379008093780067
+:100D90000895893049F480918B00826080938B00A4
+:100DA00080918B008E7F0EC08A3021F480918B0061
+:100DB000826003C080918B008D7F80938B00809137
+:100DC0008B00816080938B001092870010928600C8
+:100DD000109285001092840010928300109282007D
+:100DE0000895EBE8F0E020812E7F208320812260AF
+:100DF0002083EAE8F0E020812860208320812061C0
+:100E0000208390938100809380001092870010923D
+:100E10008600109285001092840010928300109238
+:100E200082000895EBE8F0E080818D7F80838081EF
+:100E30008E7F808380818F77808380818F7B80838A
+:100E400080818F7D808380818F7E80838081877F7A
+:100E5000808380818B7F80830895EBE8F0E0808140
+:100E60008068808380818F7B80830895EBE8F0E049
+:100E700080818062808380818F7E80830895EBE80B
+:100E8000F0E080818860808380818B7F80830895FB
+:100E9000EBE8F0E080818F77808380818F7B808397
+:100EA0000895EBE8F0E080818F7D808380818F7EE4
+:100EB00080830895EBE8F0E08081877F80838081E4
+:100EC0008B7F808308959093870080938600089598
+:100ED000909385008093840008959093830080937D
+:100EE000820008951F920F920FB60F920BB60F92C9
+:100EF00011242F933F934F935F936F937F938F931F
+:100F00009F93AF93BF93EF93FF9380913C03909196
+:100F10003D03A0913E03B0913F030196A11DB11D79
+:100F200080933C0390933D03A0933E03B0933F0313
+:100F300080913C0390913D03A0913E03B0913F030B
+:100F40000097A105B10599F480914C0390914D0350
+:100F5000A0914E03B0914F030196A11DB11D809346
+:100F60004C0390934D03A0934E03B0934F03809195
+:100F7000930190919401892B29F0E0919301F091D4
+:100F800094010995FF91EF91BF91AF919F918F913E
+:100F90007F916F915F914F913F912F910F900BBE79
+:100FA0000F900FBE0F901F9018951F920F920FB6C3
+:100FB0000F920BB60F9211242F933F934F935F9391
+:100FC0006F937F938F939F93AF93BF93EF93FF9311
+:100FD0008091970190919801892B29F0E0919701D8
+:100FE000F09198010995FF91EF91BF91AF919F9179
+:100FF0008F917F916F915F914F913F912F910F90C2
+:101000000BBE0F900FBE0F901F9018951F920F925E
+:101010000FB60F920BB60F9211242F933F934F935D
+:101020005F936F937F938F939F93AF93BF93EF9350
+:10103000FF938091480390914903A0914A03B09196
+:101040004B030196A11DB11D809348039093490362
+:10105000A0934A03B0934B038091480390914903B6
+:10106000A0914A03B0914B030097A105B10599F4F3
+:101070008091400390914103A0914203B0914303BA
+:101080000196A11DB11D8093400390934103A0934D
+:101090004203B09343038091440390914503A09190
+:1010A0004603B09147030196A11DB11D80934403EF
+:1010B00090934503A0934603B09347038091A10109
+:1010C0009091A201892B29F0E091A101F091A20158
+:1010D0000995FF91EF91BF91AF919F918F917F9172
+:1010E0006F915F914F913F912F910F900BBE0F9099
+:1010F0000FBE0F901F9018951F920F920FB60F9270
+:101100000BB60F9211242F933F934F935F936F93DE
+:101110007F938F939F93AF93BF93EF93FF938091B0
+:10112000A5019091A601892B29F0E091A501F091EC
+:10113000A6010995FF91EF91BF91AF919F918F917A
+:101140007F916F915F914F913F912F910F900BBEC7
+:101150000F900FBE0F901F9018951F920F920FB611
+:101160000F920BB60F9211242F933F934F935F93DF
+:101170006F937F938F939F93AF93BF93EF93FF935F
+:101180008091950190919601892B29F0E09195012C
+:10119000F09196010995FF91EF91BF91AF919F91C9
+:1011A0008F917F916F915F914F913F912F910F9010
+:1011B0000BBE0F900FBE0F901F9018951F920F92AD
+:1011C0000FB60F920BB60F9211242F933F934F93AC
+:1011D0005F936F937F938F939F93AF93BF93EF939F
+:1011E000FF938091990190919A01892B29F0E091C8
+:1011F0009901F0919A010995FF91EF91BF91AF91FB
+:101200009F918F917F916F915F914F913F912F911E
+:101210000F900BBE0F900FBE0F901F9018951F924E
+:101220000F920FB60F920BB60F9211242F933F938C
+:101230004F935F936F937F938F939F93AF93BF93DE
+:10124000EF93FF9380919B0190919C01892B29F052
+:10125000E0919B01F0919C010995FF91EF91BF9165
+:10126000AF919F918F917F916F915F914F913F913E
+:101270002F910F900BBE0F900FBE0F901F901895DF
+:101280001F920F920FB60F920BB60F9211242F934D
+:101290003F934F935F936F937F938F939F93AF93FE
+:1012A000BF93EF93FF9380919D0190919E01892BB5
+:1012B00029F0E0919D01F0919E010995FF91EF9138
+:1012C000BF91AF919F918F917F916F915F914F915E
+:1012D0003F912F910F900BBE0F900FBE0F901F905C
+:1012E00018951F920F920FB60F920BB60F92112402
+:1012F0002F933F934F935F936F937F938F939F931E
+:10130000AF93BF93EF93FF9380919F019091A001C2
+:10131000892B29F0E0919F01F091A0010995FF919F
+:10132000EF91BF91AF919F918F917F916F915F915D
+:101330004F913F912F910F900BBE0F900FBE0F90CA
+:101340001F9018951F920F920FB60F920BB60F9227
+:1013500011242F933F934F935F936F937F938F93BA
+:101360009F93AF93BF93EF93FF938091A3019091CD
+:10137000A401892B29F0E091A301F091A401099522
+:10138000FF91EF91BF91AF919F918F917F916F915D
+:101390005F914F913F912F910F900BBE0F900FBE19
+:1013A0000F901F9018951F920F920FB60F920BB6C9
+:1013B0000F9211242F933F934F935F936F937F93DB
+:1013C0008F939F93AF93BF93EF93FF938091A70168
+:1013D0009091A801892B29F0E091A701F091A80133
+:1013E0000995FF91EF91BF91AF919F918F917F915F
+:1013F0006F915F914F913F912F910F900BBE0F9086
+:101400000FBE0F901F9018951F920F920FB60F925C
+:101410000BB60F9211242F933F934F935F936F93CB
+:101420007F938F939F93AF93BF93EF93FF9380919D
+:10143000A9019091AA01892B29F0E091A901F091CD
+:10144000AA010995FF91EF91BF91AF919F918F9163
+:101450007F916F915F914F913F912F910F900BBEB4
+:101460000F900FBE0F901F9018951F920F920FB6FE
+:101470000F920BB60F9211242F933F934F935F93CC
+:101480006F937F938F939F93AF93BF93EF93FF934C
+:101490008091AB019091AC01892B29F0E091AB01D7
+:1014A000F091AC010995FF91EF91BF91AF919F91A0
+:1014B0008F917F916F915F914F913F912F910F90FD
+:1014C0000BBE0F900FBE0F901F9018951F920F929A
+:1014D0000FB60F920BB60F9211242F933F934F9399
+:1014E0005F936F937F938F939F93AF93BF93EF938C
+:1014F000FF938091AD019091AE01892B29F0E0918D
+:10150000AD01F091AE010995FF91EF91BF91AF91BF
+:101510009F918F917F916F915F914F913F912F910B
+:101520000F900BBE0F900FBE0F901F901895EF926B
+:10153000FF920F931F939C016091B101662379F490
+:1015400081E08093B101C901A0E0B0E08093B201D5
+:101550009093B301A093B401B093B5016EC0E09035
+:10156000B201F090B3010091B4011091B501205F78
+:10157000314FC901A0E0B0E08E199F09A00BB10B5B
+:10158000883027E0920720E0A20720E0B20728F485
+:10159000805F914FAF4FBF4F0CC0893125E192075B
+:1015A00020E0A20720E0B20720F080519E40A0403A
+:1015B000B0402091B6013091B7014091B8015091EF
+:1015C000B901280F391F4A1F5B1F2093B6013093C2
+:1015D000B7014093B8015093B901862F8F5F809374
+:1015E000B101813151F584E056954795379527959E
+:1015F0008A95D1F72E0D3F1D401F511F3093510387
+:1016000020935003809150039091510381519E404B
+:1016100050F0809150039091510380519E409093DF
+:101620005103809350031092B6011092B7011092AB
+:10163000B8011092B9011092B1011F910F91FF9062
+:10164000EF9008952091520330915303C9010895FA
+:101650002091500330915103C9010895DF93CF9336
+:101660000F92CDB7DEB781E48983109235021092D4
+:1016700034021092530310925203109251031092AD
+:10168000500382E461E0AE014F5F5F4F0E94600C47
+:10169000109254030F90CF91DF910895DF93CF9371
+:1016A00000D00F92CDB7DEB70E945E0E882309F0FE
+:1016B00087C080915403882309F449C08091350282
+:1016C000882331F08FEF809334021092350260C08E
+:1016D000809134022091AF013091B001882381F0D4
+:1016E000121613060CF45EC083E4898382E461E081
+:1016F000AE014F5F5F4F0E94600C1092540360C0B8
+:10170000121613060CF44EC082E0BE016E5F7F4FCE
+:101710000E94610E9A8180E02B81820F911D90932F
+:1017200053038093520380915203909153030E947C
+:10173000970A81E4898382E461E0AE014F5F5F4FE5
+:101740000E94600C109254038AE090E023C08091C4
+:1017500034022091AF013091B001882301F1C90119
+:1017600001969093B0018093AF018053954741F566
+:1017700085E4898382E461E0AE014F5F5F4F0E94A0
+:10178000600C8FEF80935403109235021092340254
+:1017900084E690E09093B0018093AF0111C01216DF
+:1017A00013063CF4215030403093B0012093AF0138
+:1017B00007C082E462E00E94800C8FEF80935403A4
+:1017C0000F900F900F90CF91DF91089520917100AD
+:1017D0002E7F20937100209171002D7F2093710046
+:1017E0009C0140E050E060E87EE380E090E00E94F1
+:1017F000C012203130F0822F90E040979595879568
+:10180000282F209370000895109201021092000278
+:10181000109203021092020284E690E00E94E60B0E
+:10182000E4E7F0E08081846080831092BA018081D7
+:1018300081608083808180648083089590E061115D
+:1018400091E08E7F982B90937200089590930102FF
+:1018500080930002089590930302809302020895FA
+:10186000E4E7F0E080818F70806A80830895E4E788
+:10187000F0E080818F70806D808308958091740086
+:1018800087FFFCCF089580937300E4E7F0E0808148
+:101890008F70806880830895882329F08091740078
+:1018A0008F70806C04C0809174008F70806880930A
+:1018B00074000895809173000895809171000895D7
+:1018C000982F8091BA018823E1F782E08093BA01D2
+:1018D0009E7F9093BB01ACEBB1E0FA0102C0819115
+:1018E0008D938E2F841B8617D0F31092DC016093AA
+:1018F000DD01809174008F70806A80937400089578
+:10190000982F8091BA018823E1F783E08093BA0190
+:1019100091609093BB011092FE016093FF01809152
+:1019200074008F70806A809374000895982FFA0174
+:10193000809174008E7F80937400809174008F700A
+:10194000806A809374008091740087FFFCCF9E7F33
+:1019500090937300809174008F70806880937400FE
+:101960008091740087FFFCCF80917100883189F0ED
+:1019700091E012C0808180937300809174008F7019
+:101980008068809374008091740087FFFCCF31964B
+:101990006150662379F790E0809174008F70806DBC
+:1019A000809374008091740084FFFCCF8091740058
+:1019B000816080937400892F08951F93CF93DF93E4
+:1019C000982F162FEA01809174008E7F8093740007
+:1019D000809174008F70806A80937400809174008D
+:1019E00087FFFCCF916090937300809174008F709B
+:1019F0008068809374008091740087FFFCCF809191
+:101A00007100803469F091E018C08FEF0E944C0C97
+:101A10008091740087FFFCCF8091730089931150EF
+:101A2000123098F780E00E944C0C8091740087FF80
+:101A3000FCCF80917300888390E0809174008F7058
+:101A4000806D809374008091740081608093740035
+:101A5000892FDF91CF911F9108951F920F920FB69A
+:101A60000F920BB60F9211242F933F934F935F93D6
+:101A70006F937F938F939F93AF93BF93EF93FF9356
+:101A800080917100887F803609F49FC0813670F59F
+:101A9000883209F45FC0893298F4803109F457C064
+:101AA000813138F4882309F4EEC0883009F0F3C09E
+:101AB0004EC0883109F44EC0803209F0ECC0E3C05A
+:101AC000803409F477C0813438F4803309F4DBC002
+:101AD000883309F0E0C05DC0803509F45FC0883507
+:101AE00009F44AC0883409F0D6C0CDC0883909F459
+:101AF00082C08939B0F4883709F467C0893738F46F
+:101B0000883609F462C0803709F0C5C05EC08838E5
+:101B100009F471C0803909F45EC0803809F0BBC097
+:101B20005AC0803B09F47DC0813B38F4803A09F407
+:101B300066C0883A09F0AFC074C0803C09F49EC00A
+:101B4000883C09F49BC0883B09F0A5C07BC080910C
+:101B5000BB010FC09091DC018091DD01981708F066
+:101B600092C0E92FF0E0E454FE4F80819F5F909394
+:101B7000DC01809373007BC08091FE019091730023
+:101B8000E82FF0E0E252FE4F90838F5F8093FE01DA
+:101B90007AC0809174008F70806879C08091FE0156
+:101BA00090917300E82FF0E0E252FE4F90838F5F38
+:101BB0008093FE012091FE0130E08091FF0190E0D2
+:101BC000019728173907BCF414C085E08093BA0147
+:101BD0001092FE0147C08091FE0190917300E82FA2
+:101BE000F0E0E252FE4F90838F5F8093FE018032DF
+:101BF00010F48FEF01C080E00E944C0C4CC080912B
+:101C000074008F70806C80937400E0910002F091FA
+:101C100001023097F1F18091FE016EED71E00995BE
+:101C200038C084E08093BA01E0910202F09103028F
+:101C3000309731F080E26CEB71E009958093DD0123
+:101C40001092DC019091DC01E92FF0E0E454FE4FAA
+:101C50008081809373009F5F9093DC018091DD0110
+:101C6000981728F4809174008F70806C04C0809164
+:101C700074008F708068809374000DC08091740030
+:101C80008F70806C04C0809174008F70806D809321
+:101C900074001092BA01FF91EF91BF91AF919F91A3
+:101CA0008F917F916F915F914F913F912F910F9005
+:101CB0000BBE0F900FBE0F901F9018958091BA0128
+:101CC0000895982F20E030E00AC0FB01E20FF31FD7
+:101CD000D901A252BE4F8C9180832F5F3F4F2917AD
+:101CE000A0F308951092610010926200379A35981F
+:101CF00086B1887F866086B987B18F73806487B923
+:101D00003D9810920504109266048091050497B1E5
+:101D1000E0E0F1E0E80FF11D80818F71907E892B6A
+:101D200087B9349A369A339A089533983798089534
+:101D300096B1987F982B96B9089597B18295880FA0
+:101D4000880F807C9F73982B97B9089597B18F71F6
+:101D5000907E892B87B90895349A369A089586B172
+:101D6000807408951F920F920FB60F920BB60F92C8
+:101D700011242F933F938F939F93EF93FF9334B14D
+:101D800025B1922F80E0232F30E0282B392BE091D2
+:101D90000504F0E0EE0FFF1FEB50FC4F3183208372
+:101DA00080910504833049F1843028F48130A9F012
+:101DB0008230D8F40AC0853081F1853030F1863028
+:101DC000A1F1873009F042C038C0E0916604F0E02C
+:101DD000EE0FFF1FEA5BFB4F37C0E0916604F0E0B7
+:101DE000EE0FFF1FEB56FC4F2FC0E0916604F0E0B2
+:101DF000EE0FFF1FEB54FC4F27C0E0916604F0E0AC
+:101E0000EE0FFF1FEB5AFC4F1FC0E0916604F0E09D
+:101E1000EE0FFF1FEB58FC4F17C0E0916604F0E097
+:101E2000EE0FFF1FEB52FC4F0FC0E0916604F0E095
+:101E3000EE0FFF1FEA5FFB4F07C0E0916604F0E082
+:101E4000EE0FFF1FEA5DFB4F318320838091050475
+:101E5000873041F48091660490E001968F70907015
+:101E6000809366048091050490E0019687709070DD
+:101E700080930504E091050497B1F0E0E050FF4F36
+:101E800080818F71907E892B87B9349A369AFF9121
+:101E9000EF919F918F913F912F910F900BBE0F90DB
+:101EA0000FBE0F901F901895883018F0EFEFFFEFDE
+:101EB00009C0E82FF0E0EE0FFF1FEB50FC4F019040
+:101EC000F081E02DCF0108958330D9F0843028F4DB
+:101ED000813071F0823090F40EC08530C1F08530D1
+:101EE00098F08630B9F08730C1F02FEF3FEF2DC06A
+:101EF00045E953E014C046E454E011C045EB53E01B
+:101F00000EC045E553E00BC045E753E008C045ED82
+:101F100053E005C046E054E002C046E254E060E011
+:101F200070E020E030E0FA01E20FF31F8081918140
+:101F3000680F791F2E5F3F4F20323105A1F7CB018B
+:101F400060E170E00E948B129B01C9010895FC01C1
+:101F50008FB7F8947183608353834283178216820C
+:101F6000158214828FBF0895DC014FB7F894149640
+:101F70008D919C911597892B11F4E0E025C0169660
+:101F80008D919C911797ED91FC911197E80FF91F96
+:101F9000E081019617969C938E93169712962D9139
+:101FA0003C9113978217930730F0821B930B17967F
+:101FB0009C938E93169714968D919C9115970197EB
+:101FC00015969C938E9314974FBF8E2F0895FC0106
+:101FD0004FB7F8948481958168177907B0F48681AA
+:101FE0009781860F971F978386832281338182177B
+:101FF000930720F0821B930B9783868384819581BE
+:10200000861B970B9583848302C0158214824FBF71
+:102010000895FC01CB012FB7F8942FBF268137819B
+:1020200062817381820F931F0E9477120190F08169
+:10203000E02DE80FF91F808108951F93CF93DF9360
+:10204000EC01162F4FB7F8942C813D816A817B817A
+:102050002617370798F48E819F81820F931F0E9465
+:102060007712E881F981E80FF91F10838C819D8137
+:1020700001969D838C834FBF8FEF02C04FBF80E0DE
+:10208000DF91CF911F910895FC018FB7F8948FBF16
+:102090002281338184819581281B390BC9010895E0
+:1020A000FC018FB7F8948FBF84819581892B19F03B
+:1020B00020E030E002C02FEF3FEFC9010895FC019E
+:1020C0008FB7F894158214828FBF08958CE092E048
+:1020D0000895982F809104028823E1F78FEF809371
+:1020E00004029093050289E08093060295982CB52E
+:1020F0003DB58091070290910802820F931F9BBD0E
+:102100008ABD87B7806187BF0895809106028823C2
+:1021100011F180910602823068F08091050280FF03
+:1021200002C0959A01C0959880910502869580938A
+:10213000050201C0959A8AB59BB52091070230919E
+:102140000802280F391F3BBD2ABD8091060281502D
+:102150008093060208951092040208958091090266
+:10216000882319F587B78F7D87BF4CB55DB5209162
+:102170000702309108028091070290910802240F13
+:10218000351F96958795280F391F39BD28BD86B70D
+:10219000886086BF87B7886087BF8FEF809309020A
+:1021A00010920B0210920A02089580910A028695FD
+:1021B00080930A02849B05C080910A028068809304
+:1021C0000A0280910B028F5F80930B0228B539B50C
+:1021D0008091070290910802820F931F99BD88BDDC
+:1021E00080910B02883088F060910A028CE092E0C6
+:1021F0000E941D1087B7877F87BF86B7806286BF22
+:1022000087B7806287BF109209020895CF93DF934A
+:10221000EC0180910E0290910F02892B69F0809160
+:10222000100290911102892B39F08CE092E00E940B
+:10223000B40F88838FEF01C080E0DF91CF910895C4
+:10224000EF92FF920F931F937B018C0181E00E941C
+:102250002A05C801B70196958795779567956050CF
+:102260007C4D8B409F4FA80197010E949E12309396
+:102270000802209307021F910F91FF90EF9008959D
+:1022800087B78F7E87BF87B7877F87BF87B78F7DE9
+:1022900087BF83E00E947B0584E00E947B0586E087
+:1022A0000E947B0508958CE092E064E172E040E2D8
+:1022B00050E00E94A70F0895EF92FF920F931F9393
+:1022C0006CE0E62E62E0F62EC70164E172E040E2C7
+:1022D00050E00E94A70F8D9A8C98949860E875E260
+:1022E00080E090E00E9420111092040287B78F7E58
+:1022F00087BF83E065E870E10E94700510920902D3
+:1023000087B7877F87BF0EEA10E184E0B8010E949B
+:10231000700586E0B8010E9470058EB58F7B8EBD7A
+:1023200087B7806287BFC7010E945F101F910F911E
+:10233000FF90EF900895129A1A9A139A149A159A88
+:10234000BF9ABD9ABE9A1ABA14BAE4E6F0E0808148
+:10235000887F80830895833198F590E06130C1F4DF
+:10236000FC0133E0EE0FFF1F3A95E1F7E81BF90B94
+:10237000E85FFE4FA081B18181E090E0068002C05D
+:10238000880F991F0A94E2F72C91282B2C9308951B
+:10239000FC0123E0EE0FFF1F2A95E1F7E81BF90B84
+:1023A000E85FFE4FA081B18181E090E0068002C02D
+:1023B000880F991F0A94E2F780952C9128232C937B
+:1023C0000895833110F0E0E01AC090E0FC0143E092
+:1023D000EE0FFF1F4A95E1F7E81BF90BE85FFE4F90
+:1023E00081E090E0068002C0880F991F0A94E2F70E
+:1023F0000190F081E02DE081E82309F0E1E08E2FEB
+:1024000008958331C0F490E0FC0153E0EE0FFF1F0C
+:102410005A95E1F7E81BF90BE85FFE4FA281B38103
+:1024200081E090E0068002C0880F991F0A94E2F7CD
+:102430002C91282B2C9308958331C8F490E0FC0153
+:1024400063E0EE0FFF1F6A95E1F7E81BF90BE85F09
+:10245000FE4FA281B38181E090E0068002C0880F28
+:10246000991F0A94E2F780952C9128232C930895C4
+:10247000833110F0E0E01AC090E0FC0173E0EE0F51
+:10248000FF1F7A95E1F7E81BF90BE85FFE4F81E04B
+:1024900090E0068002C0880F991F0A94E2F704803A
+:1024A000F581E02DE081E82309F0E1E08E2F089529
+:1024B000629FD001739FF001829FE00DF11D649F28
+:1024C000E00DF11D929FF00D839FF00D749FF00DB4
+:1024D000659FF00D9927729FB00DE11DF91F639F55
+:1024E000B00DE11DF91FBD01CF0111240895AA1BF4
+:1024F000BB1B51E107C0AA1FBB1FA617B70710F0EF
+:10250000A61BB70B881F991F5A95A9F78095909520
+:10251000BC01CD01089597FB092E07260AD077FD4F
+:1025200004D0E5DF06D000201AF4709561957F4F46
+:102530000895F6F7909581959F4F0895A1E21A2E80
+:10254000AA1BBB1BFD010DC0AA1FBB1FEE1FFF1F57
+:10255000A217B307E407F50720F0A21BB30BE40BA7
+:10256000F50B661F771F881F991F1A9469F76095EE
+:102570007095809590959B01AC01BD01CF010895A8
+:1025800097FB092E05260ED057FD04D0D7DF0AD0C1
+:10259000001C38F450954095309521953F4F4F4F92
+:1025A0005F4F0895F6F790958095709561957F4FF0
+:0A25B0008F4F9F4F0895F894FFCF5E
+:1025BA0000010203040506073A003B003900003A0D
+:1025CA00003B003900013A003B003900023A003B67
+:1025DA00003900033A003B003900043A003B003955
+:1025EA0000053A003B003900063A003B0039000773
+:1025FA0064006500630002340035003300073400CC
+:10260A003500330006340035003300053400350048
+:10261A00330004340035003300033400350033003E
+:10262A000234003500330001340035003300006401
+:0E263A0000650063000164006500630000009D
+:00000001FF
diff --git a/memory_map.h b/memory_map.h
new file mode 100755
index 0000000..c816575
--- /dev/null
+++ b/memory_map.h
@@ -0,0 +1,86 @@
+#ifndef _MEMORY_MAP
+#define _MEMORY_MAP
+
+// Expansio board memory map
+
+// register        access      function
+// 0x00            R           ADC0
+// 0x01            R           ADC1
+// 0x02            R           ADC2
+// 0x03            R           ADC3
+// 0x04            R           ADC4
+// 0x05            R           ADC5
+// 0x06            R           ADC6
+// 0x07            R           ADC7
+// 0x08            R           ADC0 averaged (16 samples)
+// 0x09            R           ADC1 averaged (16 samples)
+// 0x0A            R           ADC2 averaged (16 samples)
+// 0x0B            R           ADC3 averaged (16 samples)
+// 0x0C            R           ADC4 averaged (16 samples)
+// 0x0D            R           ADC5 averaged (16 samples)
+// 0x0E            R           ADC6 averaged (16 samples)
+// 0x0F            R           ADC7 averaged (16 samples)
+
+
+// 0x10            R           compass raw
+// 0x11            R           compass averaged
+
+// 0x20            W           send a byte through the serial port (FTDI)
+// 0x21            R           receive a byte through the serial port (FTDI)
+
+// 0x30            R/W         GPIO 0 configuration
+// 0x31            R/W         GPIO 0 data 
+// 0x32            R/W         GPIO 1 configuration
+// 0x33            R/W         GPIO 1 data 
+// 0x34            R/W         GPIO 2 configuration
+// 0x35            R/W         GPIO 2 data 
+// 0x36            R/W         GPIO 3 configuration
+// 0x37            R/W         GPIO 3 data 
+// 0x38            R/W         GPIO 4 configuration
+// 0x39            R/W         GPIO 4 data 
+// 0x3A            R/W         GPIO 5 configuration
+// 0x3B            R/W         GPIO 5 data 
+// 0x3C            R/W         GPIO 6 configuration
+// 0x3D            R/W         GPIO 6 data 
+// 0x3E            R/W         GPIO 7 configuration
+// 0x3F            R/W         GPIO 7 data 
+// 0x40            R/W         GPIO 8 configuration
+// 0x41            R/W         GPIO 8 data 
+// 0x41            R/W         GPIO 9 configuration
+// 0x43            R/W         GPIO 9 data 
+// 0x44            R/W         GPIO 10 configuration
+// 0x45            R/W         GPIO 10 data 
+// 0x46            R/W         GPIO 11 configuration
+// 0x47            R/W         GPIO 11 data 
+// 0x48            R/W         GPIO 12 configuration
+// 0x49            R/W         GPIO 12 data 
+// 0x4A            R/W         GPIO 13 configuration
+// 0x4B            R/W         GPIO 13 data 
+// 0x4C            R/W         GPIO 14 configuration
+// 0x4D            R/W         GPIO 14 data 
+// 0x4E            R/W         GPIO 15 configuration
+// 0x4F            R/W         GPIO 15 data 
+// 0x50            R/W         GPIO 16 configuration
+// 0x51            R/W         GPIO 16 data 
+// 0x52            R/W         GPIO 17 configuration
+// 0x53            R/W         GPIO 17 data 
+// 0x54            R/W         GPIO 18 configuration
+// 0x55            R/W         GPIO 18 data 
+
+// 0x60            W           PWM 1 duty cycle
+// 0x61            W           PWM 1 on/off
+// 0x62            W           PWM 2 duty cycle
+// 0x63            W           PWM 2 on/off
+// 0x64            W           PWM 3 duty cycle
+// 0x65            W           PWM 3 on/off
+// 0x66            W           PWM 4 duty cycle
+// 0x67            W           PWM 4 on/off
+
+// 0x70            W           D/A 1 value
+// 0x71            W           D/A 1 on/off
+// 0x72            W           D/A 2 value
+// 0x73            W           D/A 2 on/off
+
+
+
+#endif
diff --git a/patches/chipdef.h.patch b/patches/chipdef.h.patch
deleted file mode 100644
index e6a380e..0000000
--- a/patches/chipdef.h.patch
+++ /dev/null
@@ -1,18 +0,0 @@
-diff -r 407d6aac41dc uc/avrprog_boot_v0_85/chipdef.h
---- a/uc/avrprog_boot_v0_85/chipdef.h	Sun Apr 01 13:47:42 2012 +0200
-+++ b/uc/avrprog_boot_v0_85/chipdef.h	Tue Nov 10 10:52:39 2015 +0100
-@@ -12,11 +12,13 @@
- 
- #if defined (SPMCSR)
- #define SPM_REG SPMCSR
--#elif defined (SPMCR)
-+#else
-+#if defined (SPMCR)
- #define SPM_REG SPMCR
- #else
- #error "AVR processor does not provide bootloader support!"
- #endif
-+#endif
- 
- #define APP_END (FLASHEND - (BOOTSIZE * 2))
- 
diff --git a/patches/main.c.patch b/patches/main.c.patch
deleted file mode 100644
index fc1803e..0000000
--- a/patches/main.c.patch
+++ /dev/null
@@ -1,169 +0,0 @@
-diff -r 407d6aac41dc uc/avrprog_boot_v0_85/main.c
---- a/uc/avrprog_boot_v0_85/main.c	Sun Apr 01 13:47:42 2012 +0200
-+++ b/uc/avrprog_boot_v0_85/main.c	Tue Nov 10 10:52:26 2015 +0100
-@@ -51,8 +51,8 @@
- #endif
- 
- /* UART Baudrate */
-- #define BAUDRATE 19200
- // #define BAUDRATE 19200
-+#define BAUDRATE 19200
- //#define BAUDRATE 115200
- 
- /* use "Double Speed Operation" */
-@@ -167,6 +167,7 @@
- #include <avr/interrupt.h>
- #include <util/delay.h>
- 
-+#include "uart_usb.h"
- #include "chipdef.h"
- 
- uint8_t gBuffer[SPM_PAGESIZE];
-@@ -180,14 +181,20 @@
- 
- static void sendchar(uint8_t data)
- {
--	while (!(UART_STATUS & (1<<UART_TXREADY)));
--	UART_DATA = data;
-+//	while (!(UART_STATUS & (1<<UART_TXREADY)));
-+//	UART_DATA = data;
-+        uart_usb_send_byte(data);
- }
- 
- static uint8_t recvchar(void)
- {
--	while (!(UART_STATUS & (1<<UART_RXREADY)));
--	return UART_DATA;
-+	uint8_t data;
-+
-+//	while (!(UART_STATUS & (1<<UART_RXREADY)));
-+//	return UART_DATA;
-+	while(!uart_usb_is_data_available());
-+	uart_usb_receive_byte(&data);
-+	return data;
- }
- 
- static inline void eraseFlash(void)
-@@ -205,7 +212,7 @@
- static inline void recvBuffer(pagebuf_t size)
- {
- 	pagebuf_t cnt;
--	uint8_t *tmp = gBuffer;
-+		uint8_t *tmp = gBuffer;
- 
- 	for (cnt = 0; cnt < sizeof(gBuffer); cnt++) {
- 		*tmp++ = (cnt < size) ? recvchar() : 0xFF;
-@@ -331,11 +338,27 @@
- 
- static void (*jump_to_app)(void) = 0x0000;
- 
-+static void enter_app(void)
-+{
-+	cli();
-+	MCUCR = (1<<IVCE); //Enable change of interrupt vectors
-+	MCUCR = (0<<IVSEL); //Move interrupts to start flash section
-+	sei();
-+	jump_to_app();
-+} 
-+
- int main(void)
- {
- 	uint16_t address = 0;
- 	uint8_t device = 0, val;
- 
-+	MCUCR = (1<<IVCE); //Enable change of interrupt vectors
-+	MCUCR = (1<<IVSEL); //Move interrupts to boot flash section
-+
-+	uart_usb_init();
-+	uart_usb_set_baudrate(19200);
-+	uart_usb_start();
-+
- #ifdef DISABLE_WDT_AT_STARTUP
- #ifdef WDT_OFF_SPECIAL
- #warning "using target specific watchdog_off"
-@@ -346,24 +369,25 @@
- 	wdt_disable();
- #endif
- #endif
-+	sei();// enable interrupts for the software serial port.
- 	
- #ifdef START_POWERSAVE
- 	uint8_t OK = 1;
- #endif
- 
--	BLDDR  &= ~(1<<BLPNUM);		// set as Input
--	BLPORT |= (1<<BLPNUM);		// Enable pullup
-+//	BLDDR  &= ~(1<<BLPNUM);		// set as Input
-+//	BLPORT |= (1<<BLPNUM);		// Enable pullup
- 
- 	// Set baud rate
--	UART_BAUD_HIGH = (UART_CALC_BAUDRATE(BAUDRATE)>>8) & 0xFF;
--	UART_BAUD_LOW = (UART_CALC_BAUDRATE(BAUDRATE) & 0xFF);
-+//	UART_BAUD_HIGH = (UART_CALC_BAUDRATE(BAUDRATE)>>8) & 0xFF;
-+//	UART_BAUD_LOW = (UART_CALC_BAUDRATE(BAUDRATE) & 0xFF);
- 
- #ifdef UART_DOUBLESPEED
--	UART_STATUS = ( 1<<UART_DOUBLE );
-+//	UART_STATUS = ( 1<<UART_DOUBLE );
- #endif
- 
--	UART_CTRL = UART_CTRL_DATA;
--	UART_CTRL2 = UART_CTRL2_DATA;
-+//	UART_CTRL = UART_CTRL_DATA;
-+//	UART_CTRL2 = UART_CTRL2_DATA;
- 	
- #if defined(START_POWERSAVE)
- 	/*
-@@ -376,10 +400,11 @@
- 		if ((BLPIN & (1<<BLPNUM))) {
- 			// jump to main app if pin is not grounded
- 			BLPORT &= ~(1<<BLPNUM);	// set to default
--#ifdef UART_DOUBLESPEED
--			UART_STATUS &= ~( 1<<UART_DOUBLE );
--#endif
--			jump_to_app();		// Jump to application sector
-+//#ifdef UART_DOUBLESPEED
-+//			UART_STATUS &= ~( 1<<UART_DOUBLE );
-+//#endif
-+//			jump_to_app();		// Jump to application sector
-+			enter_app();
- 
- 		} else {
- 			val = recvchar();
-@@ -405,10 +430,11 @@
- 	if ((BLPIN & (1<<BLPNUM))) {
- 		// jump to main app if pin is not grounded
- 		BLPORT &= ~(1<<BLPNUM);		// set to default		
--#ifdef UART_DOUBLESPEED
--		UART_STATUS &= ~( 1<<UART_DOUBLE );
--#endif
--		jump_to_app();			// Jump to application sector
-+//#ifdef UART_DOUBLESPEED
-+//		UART_STATUS &= ~( 1<<UART_DOUBLE );
-+//#endif
-+//		jump_to_app();			// Jump to application sector
-+		enter_app();
- 	}
- 
- #elif defined(START_WAIT)
-@@ -416,13 +442,17 @@
- 	uint16_t cnt = 0;
- 
- 	while (1) {
--		if (UART_STATUS & (1<<UART_RXREADY))
--			if (UART_DATA == START_WAIT_UARTCHAR)
-+//		if (UART_STATUS & (1<<UART_RXREADY))
-+//			if (UART_DATA == START_WAIT_UARTCHAR)
-+//				break;
-+		if(uart_usb_is_data_available())
-+			if(recvchar()==START_WAIT_UARTCHAR)
- 				break;
- 
- 		if (cnt++ >= WAIT_VALUE) {
- 			BLPORT &= ~(1<<BLPNUM);		// set to default
--			jump_to_app();			// Jump to application sector
-+//			jump_to_app();			// Jump to application sector
-+			enter_app();
- 		}
- 
- 		_delay_ms(10);
diff --git a/patches/makefile.patch b/patches/makefile.patch
deleted file mode 100644
index 960cf15..0000000
--- a/patches/makefile.patch
+++ /dev/null
@@ -1,77 +0,0 @@
-diff -r 407d6aac41dc uc/avrprog_boot_v0_85/makefile
---- a/uc/avrprog_boot_v0_85/makefile	Sun Apr 01 13:47:42 2012 +0200
-+++ b/uc/avrprog_boot_v0_85/makefile	Tue Nov 10 10:52:17 2015 +0100
-@@ -37,7 +37,7 @@
- # user defined values
- 
- # MCU name
--MCU = atmega8
-+# MCU = atmega8
- ## MCU = atmega16
- ## MCU = atmega162
- ## MCU = atmega169
-@@ -46,7 +46,7 @@
- ## MCU = atmega64
- ## MCU = atmega644
- ## MCU = atmega644p
--## MCU = atmega128
-+MCU = atmega128
- ## MCU = at90can128
- 
- ################## BOOTLOADER ######################
-@@ -59,15 +59,16 @@
- #/* Select Boot Size in Words (select one, comment out the others) */
- ## NO! BOOTSIZE=128
- ## NO! BOOTSIZE=256
--BOOTSIZE=512
--##BOOTSIZE=1024
-+## BOOTSIZE=512
-+## BOOTSIZE=1024
- ## BOOTSIZE=2048
-+BOOTSIZE=4096
- 
- # /* Select if bootloader should include the inverrupt-vectors 
- # when selecting 'no' here, the bootloader must not use
- # any interrupts and the modified linker-scripts are used. */
--##BOOTINTVEC=yes
--BOOTINTVEC=no
-+BOOTINTVEC=yes
-+## BOOTINTVEC=no
- 
- ##
- ifeq ($(MCU), atmega8)
-@@ -266,7 +267,7 @@
- 
- 
- # List C source files here. (C dependencies are automatically generated.)
--SRC = $(TARGET).c
-+SRC = $(TARGET).c uart_usb.c
- 
- 
- # List Assembler source files here.
-@@ -292,7 +293,7 @@
- 
- # List any extra directories to look for include files here.
- #     Each directory must be seperated by a space.
--EXTRAINCDIRS =
-+EXTRAINCDIRS = ../../../include
- 
- 
- # Compiler flag to set the C Standard level.
-@@ -303,7 +304,7 @@
- CSTANDARD = -std=gnu99
- 
- # Place -D or -U options here
--CDEFS = -DBOOTSIZE=$(BOOTSIZE)
-+CDEFS = -DBOOTSIZE=$(BOOTSIZE) -DF_CPU=16000000
- 
- # Place -I options here
- CINCS =
-@@ -405,7 +406,7 @@
- AVRDUDE_PORT = usb    # programmer connected to serial device
- #AVRDUDE_PORT = /dev/ttyS0    # programmer connected to serial device
- 
--AVRDUDE_WRITE_FLASH = -U flash:w:$(TARGET).hex -U lfuse:w:0xe4:m -U hfuse:w:0xda:m
-+AVRDUDE_WRITE_FLASH = -U flash:w:$(TARGET).hex -U lfuse:w:0xff:m -U hfuse:w:0xd8:m
- #AVRDUDE_WRITE_EEPROM = -U eeprom:w:$(TARGET).eep
-
diff --git a/patches/uart_usb.c b/patches/uart_usb.c
deleted file mode 100644
index 1c007d5..0000000
--- a/patches/uart_usb.c
+++ /dev/null
@@ -1,241 +0,0 @@
-#include <avr/io.h>
-#include <avr/interrupt.h>
-#include "uart_usb.h"
-
-#define UART_USB_DEFAULT_BAUDRATE 9600
-
-#define UART_USB_RX_BUFFER_SIZE   0x20
-
-#define UART_USB_TX_PORT          PORTD
-#define UART_USB_TX_DDR           DDRD
-#define UART_USB_TX_PIN           PD5 
-
-#define UART_USB_RX_PORT          PORTD
-#define UART_USB_RX_DDR           DDRD
-#define UART_USB_RX_PORTIN        PIND
-#define UART_USB_RX_PIN           PD4 
-
-// uartsw transmit status and data variables
-volatile uint8_t uart_usb_tx_busy;
-volatile uint8_t uart_usb_tx_data;
-volatile uint8_t uart_usb_tx_bit_num;
-
-// baud rate common to transmit and receive
-volatile uint16_t uart_usb_baudrate_div;
-
-// uartsw receive status and data variables
-volatile uint8_t uart_usb_rx_busy;
-volatile uint8_t uart_usb_rx_data;
-volatile uint8_t uart_usb_rx_bit_num;
-
-/* rx buffer */
-unsigned char uart_usb_rx_data_buffer[UART_USB_RX_BUFFER_SIZE];
-unsigned char uart_usb_rx_read_ptr;
-unsigned char uart_usb_rx_write_ptr;
-unsigned char uart_usb_rx_num_data;
-
-/* private functions */
-
-/* interrupt handlers */
-ISR(TIMER1_CAPT_vect)//RX
-{
-  uint16_t capture;
-  // clear ICP interrupt flag
-  TIFR|=(1<<ICF1);
-  
-  if(!uart_usb_rx_busy)
-  {
-    // disable input capture interrutps
-    TIMSK&=~(1<<TICIE1);
-    capture=TCNT1+uart_usb_baudrate_div + uart_usb_baudrate_div/2;
-    // schedule data bit sampling 1.5 bit periods from now
-    OCR1BH=(capture>>8)&0xFF;
-    OCR1BL=capture&0xFF;
-    // clear OC1B interrupt flag
-    TIFR|=(1<<OCF1B);
-    // enable OC1B interrupt
-    TIMSK|=(1<<OCIE1B);
-    // set start bit flag
-    uart_usb_rx_busy = 0x01;
-    // reset bit counter
-    uart_usb_rx_bit_num = 0;
-    // reset data
-    uart_usb_rx_data = 0;
-  }
-}
-
-ISR(TIMER1_COMPB_vect)//RX
-{
-  uint16_t capture;
-
-  // clear OC1B interrupt flag
-  TIFR|=(1<<OCF1B);
-  // shift data byte to make room for new bit
-  uart_usb_rx_data = uart_usb_rx_data>>1;
-
-  if(UART_USB_RX_PORTIN&(1<<UART_USB_RX_PIN))
-    uart_usb_rx_data |= 0x80;
-
-  // increment bit counter
-  uart_usb_rx_bit_num++;
-  // schedule next bit sample
-  capture=OCR1B+uart_usb_baudrate_div;
-  OCR1BH=(capture>>8)&0xFF;
-  OCR1BL=capture&0xFF;
-
-  // check if we have a full byte
-  if(uart_usb_rx_bit_num >= 8)
-  {
-    // save data in receive buffer
-    uart_usb_rx_data_buffer[uart_usb_rx_write_ptr]=uart_usb_rx_data;
-    uart_usb_rx_write_ptr=(uart_usb_rx_write_ptr+1)%UART_USB_RX_BUFFER_SIZE;
-    uart_usb_rx_num_data++;
-    // disable OC1B interrupt
-    TIMSK&=~(1<<OCIE1B);
-    // enable ICP interrupt
-    TIMSK|=(1<<TICIE1);
-    // clear start bit flag
-    uart_usb_rx_busy = 0x00;
-  }
-}
-
-ISR(TIMER1_COMPA_vect)//TX
-{
-  uint16_t capture;
-
-  // clear OC1B interrupt flag
-  TIFR|=(1<<OCF1A);
-  if(uart_usb_tx_bit_num)
-  {
-    if(uart_usb_tx_bit_num>1)
-    {
-      // transmit data bits (inverted, LSB first)
-      if((uart_usb_tx_data&0x01))
-        UART_USB_TX_PORT|=(1<<UART_USB_TX_PIN);
-      else
-        UART_USB_TX_PORT&=~(1<<UART_USB_TX_PIN);
-      // shift bits down
-      uart_usb_tx_data = uart_usb_tx_data>>1;
-    }
-    else
-      UART_USB_TX_PORT|=(1<<UART_USB_TX_PIN);
-    // schedule the next bit
-    capture=OCR1A+uart_usb_baudrate_div;
-    OCR1AH=(capture>>8)&0xFF;
-    OCR1AL=capture&0xFF;
-    // count down
-    uart_usb_tx_bit_num--;
-  }
-  else
-  {
-    // enable OC1A interrupt
-    TIMSK&=~(1<<OCIE1A);
-    uart_usb_tx_busy = 0x00;
-  }
-}
-
-/* public functions */
-void uart_usb_init(void)
-{
-  // configure GPIO ports
-  UART_USB_TX_DDR|=(1<<UART_USB_TX_PIN);// output
-  UART_USB_RX_DDR&=~(1<<UART_USB_RX_PIN);//input
-  // set input to 0
-  UART_USB_RX_PORT&=~(1<<UART_USB_RX_PIN);
-  // initialize baud rate
-  uart_usb_set_baudrate(UART_USB_DEFAULT_BAUDRATE);
-
-  // setup the transmitter
-  uart_usb_tx_busy = 0x00;
-  TIMSK&=~(1<<OCIE1A);
-
-  // setup the receiver
-  uart_usb_rx_busy = 0x00;
-  TIMSK&=~(1<<OCIE1B);
-  // trigger on falling edge 
-  TCCR1B&=~(1<<ICES1);
-  // enable ICP interrupt
-  TIMSK|=(1<<TICIE1);
-
-  /* initlaize buffer variables */
-  uart_usb_rx_read_ptr=0;
-  uart_usb_rx_write_ptr=0;
-  uart_usb_rx_num_data=0;
-}
-
-void uart_usb_start(void)
-{
-  TIMSK&=~(1<<OCIE1A);
-  TIMSK&=~(1<<OCIE1B);
-  // clear ICP interrupt flag
-  TIFR|=(1<<ICF1);
-  TIMSK|=(1<<TICIE1);
-}
-
-void uart_usb_stop(void)
-{
-  // disable interrupts
-  TIMSK&=~(1<<OCIE1A);
-  TIMSK&=~(1<<OCIE1B);
-  TIMSK&=~(1<<TICIE1);
-}
-
-void uart_usb_set_baudrate(uint32_t baudrate)
-{
-  TCCR1B&=0xF8;
-  TCCR1B|=0x01;
-  // calculate division factor for requested baud rate, and set it
-  uart_usb_baudrate_div = (uint16_t)((F_CPU+(baudrate/2L))/(baudrate*1L));
-}
-
-void uart_usb_send_byte(uint8_t data)
-{
-  uint16_t capture;
-
-  // wait until uart is ready
-  while(uart_usb_tx_busy);
-  // set busy flag
-  uart_usb_tx_busy = 0x01;
-  // save data
-  uart_usb_tx_data = data;
-  // set number of bits (+1 for stop bit)
-  uart_usb_tx_bit_num = 9;
-
-  UART_USB_TX_PORT&=~(1<<UART_USB_TX_PIN);
-
-  capture=TCNT1+uart_usb_baudrate_div;
-  OCR1AH=(capture>>8)&0xFF;
-  OCR1AL=capture&0xFF;
-  // clear interrupts
-  TIFR|=(1<<OCF1A);
-  // enable OC1A interrupt
-  TIMSK|=(1<<OCIE1A);
-}
-
-uint8_t uart_usb_is_sending(void)
-{
-  return uart_usb_tx_busy;
-}
-
-uint8_t uart_usb_receive_byte(uint8_t* data)
-{
-  // make sure we have a receive buffer
-  if(uart_usb_rx_num_data>0)
-  {
-    *data=uart_usb_rx_data_buffer[uart_usb_rx_read_ptr];
-    uart_usb_rx_read_ptr=(uart_usb_rx_read_ptr+1)%UART_USB_RX_BUFFER_SIZE;
-    uart_usb_rx_num_data--;
-    // make sure we have data
-    return 0x01;
-  }
-  else
-    return 0x00;
-}
-
-uint8_t uart_usb_is_data_available(void)
-{
-  if(uart_usb_rx_num_data>0)
-    return 0x01;
-  else
-    return 0x00;
-}
diff --git a/port128.h b/port128.h
new file mode 100755
index 0000000..41617aa
--- /dev/null
+++ b/port128.h
@@ -0,0 +1,98 @@
+/*! \file port128.h \brief Additional include for Mega128 to define individual port pins. */
+//*****************************************************************************
+//
+// File Name	: 'port128.h'
+// Title		: Additional include for Mega128 to define individual port pins
+// Author		: Pascal Stang
+// Created		: 11/18/2002
+// Revised		: 11/18/2002
+// Version		: 1.1
+// Target MCU	: Atmel AVR series
+// Editor Tabs	: 4
+//
+//	Description : This include file contains additional port and pin defines
+//		to help make code transparently compatible with the mega128.  As in
+//		the other AVR processors, using defines like PD2 to denote PORTD, pin2
+//		is not absolutely necessary but enhances readability.  The mega128 io.h
+//		no longer defines individual pins of ports (like PD2 or PA5, for
+//		example).  Instead, port pins are defines universally for all ports as
+//		PORT0 through PORT7.  However, this renaming causes a code-portability
+//		issue from non-mega128 AVRs to the mega128.  Including this file will
+//		replace the missing defines.
+//
+// This code is distributed under the GNU Public License
+//		which can be found at http://www.gnu.org/licenses/gpl.txt
+//
+//*****************************************************************************
+
+#ifndef PORT128_H
+#define PORT128_H
+
+// Mega128 individual port defines
+// (using these is technically unnecessary but improves code compatibility to
+//  the mega128 from other AVR processors where these values were still defined
+//  in the io.h for that processor)
+
+// PORTA
+#define PA0		PORT0
+#define PA1		PORT1
+#define PA2		PORT2
+#define PA3		PORT3
+#define PA4		PORT4
+#define PA5		PORT5
+#define PA6		PORT6
+#define PA7		PORT7
+// PORTB
+#define PB0		PORT0
+#define PB1		PORT1
+#define PB2		PORT2
+#define PB3		PORT3
+#define PB4		PORT4
+#define PB5		PORT5
+#define PB6		PORT6
+#define PB7		PORT7
+// PORTC
+#define PC0		PORT0
+#define PC1		PORT1
+#define PC2		PORT2
+#define PC3		PORT3
+#define PC4		PORT4
+#define PC5		PORT5
+#define PC6		PORT6
+#define PC7		PORT7
+// PORTD
+#define PD0		PORT0
+#define PD1		PORT1
+#define PD2		PORT2
+#define PD3		PORT3
+#define PD4		PORT4
+#define PD5		PORT5
+#define PD6		PORT6
+#define PD7		PORT7
+// PORTE
+#define PE0		PORT0
+#define PE1		PORT1
+#define PE2		PORT2
+#define PE3		PORT3
+#define PE4		PORT4
+#define PE5		PORT5
+#define PE6		PORT6
+#define PE7		PORT7
+// PORTF
+#define PF0		PORT0
+#define PF1		PORT1
+#define PF2		PORT2
+#define PF3		PORT3
+#define PF4		PORT4
+#define PF5		PORT5
+#define PF6		PORT6
+#define PF7		PORT7
+// PORTG
+#define PG0		PORT0
+#define PG1		PORT1
+#define PG2		PORT2
+#define PG3		PORT3
+#define PG4		PORT4
+#define PG5		PORT5
+
+#endif
diff --git a/ports.c b/ports.c
new file mode 100755
index 0000000..bbaa594
--- /dev/null
+++ b/ports.c
@@ -0,0 +1,105 @@
+#include <avr/io.h>
+#include "ports.h"
+#include "global.h"
+
+TGPIO gpio_bits[NUM_GPIO]={{&DDRA,&PORTA,&PINA,0},
+                           {&DDRA,&PORTA,&PINA,1},
+                           {&DDRA,&PORTA,&PINA,2},
+						   {&DDRA,&PORTA,&PINA,3},
+						   {&DDRA,&PORTA,&PINA,4},
+						   {&DDRA,&PORTA,&PINA,5},
+						   {&DDRA,&PORTA,&PINA,6},
+						   {&DDRA,&PORTA,&PINA,7},
+						   {&DDRG,&PORTG,&PING,2},
+						   {&DDRC,&PORTC,&PINC,7},
+						   {&DDRC,&PORTC,&PINC,6},
+						   {&DDRC,&PORTC,&PINC,5},
+						   {&DDRC,&PORTC,&PINC,4},
+						   {&DDRC,&PORTC,&PINC,3},
+						   {&DDRC,&PORTC,&PINC,2},
+						   {&DDRC,&PORTC,&PINC,1},
+						   {&DDRC,&PORTC,&PINC,0},
+						   {&DDRG,&PORTG,&PING,1},
+						   {&DDRG,&PORTG,&PING,0}};
+
+void init_ports(void)
+{
+  //auxiliar LED
+  sbi(DDRE,2);
+  sbi(PORTE,2);
+
+  // configure as outputs the pwm pins
+  sbi(DDRE,3);
+  sbi(DDRE,4);
+  sbi(DDRE,5);
+  sbi(DDRB,7);
+
+  // configure as outputs the DA pins
+  sbi(DDRB,5);
+  sbi(DDRB,6);
+
+  // general purpose input/output
+  // all inputs by default
+  DDRA=0x00;
+  DDRC=0x00;
+  DDRG=DDRG&0xF8;
+  
+}
+
+void config_port(unsigned char port_id,unsigned char dir)
+{
+  if(port_id>=0 && port_id<NUM_GPIO)
+  {
+     if(dir==OUTPUT)// configure as an output
+	    sbi(*(gpio_bits[port_id].dir_reg),gpio_bits[port_id].bit);
+	 else// configure as an input
+	    cbi(*(gpio_bits[port_id].dir_reg),gpio_bits[port_id].bit);
+  }
+}
+
+unsigned char get_port_config(unsigned char port_id)
+{
+  unsigned char dir;
+
+  if(port_id>=0 && port_id<NUM_GPIO)
+  {
+     dir=(*(gpio_bits[port_id].dir_reg)&(0x01<<gpio_bits[port_id].bit));
+	 if(dir==0x00)
+	   return INPUT;
+     else
+       return OUTPUT;
+  }
+  else
+    return INPUT;
+}
+
+void set_port(unsigned char port_id)
+{
+  if(port_id>=0 && port_id<NUM_GPIO)
+  {
+    sbi(*(gpio_bits[port_id].write_reg),gpio_bits[port_id].bit);
+  }
+}
+
+void clear_port(unsigned char port_id)
+{
+  if(port_id>=0 && port_id<NUM_GPIO)
+  {
+    cbi(*(gpio_bits[port_id].write_reg),gpio_bits[port_id].bit);
+  }
+}
+
+unsigned char read_port(unsigned char port_id)
+{
+  unsigned char value;
+  if(port_id>=0 && port_id<NUM_GPIO)
+  {
+    value=((*(gpio_bits[port_id].read_reg))&(0x01<<gpio_bits[port_id].bit));
+	if(value==0x00)
+	  return 0x00;
+    else
+      return 0x01;
+  }
+  else
+    return 0x00;
+}
diff --git a/ports.h b/ports.h
new file mode 100755
index 0000000..45cdfb9
--- /dev/null
+++ b/ports.h
@@ -0,0 +1,24 @@
+#ifndef _PORTS_H
+#define _PORTS_H
+
+#define NUM_GPIO 19
+
+#define INPUT 0x00
+#define OUTPUT 0x01
+
+typedef struct
+{
+  unsigned char *dir_reg;
+  unsigned char *write_reg;
+  unsigned char *read_reg;
+  unsigned char bit;
+}TGPIO;
+
+void init_ports(void);
+void config_port(unsigned char port_id,unsigned char dir);
+unsigned char get_port_config(unsigned char port_id);
+void set_port(unsigned char port_id);
+void clear_port(unsigned char port_id);
+unsigned char read_port(unsigned char port_id);
+
+#endif
diff --git a/src/adc.c b/src/adc.c
deleted file mode 100644
index 6615ac5..0000000
--- a/src/adc.c
+++ /dev/null
@@ -1,181 +0,0 @@
-#include "adc.h"
-#include "mem.h"
-#include "ports.h"
-
-// number of channels to convert
-#define NUM_CH 8
-// number of samples to average
-#define ADC_MAX_NUM_SAMPLES 16
-
-// private variables
-volatile uint8_t adc_sample_period_ms;
-// current channel
-volatile uint8_t adc_current_ch;
-// channel data
-volatile int16_t adc_data[NUM_CH];
-// averaged channel data
-volatile int16_t adc_ch_data[NUM_CH][ADC_MAX_NUM_SAMPLES];
-volatile uint8_t adc_current_sample;
-volatile uint8_t adc_num_samples;
-volatile uint8_t adc_running;
-volatile uint8_t adc_prescaler_mask;
-
-/* private functions */
-void adc_set_channel(uint8_t ch_id)
-{
-  ADMUX&=0xF8;
-  ADMUX|= (ch_id&0x07);
-}
-
-void adc_start_conv(void)
-{
-  ADCSRA|=(1<<ADSC);
-}
-
-uint8_t adc_is_conversion_done(void)
-{
-  if(ADCSRA&(1<<ADIF))
-    return 0x01;
-  else
-    return 0x00;
-}
-
-uint8_t adc_is_period_done(void)
-{
-  if(TIFR&(1<<OCF2))
-    return 0x01;
-  else
-    return 0x00;
-}
-
-/* public functions */
-void adc_init(void)
-{
-  // configure the analog inputs
-  DDRF = 0x00;
-  PORTF = 0x00;  
-
-  ADMUX = (1<<REFS0);// use AVCC as reference, Right justified, channel 0
-  ADCSRA = (1<<ADPS2) | (1<<ADPS1) | (1<<ADPS0); // free running mode disabled, interrupts enabled, prescaler to 128
-
-  // clear any pending interrupt
-  ADCSRA|=(1<<ADIF);
-
-  // set the initial channel to convert
-  adc_current_ch=0;
-  adc_current_sample=0;
-  adc_running=0;
-  adc_num_samples=ADC_MAX_NUM_SAMPLES;
-  ram_data[ADC_NUM_SAMPLES]=ADC_MAX_NUM_SAMPLES;
-  adc_sample_period_ms=0x01;
-  ram_data[ADC_SAMPLE_PERIOD]=0x01;
-  adc_set_sample_period(adc_sample_period_ms);
-
-  // configure the timer 2 to perform periodic conversions (1 ms period)
-  TCCR2=(1<<WGM21);// CTC mode, no output, prescaler to 0 (no clock source)
-  TCNT2=0x00;// start from 0
-  TIMSK=0x00;// interrupts not enabled
-}
-
-void adc_start(void)
-{
-  // enable the ADC 
-  ADCSRA|=(1<<ADEN);
-  // enable the timer 2 interrupts
-  TCNT2=0x00;// start from 0
-  TIMSK=0x00;// interrupts not enabled
-  // clear interrupts
-  TIFR|=(1<<OCF2);
-  TIFR|=(1<<TOV2);
-  // configure the timer prescaler and count value
-  adc_running=0x01;
-  adc_set_sample_period(adc_sample_period_ms);
-  ram_data[ADC_CONTROL]|=0x04;
-}
-
-void adc_stop(void)
-{
-  TCCR2&=0xF8;// set prescaler to 0 (no clock source)
-  // disable the ADC
-  ADCSRA&=~(1<<ADEN);
-  adc_running=0x00;
-  ram_data[ADC_CONTROL]&=0xFB;
-}
-
-void adc_set_num_samples(uint8_t num)
-{
-  if(num>ADC_MAX_NUM_SAMPLES)
-    adc_num_samples=ADC_MAX_NUM_SAMPLES;
-  else
-  {
-    if(num<=0)
-      adc_num_samples=1;
-    else
-      adc_num_samples=num;
-  }
-  if(adc_current_sample>num)
-    adc_current_sample=0;
-  ram_data[ADC_NUM_SAMPLES]=num;
-}
-
-void adc_set_sample_period(uint8_t time_ms)
-{
-  uint16_t prescaler_values[5]={1,8,64,256,1024};
-  uint16_t compare_value;
-  uint8_t i;
-
-  for(i=0;i<5;i++)
-  {
-    compare_value=(((F_CPU/1000)*time_ms)/(prescaler_values[i]*NUM_CH))-1;
-    if(compare_value<256)
-    {
-      OCR2=(uint8_t)compare_value;
-      if(adc_running)
-      {
-        TCCR2&=0xF8;
-        TCCR2|=(i+1);
-      }
-      else
-        adc_prescaler_mask=i+1;
-      break;
-    }
-  }
-  ram_data[ADC_SAMPLE_PERIOD]=time_ms;
-}
-
-void adc_loop(void)
-{
-  uint8_t i;
-  uint16_t data;
-
-  if(adc_is_period_done())
-  {
-    TIFR|=(1<<OCF2);// clear interrupt flag
-    TIFR|=(1<<TOV2);
-    TCNT2=0x00;// start from 0
-    // start a new conversion
-    adc_set_channel(adc_current_ch);
-    adc_start_conv();
-  }
-  else
-  {
-    if(adc_is_conversion_done())
-    {
-      ADCSRA|=(1<<ADIF);// clear interrupt flag
-      data=(ADCL | (ADCH<<8));
-      ram_data[ADC_CHANNEL0_L+adc_current_ch*2]=data%256;
-      ram_data[ADC_CHANNEL0_H+adc_current_ch*2]=data/256;
-      adc_ch_data[adc_current_ch][adc_current_sample]=data;
-      // compute the average for the current channel
-      data=0;
-      for(i=0;i<adc_num_samples;i++)
-        data+=adc_ch_data[adc_current_ch][i];
-      data=data/adc_num_samples;
-      ram_data[ADC_AVG_CHANNEL0_L+adc_current_ch*2]=data%256;
-      ram_data[ADC_AVG_CHANNEL0_H+adc_current_ch*2]=data/256;
-      if(adc_current_ch==NUM_CH-1)// last channel
-        adc_current_sample=(adc_current_sample+1)%adc_num_samples;
-      adc_current_ch=(adc_current_ch+1)%NUM_CH;
-    }
-  }
-}
diff --git a/src/compass.c b/src/compass.c
deleted file mode 100644
index ffb186f..0000000
--- a/src/compass.c
+++ /dev/null
@@ -1,252 +0,0 @@
-#include "compass.h"
-#include "i2c.h"
-#include "mem.h"
-#include "ports.h"
-
-#define COMPASS_MAX_NUM_SAMPLES 16
-
-typedef enum {idle,get_data,get_data_delay,read_data,start_cal,calibrating,calibration_delay,stop_cal} compass_states_t;
-
-/* private variables */
-volatile uint8_t compass_current_sample;
-volatile uint8_t compass_num_samples;
-
-volatile uint8_t compass_start_cal;
-volatile uint8_t compass_stop_cal;
-volatile uint8_t compass_stop_op;
-volatile uint8_t compass_start_op;
-volatile compass_states_t compass_state;
-// time control variables
-volatile uint8_t compass_delay_done;
-
-/* private functions */
-void compass_avrg(uint16_t heading)
-{
-  static unsigned long int new_average,first_value;
-  unsigned long int diff=0;
-
-  if(compass_current_sample==0)
-  {
-    compass_current_sample++;
-    first_value=(long int)heading;
-  }  
-  else
-  {
-    diff=heading+3600-first_value;
-    if(diff<1800)
-      diff=diff+3600;
-    else if(diff>5400) 
-      diff=diff-3600;
-    new_average=new_average+diff;
-    compass_current_sample++;
-    if(compass_current_sample==compass_num_samples)
-    {
-      new_average=new_average/(compass_num_samples-1);
-      new_average=new_average+first_value;
-      if(new_average>3600)
-	new_average-=3600;
-      ram_data[COMPASS_AVG_HEADING_VAL_L]=new_average%256;
-      ram_data[COMPASS_AVG_HEADING_VAL_H]=new_average/256;
-      new_average=0;
-      compass_current_sample=0; 
-    }
-  }
-}
-
-void compass_start_time_delay(uint8_t delay_ms)
-{
-  TCNT0=0x00;// reset counter
-  OCR0=delay_ms*16;// set count value
-  TCCR0&=0xF8;
-  TCCR0|=0x07;// enable clock
-  compass_delay_done=0x00;
-}
-
-uint8_t compass_is_delay_done(void)
-{
-  return compass_delay_done;
-}
-
-/* interrupt handlers */
-ISR(TIMER0_COMP_vect)
-{
-  compass_delay_done=0x01; 
-  // disable clock
-  TCCR0&=0xF8;
-}
-
-/* public functions */
-void compass_init(void)
-{
-  /* initialize private variables */
-  compass_start_cal=0;
-  compass_stop_cal=0;
-  compass_stop_op=0;
-  compass_start_op=0;
-  compass_delay_done=0x00;
-  compass_state=idle;
-  compass_current_sample=0;
-  compass_num_samples=COMPASS_MAX_NUM_SAMPLES;
-  ram_data[COMPASS_NUM_SAMPLES]=COMPASS_MAX_NUM_SAMPLES;
-
-  /* use timer 0 to control the operation delay */
-  TCCR0=(1<<WGM01);//campare mode, output disable, prescaler 0
-  ASSR=0x00;// disable assynchronous operation
-  TIMSK=(1<<OCIE0);// enable interrupts
-  OCR0=0xFF;
-  TCNT0=0x00;
-
-  /* initialize i2c peripheral */
-  i2c_init(100);
-}
-
-void compass_start(void)
-{
-  compass_stop_op=0;
-  compass_start_op=1;
-  ram_data[COMPASS_CONTROL]|=0x40;
-}
-
-void compass_stop(void)
-{
-  compass_stop_op=1;
-  compass_start_op=0;
-}
-
-void compass_start_calibration(void)
-{
-  compass_start_cal=1;
-  compass_stop_cal=0;
-}
-
-void compass_stop_calibration(void)
-{
-  compass_start_cal=0;
-  compass_stop_cal=1;
-}
-
-void compass_set_num_samples(uint8_t num)
-{
-  if(num>COMPASS_MAX_NUM_SAMPLES)
-    compass_num_samples=COMPASS_MAX_NUM_SAMPLES;
-  else if(num<=2)
-    compass_num_samples=2;
-  else
-    compass_num_samples=num;
-  ram_data[COMPASS_NUM_SAMPLES]=compass_num_samples;
-}
-
-void compass_loop(void)
-{
-  uint8_t cmd,heading[2];
-  unsigned short int compass_heading;
-  static compass_states_t prev_state=idle;
-
-  switch(compass_state)
-  {
-    case idle: if(compass_start_op==1)
-               {
-                 compass_state=get_data;
-                 compass_start_op=0;
-               }
-               else
-               {
-                 if(compass_start_cal==1)
-                 {
-                   compass_start_cal=0;
-                   compass_state=start_cal;
-                   prev_state=idle;
-                 }
-                 else
-                   compass_state=idle;
-               }
-               break;
-    case get_data: if(i2c_get_state()==I2C_IDLE)
-                   {
-                     cmd=COMPASS_HEADING;
-                     i2c_master_send(COMPASS_ADDR,1,&cmd);
-                     compass_start_time_delay(10);
-                     compass_state=get_data_delay;
-                   }
-                   else
-                     compass_state=get_data;
-                   break;
-    case get_data_delay: if(compass_is_delay_done()==1)
-                         {
-                           if(i2c_get_state()==I2C_IDLE)
-                           {
-                             i2c_master_receive(COMPASS_ADDR,2);
-                             compass_state=read_data;
-                           }
-                           else
-                             compass_state=get_data_delay;
-                         }
-                         else
-                           compass_state=get_data_delay;
-                         break;
-    case read_data: if(i2c_get_state()==I2C_IDLE)
-                    {
-                      i2c_get_data(2,heading);
-                      compass_heading=heading[1]+(heading[0]<<8);
-                      ram_data[COMPASS_HEADING_VAL_L]=heading[1];
-                      ram_data[COMPASS_HEADING_VAL_H]=heading[0];
-                      compass_avrg(compass_heading);
-                      if(compass_stop_op==1)
-                      {
-                        compass_stop_op=0;
-                        compass_state=idle;
-                        ram_data[COMPASS_CONTROL]&=0xBF;
-                      }
-                      else
-                      {
-                        if(compass_start_cal==1)
-                        {
-                          compass_start_cal=0;
-                          compass_state=start_cal;
-                          prev_state=get_data;
-                        }
-                        else
-                          compass_state=get_data;
-                      }
-                    }
-                    else
-                      compass_state=read_data;
-                    break;
-    case start_cal: if(i2c_get_state()==I2C_IDLE)
-                    {
-                      cmd=COMPASS_START_CAL;
-                      i2c_master_send(COMPASS_ADDR,1,&cmd);
-                      ram_data[COMPASS_CONTROL]|=0x80;
-                      compass_state=calibrating;
-                    }
-                    else
-                      compass_state=start_cal; 
-                    break;
-    case calibrating: if(compass_stop_cal==1)
-                      {
-                        compass_state=stop_cal;
-                        compass_stop_cal=0;
-                      }
-                      else
-                        compass_state=calibrating;
-                      break;
-    case stop_cal: if(i2c_get_state()==I2C_IDLE)
-                   {
-                     cmd=COMPASS_STOP_CAL;
-                     i2c_master_send(COMPASS_ADDR,1,&cmd);
-                     compass_start_time_delay(20);
-                     compass_state=calibration_delay;
-                   }
-                   else
-                     compass_state=stop_cal;
-                   break;
-    case calibration_delay: if(compass_is_delay_done()==1)
-                            {
-                              compass_state=prev_state;
-                              ram_data[COMPASS_CONTROL]&=0x7F;
-                            }
-                            else
-                              compass_state=calibration_delay;
-                            break;
-  }
-}
diff --git a/src/dac.c b/src/dac.c
deleted file mode 100644
index 77d9f10..0000000
--- a/src/dac.c
+++ /dev/null
@@ -1,102 +0,0 @@
-#include "dac.h"
-#include "mem.h"
-
-#define         DAC_TOP_VALUE         ((uint32_t)1600)
-#define         DAC_PRESCALE_MASK     1
-#define         DAC_MAX_VOLTAGE       ((uint32_t)40960) //5V in 3|13 fixed point format
-
-/* private variables */
-uint8_t dac_running;
-
-/* public functions */
-void dac_init(void)
-{
-  // configure as outputs the DA pins
-  DDRB|=0x60;
-
-  /* initialize internal variables */
-  dac_running=0;
-  OCR1AH=0x00;
-  OCR1AL=0x00;
-  OCR1BH=0x00;
-  OCR1BL=0x00;
-  /* set the top value */
-  ICR1H=(DAC_TOP_VALUE>>8)&0xFF;
-  ICR1L=(DAC_TOP_VALUE)&0xFF;
-  
-  /* configure the timer 3 */
-  TCNT1H=0x00;
-  TCNT1L=0x00;
-  /* set the timer mode */
-  TCCR1A=(1<<WGM11);// all three channels in fast PWM mode, output disabled
-  TCCR1B=(1<<WGM13)|(1<<WGM12);// no clock source, fast PWM mode
-}
-
-void dac_start(void)
-{
-  TCNT1H=0x00;
-  TCNT1L=0x00;
-  /* set the prescaler value */
-  TCCR1B&=0xF8;
-  TCCR1B|=DAC_PRESCALE_MASK;
-  dac_running=0x01;
-  ram_data[DAC_CONTROL]|=0x10;
-}
-
-void dac_stop(void)
-{
-  /* set the prescaler to 0 (no clock source) */
-  TCCR1B&=0xF8;
-  dac_running=0x00;
-  ram_data[DAC_CONTROL]&=0xEF;
-}
-
-void dac_enable_channel(dac_ch_t ch)
-{
-  switch(ch)
-  {
-    case dac0: TCCR1A|=(1<<COMA1);
-               ram_data[DAC_CONTROL]|=0x40;
-               break;
-    case dac1: TCCR1A|=(1<<COMB1);
-               ram_data[DAC_CONTROL]|=0x80;
-               break;
-  }
-}
-
-void dac_disable_channel(dac_ch_t ch)
-{
-  switch(ch)
-  {
-    case dac0: TCCR1A&=~(1<<COMA1);
-               ram_data[DAC_CONTROL]&=0xBF;
-               break;
-    case dac1: TCCR1A&=~(1<<COMB1);
-               ram_data[DAC_CONTROL]|=0x7F;
-               break;
-  }
-}
-
-void dac_set_voltage(dac_ch_t ch,uint16_t voltage)
-{
-  uint32_t compare_value;
-
-  if(voltage>DAC_MAX_VOLTAGE)
-    voltage=DAC_MAX_VOLTAGE;
-  compare_value=(voltage*DAC_TOP_VALUE)/DAC_MAX_VOLTAGE;
-
-  switch(ch)
-  {
-    case dac0: OCR1AH=(compare_value>>8)&0xFF;
-               OCR1AL=(compare_value)&0xFF;
-               ram_data[DAC_CH0_VOLTAGE_L]=voltage%256;
-               ram_data[DAC_CH0_VOLTAGE_H]=voltage/256;
-               break;
-    case dac1: OCR1BH=(compare_value>>8)&0xFF;
-               OCR1BL=(compare_value)&0xFF;
-               ram_data[DAC_CH1_VOLTAGE_L]=voltage%256;
-               ram_data[DAC_CH1_VOLTAGE_H]=voltage/256;
-               break;
-  }
-}
-
diff --git a/src/dyn_common.c b/src/dyn_common.c
deleted file mode 100644
index 076333f..0000000
--- a/src/dyn_common.c
+++ /dev/null
@@ -1,226 +0,0 @@
-#include "dyn_common.h"
-#include "dyn_slave_se.h"
-#include "mem.h"
-#include "ports.h"
-#include "adc.h"
-#ifdef _PWM
-#include "pwm.h"
-#endif
-#ifdef _DAC
-#include "dac.h"
-#endif
-#include "compass.h"
-#ifdef _UART_TTL
-#include "uart_ttl.h"
-#endif
-#ifdef _UART_USB
-#include "uart_usb.h"
-#endif
-
-uint8_t do_write(uint8_t address,uint8_t length,uint8_t *data)
-{
-  uint8_t i,num=0;
-  uint8_t low_byte=0x00;
-
-  for(i=address;i<address+length;i++)
-  {
-    /* dynamixel interface */
-    if(i==ID)
-      dyn_slave_se_set_id(data[num]);
-    else if(i==Baud_Rate)
-      dyn_slave_se_set_baudrate(data[num]);
-    /* gpio interface */
-    else if(i>=GPIO0_config && i<=GPIO18_data)
-    {
-      if((i%2)==0)// config register
-        config_port((i-GPIO0_config)>>1,data[num]);
-      else// data register
-      {
-        if(data[num]==0x00)
-          clear_port((i-GPIO0_data)>>1);
-        else
-          set_port((i-GPIO0_data)>>1);
-      }
-    }
-    else if(i==LED)
-    { 
-      if(data[num]==0x00)
-        clear_led();
-      else
-        set_led();
-    }
-    /* ADC interface */
-    else if(i==ADC_CONTROL)
-    {
-      if(data[num]&0x01)
-        adc_start();
-      else if(data[num]&0x02)
-        adc_stop();
-    }
-    else if(i==ADC_NUM_SAMPLES)
-      adc_set_num_samples(data[num]);
-    else if(i==ADC_SAMPLE_PERIOD)
-      adc_set_sample_period(data[num]);
-    #ifdef _PWM
-    /* PWM interface */
-    else if(i==PWM_CONTROL)
-    {
-      if(data[num]&0x01)
-        pwm_start();
-      else if(data[num]&0x02)
-        pwm_stop();
-    }
-    else if(i==PWM_ENABLE)
-    {
-      if(data[num]&0x01)
-        pwm_enable_ch(pwm0);
-      else if(data[num]&0x10)
-        pwm_disable_ch(pwm0);
-      if(data[num]&0x02)
-        pwm_enable_ch(pwm1);
-      else if(data[num]&0x20)
-        pwm_disable_ch(pwm1);
-      if(data[num]&0x04)
-        pwm_enable_ch(pwm2);
-      else if(data[num]&0x40)
-        pwm_disable_ch(pwm2);
-      if(data[num]&0x08)
-        pwm_enable_ch(pwm3);
-      else if(data[num]&0x80)
-        pwm_disable_ch(pwm3);
-    }  
-    else if(i==PWM_FREQ_L)
-      low_byte=data[num];
-    else if(i==PWM_FREQ_H)
-      pwm_set_frequency(low_byte+data[num]*256);
-    else if(i>=PWM_CH0_DUTY && i<=PWM_CH3_DUTY) 
-      pwm_set_duty_cycle((pwm_id_t)(i-PWM_CH0_DUTY),data[num]);
-    #endif
-    #ifdef _DAC
-    /* dac interface */
-    else if(i==DAC_CONTROL)
-    {
-      if(data[num]&0x01)
-        dac_start();
-      else if(data[num]&0x02)
-        dac_stop();
-    }
-    else if(i==DAC_ENABLE)
-    {
-      if(data[num]&0x01)
-        dac_enable_channel(dac0);
-      else if(data[num]&0x04)
-        dac_disable_channel(dac0);
-      if(data[num]&0x02)
-        dac_enable_channel(dac1);
-      else if(data[num]&0x08)
-        dac_disable_channel(dac1);
-    }
-    else if(i==DAC_CH0_VOLTAGE_L)
-      low_byte=data[num];
-    else if(i==DAC_CH0_VOLTAGE_H)
-      dac_set_voltage(dac0,low_byte+data[num]*256);
-    else if(i==DAC_CH1_VOLTAGE_L)
-      low_byte=data[num];
-    else if(i==DAC_CH1_VOLTAGE_H)
-      dac_set_voltage(dac1,low_byte+data[num]*256);
-    #endif
-    /* compass interface */
-    else if(i==COMPASS_CONTROL)
-    {
-      if(data[num]&0x01)
-        compass_start();
-      else if(data[num]&0x02)
-        compass_stop();
-      else if(data[num]&0x04)
-        compass_start_calibration();
-      else if(data[num]&0x08)
-        compass_stop_calibration();
-    }
-    else if(i==COMPASS_NUM_SAMPLES)
-      compass_set_num_samples(data[num]);
-    #ifdef _UART_TTL
-    /* uart TTL interface */
-    else if(i==UART_TTL_CONTROL)
-    {
-      if(data[num]&0x01)
-        uart_ttl_start();
-      else if(data[num]&0x02)
-        uart_ttl_stop();
-    }
-    else if(i==UART_TTL_TX_DATA)
-      uart_ttl_send_byte(data[num]);
-    else if(i==UART_TTL_BAUDRATE_L)
-      low_byte=data[num];
-    else if(i==UART_TTL_BAUDRATE_H)
-      uart_ttl_set_baudrate(low_byte+data[num]*256);
-    #endif
-    #ifdef _UART_USB
-    /* uart TTL interface */
-    else if(i==UART_USB_CONTROL)
-    {
-      if(data[num]&0x01)
-        uart_usb_start();
-      else if(data[num]&0x02)
-        uart_usb_stop();
-    }
-    else if(i==UART_USB_TX_DATA)
-      uart_usb_send_byte(data[num]);
-    else if(i==UART_USB_BAUDRATE_L)
-      low_byte=data[num];
-    else if(i==UART_USB_BAUDRATE_H)
-      uart_usb_set_baudrate(low_byte+data[num]*256);
-    #endif
-    num++;
-  }
-
-  return 0x01;
-}
-
-uint8_t do_read(uint8_t address,uint8_t length,uint8_t **data)
-{
-  uint8_t i=0;
-
-  /* perform operations before reading the ram */
-  for(i=address;i<address+length;i++)
-  {
-    if(i>=GPIO0_config && i<=GPIO18_data)
-    {
-      if((i%2)!=0) // data register
-        read_port((i-GPIO0_config)>>1);
-    }
-    else if(i==SWITCHES)
-      get_selector_value();
-    #ifdef _UART_TTL
-    else if(i==UART_TTL_CONTROL)
-    {
-      if(uart_ttl_is_data_available())
-        ram_data[UART_TTL_CONTROL]|=0x80;
-      else
-        ram_data[UART_TTL_CONTROL]&=0x7F;
-      if(uart_ttl_is_sending())
-        ram_data[UART_TTL_CONTROL]|=0x40;
-      else
-        ram_data[UART_TTL_CONTROL]&=0xBF;
-    }
-    else if(i==UART_TTL_RX_DATA)
-      uart_ttl_receive_byte(&ram_data[UART_TTL_RX_DATA]);
-    #endif
-    #ifdef _UART_USB
-    else if(i==UART_USB_CONTROL)
-    {
-      if(uart_usb_is_data_available())
-        ram_data[UART_USB_CONTROL]|=0x80;
-      else
-        ram_data[UART_USB_CONTROL]&=0x7F;
-      if(uart_usb_is_sending())
-        ram_data[UART_USB_CONTROL]|=0x40;
-      else
-        ram_data[UART_USB_CONTROL]&=0xBF;
-    }
-    else if(i==UART_USB_RX_DATA)
-      uart_usb_receive_byte(&ram_data[UART_USB_RX_DATA]);
-    #endif
-  }
-  return ram_read(address,length,data); 
-}
diff --git a/src/dyn_slave_diff.c b/src/dyn_slave_diff.c
deleted file mode 100644
index 6b7206a..0000000
--- a/src/dyn_slave_diff.c
+++ /dev/null
@@ -1,427 +0,0 @@
-#include <avr/interrupt.h>
-#include <avr/io.h>
-#include "dyn_slave_diff.h"
-#include "mem.h"
-
-/* private variables */
-uint8_t dyn_slave_diff_id;
-uint8_t dyn_slave_diff_data[128];
-uint8_t dyn_slave_diff_num_rx_bytes;
-uint8_t dyn_slave_diff_num_tx_bytes;
-uint8_t dyn_slave_diff_packet_ready;
-uint8_t dyn_slave_diff_send_done;
-uint8_t dyn_slave_diff_error;
-uint8_t dyn_slave_diff_tmp_data[RAM_SIZE];
-uint8_t dyn_slave_diff_tmp_address;
-uint8_t dyn_slave_diff_tmp_length;
-uint8_t dyn_slave_diff_reg_pending;
-uint8_t dyn_slave_diff_sync_read_pending;
-uint8_t dyn_slave_diff_sync_read_previous;
-uint8_t dyn_slave_diff_bulk_read_pending;
-uint8_t dyn_slave_diff_bulk_read_previous;
-
-inline void dyn_slave_diff_set_rx(void)
-{
-  PORTB &= 0xEF;
-}
-
-inline void dyn_slave_diff_set_tx(void)
-{
-  PORTB |= 0x10;
-}
-
-/* interrupt handlers */
-ISR(USART0_TX_vect)
-{
-  if(dyn_slave_diff_num_tx_bytes==dyn_slave_diff_data[3]+4)
-  {
-    dyn_slave_diff_set_rx();
-    dyn_slave_diff_send_done=1;
-  }
-  else
-  {
-    UDR0=dyn_slave_diff_data[dyn_slave_diff_num_tx_bytes];
-    dyn_slave_diff_num_tx_bytes++;
-  }
-}
-
-ISR(USART0_RX_vect)
-{
-  static uint8_t length;
-
-  cli();// disable any other interrupt
-  dyn_slave_diff_data[dyn_slave_diff_num_rx_bytes]=UDR0;
-  switch(dyn_slave_diff_num_rx_bytes)
-  {
-    case 0: if(dyn_slave_diff_data[dyn_slave_diff_num_rx_bytes]==0xFF)
-              dyn_slave_diff_num_rx_bytes++;
-            break;
-    case 1: if(dyn_slave_diff_data[dyn_slave_diff_num_rx_bytes]==0xFF)
-              dyn_slave_diff_num_rx_bytes++;
-            else
-              dyn_slave_diff_num_rx_bytes--;
-            break;
-    case 2: dyn_slave_diff_num_rx_bytes++;
-            break;
-    case 3: length=dyn_slave_diff_data[dyn_slave_diff_num_rx_bytes]+3;
-            dyn_slave_diff_num_rx_bytes++;
-            break;
-    default: if(dyn_slave_diff_num_rx_bytes==length)
-             {
-               dyn_slave_diff_num_rx_bytes=0;
-               dyn_slave_diff_packet_ready=1;
-             }
-             else
-               dyn_slave_diff_num_rx_bytes++;
-             break;
-  }
-  sei();// enable all interrutps
-}
-
-/* private functions */
-uint8_t dyn_slave_diff_is_packet_ready(void)
-{
-  if(dyn_slave_diff_packet_ready==0x01)
-  {
-    dyn_slave_diff_packet_ready=0x00;
-    return 0x01;
-  }
-  else
-    return 0x00;
-}
-
-uint8_t dyn_slave_diff_check_id(void)
-{
-  if(dyn_slave_diff_id==dyn_slave_diff_data[2] || dyn_slave_diff_data[2]==0xFE)
-    return 0x01;
-  else
-  { 
-    dyn_slave_diff_num_rx_bytes=0;
-    return 0x00;
-  }
-}
-
-uint8_t dyn_slave_diff_check_checksum(void)
-{
-  uint8_t i,cs=0x00;
-
-  for(i=2;i<dyn_slave_diff_data[3]+4;i++)
-    cs+=dyn_slave_diff_data[i];
-  if(cs==0xFF)
-    return 0x01;
-  else 
-    return 0x00;
-}
-
-inline uint8_t dyn_slave_diff_get_instruction(void)
-{
-  return dyn_slave_diff_data[4];
-}
-
-inline uint8_t dyn_slave_diff_get_received_id(void)
-{
-  return dyn_slave_diff_data[2];
-}
-
-// read operation
-inline uint8_t dyn_slave_diff_get_address(void)
-{
-  return dyn_slave_diff_data[5];
-}
-
-inline uint8_t dyn_slave_diff_get_read_length(void)
-{
-  return dyn_slave_diff_data[6];
-}
-
-// write operation
-inline uint8_t dyn_slave_diff_get_write_length(void)
-{
-  return dyn_slave_diff_data[3]-3;
-}
-
-inline uint8_t *dyn_slave_diff_get_write_data(void)
-{
-  return &dyn_slave_diff_data[6];
-}
-
-// sync read operation
-uint8_t dyn_slave_diff_sync_read_id_present(void)
-{
-  uint8_t i,num;
-
-  num=dyn_slave_diff_data[3]-4;
-  for(i=0;i<num;i++)
-  {
-    if(dyn_slave_diff_data[7+i]==dyn_slave_diff_id)
-    {
-      if(i==0)
-        return 0x00;
-      else
-        return dyn_slave_diff_data[6+i];
-    }
-  }
-  return 0xFF;
-}
-
-// sync write operation
-uint8_t dyn_slave_diff_sync_write_id_present(uint8_t **data)
-{
-  uint8_t i,num;
-
-  num=(dyn_slave_diff_data[3]-4)/(dyn_slave_diff_data[6]+1);
-  for(i=0;i<num;i++)
-  {
-    if(dyn_slave_diff_data[7+i*(dyn_slave_diff_data[6]+1)]==dyn_slave_diff_id)
-    {
-      (*data)=&dyn_slave_diff_data[7+i*(dyn_slave_diff_data[6]+1)+1];
-      return 0x01;
-    }
-  }
-  return 0x00;
-}
-
-// bulk read operation
-uint8_t dyn_slave_diff_bulk_read_id_present(uint8_t *address,uint8_t *length)
-{
-  uint8_t i,num;
-
-  num=(dyn_slave_diff_data[3]-2)/3;
-  for(i=0;i<num;i++)
-  {
-    if(dyn_slave_diff_data[5+i*3]==dyn_slave_diff_id)
-    {
-      (*address)=dyn_slave_diff_data[6+i*3];
-      (*length)=dyn_slave_diff_data[7+i*3];
-      if(i==0)
-        return 0x00;
-      else
-        return dyn_slave_diff_data[5+(i-1)*3];
-    }
-  }
-  return 0xFF;
-}
-
-// bulk write operation
-uint8_t dyn_slave_diff_bulk_write_id_present(uint8_t *address,uint8_t *length,uint8_t **data)
-{
-  uint8_t i,num;
-
-  num=dyn_slave_diff_data[3]+4;
-  for(i=5;i<num;)
-  {
-    if(dyn_slave_diff_data[i]==dyn_slave_diff_id)
-    {
-      (*address)=dyn_slave_diff_data[i+1];
-      (*length)=dyn_slave_diff_data[i+2];
-      (*data)=&dyn_slave_diff_data[i+3];
-      return 0x01;
-    }
-    else
-      i+=dyn_slave_diff_data[i+2]+3;
-  }
-  return 0x00;
-}
-
-void dyn_slave_diff_send_status(uint8_t error,uint8_t length, uint8_t *data)
-{
-  uint8_t i,cs=0;
-
-  if(dyn_slave_diff_data[2]!=0xFE)
-  {
-    if(dyn_slave_diff_data[4]==INST_PING || ((dyn_slave_diff_data[4]==INST_READ || 
-       dyn_slave_diff_data[4]==INST_SYNC_READ || dyn_slave_diff_data[4]==INST_BULK_READ) && 
-       ram_data[Status_Return_Level]!=0x00) || ram_data[Status_Return_Level]==0x02) 
-    dyn_slave_diff_data[0]=0xFF;
-    dyn_slave_diff_data[1]=0xFF;
-    dyn_slave_diff_data[2]=dyn_slave_diff_id;
-    cs+=dyn_slave_diff_id;
-    dyn_slave_diff_data[3]=length+2;
-    cs+=length+2;
-    dyn_slave_diff_data[4]=error;
-    cs+=error;
-    for(i=0;i<length;i++)
-    {
-      dyn_slave_diff_data[5+i]=data[i];
-      cs+=data[i];
-    }
-    dyn_slave_diff_data[5+i]=~cs;
-    // set in tex mode
-    dyn_slave_diff_set_tx();
-    // start transmission
-    dyn_slave_diff_num_tx_bytes=1;
-    UDR0=dyn_slave_diff_data[0];
-  }
-}
-
-inline uint8_t dyn_slave_diff_is_send_done(void)
-{
-  return dyn_slave_diff_send_done;
-}
-
-/* public functions */
-void dyn_slave_diff_init(uint8_t baudrate,uint8_t id)
-{
-  DDRE=DDRE|0x01;// TX (0) are outputs 0x01=00000001
-  DDRE=DDRE&0xFD;// RX(1) is an input  0xFE=11111101
-
-  DDRB=DDRB|0x10;// DIR (4) are outputs 0x10=00010000
-  // configure the ports to receive data
-  dyn_slave_diff_set_rx();
-
-  // initialize the rs485 ports
-  UCSR0A = (1<<U2X);// double USART transmission speed
-  dyn_slave_diff_set_baudrate(baudrate);
-  UCSR0A|=0x40;// clear any pending interrupt
-  UCSR0B = (1<<RXEN)|(1<<TXEN)|(1<<RXCIE)|(1<<TXCIE);
-  UCSR0C = (1<<UCSZ1)|(1<< UCSZ0); // 8 bit data, no parity, 1 stop bit
-
-  dyn_slave_diff_set_id(id);
-  // initialize private variables
-  dyn_slave_diff_num_tx_bytes=0;
-  dyn_slave_diff_num_rx_bytes=0;
-  dyn_slave_diff_packet_ready=0;
-  dyn_slave_diff_send_done=0;
-  dyn_slave_diff_error=NO_ERROR;
-  dyn_slave_diff_tmp_address=0x00;
-  dyn_slave_diff_tmp_length=0x00;
-  dyn_slave_diff_reg_pending=0x00;
-  dyn_slave_diff_sync_read_pending=0x00;
-  dyn_slave_diff_bulk_read_pending=0x00;
-}
-
-void dyn_slave_diff_set_baudrate(uint8_t baudrate)
-{
-  UBRR0H = 0;
-  UBRR0L = baudrate;
-}
-
-void dyn_slave_diff_set_id(uint8_t id)
-{
-  dyn_slave_diff_id=id;
-}
-
-void dyn_slave_diff_loop(void)
-{
-  static uint8_t *data,i;
-
-  if(dyn_slave_diff_is_packet_ready())
-  {
-    if(dyn_slave_diff_check_id())
-    {
-      if(dyn_slave_diff_check_checksum())
-      {
-        switch(dyn_slave_diff_get_instruction())
-        {
-          case INST_PING: dyn_slave_diff_send_status(dyn_slave_diff_error|NO_ERROR,0x00,0x00000000);
-                          break;
-          case INST_READ: if(do_read(dyn_slave_diff_get_address(),dyn_slave_diff_get_read_length(),&data))
-                            dyn_slave_diff_send_status(dyn_slave_diff_error|NO_ERROR,dyn_slave_diff_get_read_length(),data);
-                          else
-                            dyn_slave_diff_send_status(dyn_slave_diff_error|INSTRUCTION_ERROR,0x00,0x00000000);
-                          break;
-          case INST_WRITE: if(do_write(dyn_slave_diff_get_address(),dyn_slave_diff_get_write_length(),dyn_slave_diff_get_write_data()))
-                             dyn_slave_diff_send_status(dyn_slave_diff_error|NO_ERROR,0x00,0x00000000);
-                           else 
-                             dyn_slave_diff_send_status(dyn_slave_diff_error|INSTRUCTION_ERROR,0x00,0x00000000);
-                           break;
-          case INST_REG_WRITE: dyn_slave_diff_tmp_address=dyn_slave_diff_get_address();
-                               dyn_slave_diff_tmp_length=dyn_slave_diff_get_write_length();
-                               data=dyn_slave_diff_get_write_data();
-                               for(i=0;i<dyn_slave_diff_tmp_length;i++)
-                                 dyn_slave_diff_tmp_data[i]=data[i];
-                               dyn_slave_diff_reg_pending=0x01;
-                               dyn_slave_diff_send_status(dyn_slave_diff_error|NO_ERROR,0x00,0x00000000);
-                               break;
-          case INST_ACTION: if(dyn_slave_diff_reg_pending)
-                            {
-                              if(do_write(dyn_slave_diff_tmp_address,dyn_slave_diff_tmp_length,dyn_slave_diff_tmp_data))
-                                dyn_slave_diff_send_status(dyn_slave_diff_error|NO_ERROR,0x00,0x00000000);
-                            }
-                            else
-                              dyn_slave_diff_send_status(dyn_slave_diff_error|INSTRUCTION_ERROR,0x00,0x00000000);
-                            break;
-          case INST_RESET:
-                           break;
-          case INST_SYNC_READ: dyn_slave_diff_sync_read_previous=dyn_slave_diff_sync_read_id_present();
-                               if(dyn_slave_diff_sync_read_previous!=0xFF)
-                               {
-                                 if(dyn_slave_diff_sync_read_previous==0x00)// first device on the list
-                                 {
-                                   if(do_read(dyn_slave_diff_get_address(),dyn_slave_diff_get_read_length(),&data))
-                                     dyn_slave_diff_send_status(dyn_slave_diff_error|NO_ERROR,dyn_slave_diff_get_read_length(),data);
-                                   else
-                                     dyn_slave_diff_send_status(dyn_slave_diff_error|INSTRUCTION_ERROR,0x00,0x00000000);
-                                 }
-                                 else// sync read pending
-                                 {
-                                   dyn_slave_diff_tmp_address=dyn_slave_diff_get_address();
-                                   dyn_slave_diff_tmp_length=dyn_slave_diff_get_read_length();
-                                   dyn_slave_diff_sync_read_pending=0x01;
-                                 }
-                               }
-                               break;
-          case INST_SYNC_WRITE: if(dyn_slave_diff_sync_write_id_present(&data))
-                                  do_write(dyn_slave_diff_get_address(),dyn_slave_diff_get_read_length(),data);
-                                break;
-          case INST_BULK_READ: dyn_slave_diff_bulk_read_previous=dyn_slave_diff_bulk_read_id_present(&dyn_slave_diff_tmp_address,&dyn_slave_diff_tmp_length);
-                               if(dyn_slave_diff_bulk_read_previous!=0xFF)
-                               {
-                                 if(dyn_slave_diff_bulk_read_previous==0x00)// first device on the list
-                                 {
-                                   if(do_read(dyn_slave_diff_tmp_address,dyn_slave_diff_tmp_length,&data))
-                                     dyn_slave_diff_send_status(dyn_slave_diff_error|NO_ERROR,dyn_slave_diff_tmp_length,data);
-                                   else
-                                     dyn_slave_diff_send_status(dyn_slave_diff_error|INSTRUCTION_ERROR,0x00,0x00000000);
-                                 }
-                                 else// sync read pending
-                                   dyn_slave_diff_bulk_read_pending=0x01;
-                               }
-                               break;
-          case INST_BULK_WRITE: if(dyn_slave_diff_bulk_write_id_present(&dyn_slave_diff_tmp_address,&dyn_slave_diff_tmp_length,&data))
-                                  do_write(dyn_slave_diff_tmp_address,dyn_slave_diff_tmp_length,data);
-                                break;
-          default: dyn_slave_diff_send_status(dyn_slave_diff_error|INSTRUCTION_ERROR,0x00,0x00000000);
-                   break;
-        }
-      }
-      else
-        dyn_slave_diff_send_status(dyn_slave_diff_error|CHECKSUM_ERROR,0x00,0x00000000);
-    }
-    else
-    {
-      if(dyn_slave_diff_sync_read_pending)
-      {
-        if(dyn_slave_diff_get_received_id()==dyn_slave_diff_sync_read_previous)
-        {
-          dyn_slave_diff_sync_read_pending=0x00;
-          if(do_read(dyn_slave_diff_tmp_address,dyn_slave_diff_tmp_length,&data))
-            dyn_slave_diff_send_status(dyn_slave_diff_error|NO_ERROR,dyn_slave_diff_tmp_length,data);
-          else
-            dyn_slave_diff_send_status(dyn_slave_diff_error|INSTRUCTION_ERROR,0x00,0x00000000); 
-        }
-      }
-      if(dyn_slave_diff_bulk_read_pending)
-      {
-        if(dyn_slave_diff_get_received_id()==dyn_slave_diff_bulk_read_previous)
-        {
-          dyn_slave_diff_bulk_read_pending=0x00;
-          if(do_read(dyn_slave_diff_tmp_address,dyn_slave_diff_tmp_length,&data))
-            dyn_slave_diff_send_status(dyn_slave_diff_error|NO_ERROR,dyn_slave_diff_tmp_length,data);
-          else
-            dyn_slave_diff_send_status(dyn_slave_diff_error|INSTRUCTION_ERROR,0x00,0x00000000); 
-        }
-      }
-    }
-  }
-}
-
-void dyn_slave_diff_set_error(uint8_t error)
-{
-  dyn_slave_diff_error|=error;
-}
-
-void dyn_slave_diff_clear_error(void)
-{
-  dyn_slave_diff_error=NO_ERROR;
-}
diff --git a/src/dyn_slave_se.c b/src/dyn_slave_se.c
deleted file mode 100644
index 14432c0..0000000
--- a/src/dyn_slave_se.c
+++ /dev/null
@@ -1,431 +0,0 @@
-#include <avr/interrupt.h>
-#include <avr/io.h>
-#include "dyn_slave_se.h"
-#include "mem.h"
-
-/* private variables */
-uint8_t dyn_slave_se_id;
-uint8_t dyn_slave_se_data[128];
-uint8_t dyn_slave_se_num_rx_bytes;
-uint8_t dyn_slave_se_num_tx_bytes;
-uint8_t dyn_slave_se_packet_ready;
-uint8_t dyn_slave_se_send_done;
-uint8_t dyn_slave_se_error;
-uint8_t dyn_slave_se_tmp_data[RAM_SIZE];
-uint8_t dyn_slave_se_tmp_address;
-uint8_t dyn_slave_se_tmp_length;
-uint8_t dyn_slave_se_reg_pending;
-uint8_t dyn_slave_se_sync_read_pending;
-uint8_t dyn_slave_se_sync_read_previous;
-uint8_t dyn_slave_se_bulk_read_pending;
-uint8_t dyn_slave_se_bulk_read_previous;
-
-inline void dyn_slave_se_set_rx(void)
-{
-  PORTD &= 0xBF;
-  PORTD |= 0x80;
-}
-
-inline void dyn_slave_se_set_tx(void)
-{
-  PORTD &= 0x7F;
-  PORTD |= 0x40;
-}
-
-/* interrupt handlers */
-ISR(USART1_TX_vect)
-{
-  if(dyn_slave_se_num_tx_bytes==dyn_slave_se_data[3]+4)
-  {
-    dyn_slave_se_set_rx();
-    dyn_slave_se_send_done=1;
-  }
-  else
-  {
-    UDR1=dyn_slave_se_data[dyn_slave_se_num_tx_bytes];
-    dyn_slave_se_num_tx_bytes++;
-  }
-}
-
-ISR(USART1_RX_vect)
-{
-  static uint8_t length;
-
-  cli();// disable any other interrupt
-  dyn_slave_se_data[dyn_slave_se_num_rx_bytes]=UDR1;
-  switch(dyn_slave_se_num_rx_bytes)
-  {
-    case 0: if(dyn_slave_se_data[dyn_slave_se_num_rx_bytes]==0xFF)
-              dyn_slave_se_num_rx_bytes++;
-            break;
-    case 1: if(dyn_slave_se_data[dyn_slave_se_num_rx_bytes]==0xFF)
-              dyn_slave_se_num_rx_bytes++;
-            else
-              dyn_slave_se_num_rx_bytes--;
-            break;
-    case 2: dyn_slave_se_num_rx_bytes++;
-            break;
-    case 3: length=dyn_slave_se_data[dyn_slave_se_num_rx_bytes]+3;
-            dyn_slave_se_num_rx_bytes++;
-            break;
-    default: if(dyn_slave_se_num_rx_bytes==length)
-             {
-               dyn_slave_se_num_rx_bytes=0;
-               dyn_slave_se_packet_ready=1;
-             }
-             else
-               dyn_slave_se_num_rx_bytes++;
-             break;
-  }
-  sei();// enable all interrutps
-}
-
-/* private functions */
-uint8_t dyn_slave_se_is_packet_ready(void)
-{
-  if(dyn_slave_se_packet_ready==0x01)
-  {
-    dyn_slave_se_packet_ready=0x00;
-    return 0x01;
-  }
-  else
-    return 0x00;
-}
-
-uint8_t dyn_slave_se_check_id(void)
-{
-  if(dyn_slave_se_id==dyn_slave_se_data[2] || dyn_slave_se_data[2]==0xFE)
-    return 0x01;
-  else
-  { 
-    dyn_slave_se_num_rx_bytes=0;
-    return 0x00;
-  }
-}
-
-uint8_t dyn_slave_se_check_checksum(void)
-{
-  uint8_t i,cs=0x00;
-
-  for(i=2;i<dyn_slave_se_data[3]+4;i++)
-    cs+=dyn_slave_se_data[i];
-  if(cs==0xFF)
-    return 0x01;
-  else 
-    return 0x00;
-}
-
-inline uint8_t dyn_slave_se_get_instruction(void)
-{
-  return dyn_slave_se_data[4];
-}
-
-inline uint8_t dyn_slave_se_get_received_id(void)
-{
-  return dyn_slave_se_data[2];
-}
-
-// read operation
-inline uint8_t dyn_slave_se_get_address(void)
-{
-  return dyn_slave_se_data[5];
-}
-
-inline uint8_t dyn_slave_se_get_read_length(void)
-{
-  return dyn_slave_se_data[6];
-}
-
-// write operation
-inline uint8_t dyn_slave_se_get_write_length(void)
-{
-  return dyn_slave_se_data[3]-3;
-}
-
-inline uint8_t *dyn_slave_se_get_write_data(void)
-{
-  return &dyn_slave_se_data[6];
-}
-
-// sync read operation
-uint8_t dyn_slave_se_sync_read_id_present(void)
-{
-  uint8_t i,num;
-
-  num=dyn_slave_se_data[3]-4;
-  for(i=0;i<num;i++)
-  {
-    if(dyn_slave_se_data[7+i]==dyn_slave_se_id)
-    {
-      if(i==0)
-        return 0x00;
-      else
-        return dyn_slave_se_data[6+i];
-    }
-  }
-  return 0xFF;
-}
-
-// sync write operation
-uint8_t dyn_slave_se_sync_write_id_present(uint8_t **data)
-{
-  uint8_t i,num;
-
-  num=(dyn_slave_se_data[3]-4)/(dyn_slave_se_data[6]+1);
-  for(i=0;i<num;i++)
-  {
-    if(dyn_slave_se_data[7+i*(dyn_slave_se_data[6]+1)]==dyn_slave_se_id)
-    {
-      (*data)=&dyn_slave_se_data[7+i*(dyn_slave_se_data[6]+1)+1];
-      return 0x01;
-    }
-  }
-  return 0x00;
-}
-
-// bulk read operation
-uint8_t dyn_slave_se_bulk_read_id_present(uint8_t *address,uint8_t *length)
-{
-  uint8_t i,num;
-
-  num=(dyn_slave_se_data[3]-2)/3;
-  for(i=0;i<num;i++)
-  {
-    if(dyn_slave_se_data[5+i*3]==dyn_slave_se_id)
-    {
-      (*address)=dyn_slave_se_data[6+i*3];
-      (*length)=dyn_slave_se_data[7+i*3];
-      if(i==0)
-        return 0x00;
-      else
-        return dyn_slave_se_data[5+(i-1)*3];
-    }
-  }
-  return 0xFF;
-}
-
-// bulk write operation
-uint8_t dyn_slave_se_bulk_write_id_present(uint8_t *address,uint8_t *length,uint8_t **data)
-{
-  uint8_t i,num;
-
-  num=dyn_slave_se_data[3]+4;
-  for(i=5;i<num;)
-  {
-    if(dyn_slave_se_data[i]==dyn_slave_se_id)
-    {
-      (*address)=dyn_slave_se_data[i+1];
-      (*length)=dyn_slave_se_data[i+2];
-      (*data)=&dyn_slave_se_data[i+3];
-      return 0x01;
-    }
-    else
-      i+=dyn_slave_se_data[i+2]+3;
-  }
-  return 0x00;
-}
-
-void dyn_slave_se_send_status(uint8_t error,uint8_t length, uint8_t *data)
-{
-  uint8_t i,cs=0;
-
-  if(dyn_slave_se_data[2]!=0xFE)
-  {
-    if(dyn_slave_se_data[4]==INST_PING || ((dyn_slave_se_data[4]==INST_READ || 
-       dyn_slave_se_data[4]==INST_SYNC_READ || dyn_slave_se_data[4]==INST_BULK_READ) && 
-       ram_data[Status_Return_Level]!=0x00) || ram_data[Status_Return_Level]==0x02) 
-    dyn_slave_se_data[0]=0xFF;
-    dyn_slave_se_data[1]=0xFF;
-    dyn_slave_se_data[2]=dyn_slave_se_id;
-    cs+=dyn_slave_se_id;
-    dyn_slave_se_data[3]=length+2;
-    cs+=length+2;
-    dyn_slave_se_data[4]=error;
-    cs+=error;
-    for(i=0;i<length;i++)
-    {
-      dyn_slave_se_data[5+i]=data[i];
-      cs+=data[i];
-    }
-    dyn_slave_se_data[5+i]=~cs;
-    // set in tex mode
-    dyn_slave_se_set_tx();
-    // start transmission
-    dyn_slave_se_num_tx_bytes=1;
-    UDR1=dyn_slave_se_data[0];
-  }
-}
-
-inline uint8_t dyn_slave_se_is_send_done(void)
-{
-  return dyn_slave_se_send_done;
-}
-
-/* public functions */
-void dyn_slave_se_init(uint8_t baudrate,uint8_t id)
-{
-  // DDRD - Port D Data Direction Register 
-  DDRD=DDRD|0xC8;// RX_en (7), TX_en (6), TX (3) are outputs 0xC2=11000010
-  DDRD=DDRD&0xFB;// RX(2) is an input     0xFE=11111110
-
-  // configure the ports to receive data
-  dyn_slave_se_set_rx();
-
-  // initialize the rs485 ports
-  UCSR1A = (1<<U2X);// double USART transmission speed
-  dyn_slave_se_set_baudrate(baudrate);
-  UCSR1A|=0x40;// clear any pending interrupt
-  UCSR1B = (1<<RXEN)|(1<<TXEN)|(1<<RXCIE)|(1<<TXCIE);
-  UCSR1C = (1<<UCSZ1)|(1<< UCSZ0); // 8 bit data, no parity, 1 stop bit
-
-  dyn_slave_se_set_id(id);
-  // initialize private variables
-  dyn_slave_se_num_tx_bytes=0;
-  dyn_slave_se_num_rx_bytes=0;
-  dyn_slave_se_packet_ready=0;
-  dyn_slave_se_send_done=0;
-  dyn_slave_se_error=NO_ERROR;
-  dyn_slave_se_tmp_address=0x00;
-  dyn_slave_se_tmp_length=0x00;
-  dyn_slave_se_reg_pending=0x00;
-  dyn_slave_se_sync_read_pending=0x00;
-  dyn_slave_se_bulk_read_pending=0x00;
-}
-
-void dyn_slave_se_set_baudrate(uint8_t baudrate)
-{
-  UBRR1H = 0;
-  UBRR1L = baudrate;
-  ram_data[Baud_Rate]=baudrate;
-}
-
-void dyn_slave_se_set_id(uint8_t id)
-{
-  dyn_slave_se_id=id;
-  ram_data[ID]=id;
-}
-
-void dyn_slave_se_loop(void)
-{
-  static uint8_t *data,i;
-
-  if(dyn_slave_se_is_packet_ready())
-  {
-    if(dyn_slave_se_check_id())
-    {
-      if(dyn_slave_se_check_checksum())
-      {
-        switch(dyn_slave_se_get_instruction())
-        {
-          case INST_PING: dyn_slave_se_send_status(dyn_slave_se_error|NO_ERROR,0x00,0x00000000);
-                          break;
-          case INST_READ: if(do_read(dyn_slave_se_get_address(),dyn_slave_se_get_read_length(),&data))
-                            dyn_slave_se_send_status(dyn_slave_se_error|NO_ERROR,dyn_slave_se_get_read_length(),data);
-                          else
-                            dyn_slave_se_send_status(dyn_slave_se_error|INSTRUCTION_ERROR,0x00,0x00000000);
-                          break;
-          case INST_WRITE: if(do_write(dyn_slave_se_get_address(),dyn_slave_se_get_write_length(),dyn_slave_se_get_write_data()))
-                             dyn_slave_se_send_status(dyn_slave_se_error|NO_ERROR,0x00,0x00000000);
-                           else 
-                             dyn_slave_se_send_status(dyn_slave_se_error|INSTRUCTION_ERROR,0x00,0x00000000);
-                           break;
-          case INST_REG_WRITE: dyn_slave_se_tmp_address=dyn_slave_se_get_address();
-                               dyn_slave_se_tmp_length=dyn_slave_se_get_write_length();
-                               data=dyn_slave_se_get_write_data();
-                               for(i=0;i<dyn_slave_se_tmp_length;i++)
-                                 dyn_slave_se_tmp_data[i]=data[i];
-                               dyn_slave_se_reg_pending=0x01;
-                               dyn_slave_se_send_status(dyn_slave_se_error|NO_ERROR,0x00,0x00000000);
-                               break;
-          case INST_ACTION: if(dyn_slave_se_reg_pending)
-                            {
-                              if(do_write(dyn_slave_se_tmp_address,dyn_slave_se_tmp_length,dyn_slave_se_tmp_data))
-                                dyn_slave_se_send_status(dyn_slave_se_error|NO_ERROR,0x00,0x00000000);
-                            }
-                            else
-                              dyn_slave_se_send_status(dyn_slave_se_error|INSTRUCTION_ERROR,0x00,0x00000000);
-                            break;
-          case INST_RESET:
-                           break;
-          case INST_SYNC_READ: dyn_slave_se_sync_read_previous=dyn_slave_se_sync_read_id_present();
-                               if(dyn_slave_se_sync_read_previous!=0xFF)
-                               {
-                                 if(dyn_slave_se_sync_read_previous==0x00)// first device on the list
-                                 {
-                                   if(do_read(dyn_slave_se_get_address(),dyn_slave_se_get_read_length(),&data))
-                                     dyn_slave_se_send_status(dyn_slave_se_error|NO_ERROR,dyn_slave_se_get_read_length(),data);
-                                   else
-                                     dyn_slave_se_send_status(dyn_slave_se_error|INSTRUCTION_ERROR,0x00,0x00000000);
-                                 }
-                                 else// sync read pending
-                                 {
-                                   dyn_slave_se_tmp_address=dyn_slave_se_get_address();
-                                   dyn_slave_se_tmp_length=dyn_slave_se_get_read_length();
-                                   dyn_slave_se_sync_read_pending=0x01;
-                                 }
-                               }
-                               break;
-          case INST_SYNC_WRITE: if(dyn_slave_se_sync_write_id_present(&data))
-                                  do_write(dyn_slave_se_get_address(),dyn_slave_se_get_read_length(),data);
-                                break;
-          case INST_BULK_READ: dyn_slave_se_bulk_read_previous=dyn_slave_se_bulk_read_id_present(&dyn_slave_se_tmp_address,&dyn_slave_se_tmp_length);
-                               if(dyn_slave_se_bulk_read_previous!=0xFF)
-                               {
-                                 if(dyn_slave_se_bulk_read_previous==0x00)// first device on the list
-                                 {
-                                   if(do_read(dyn_slave_se_tmp_address,dyn_slave_se_tmp_length,&data))
-                                     dyn_slave_se_send_status(dyn_slave_se_error|NO_ERROR,dyn_slave_se_tmp_length,data);
-                                   else
-                                     dyn_slave_se_send_status(dyn_slave_se_error|INSTRUCTION_ERROR,0x00,0x00000000);
-                                 }
-                                 else// sync read pending
-                                   dyn_slave_se_bulk_read_pending=0x01;
-                               }
-                               break;
-          case INST_BULK_WRITE: if(dyn_slave_se_bulk_write_id_present(&dyn_slave_se_tmp_address,&dyn_slave_se_tmp_length,&data))
-                                  do_write(dyn_slave_se_tmp_address,dyn_slave_se_tmp_length,data);
-                                break;
-          default: dyn_slave_se_send_status(dyn_slave_se_error|INSTRUCTION_ERROR,0x00,0x00000000);
-                   break;
-        }
-      }
-      else
-        dyn_slave_se_send_status(dyn_slave_se_error|CHECKSUM_ERROR,0x00,0x00000000);
-    }
-    else
-    {
-      if(dyn_slave_se_sync_read_pending)
-      {
-        if(dyn_slave_se_get_received_id()==dyn_slave_se_sync_read_previous)
-        {
-          dyn_slave_se_sync_read_pending=0x00;
-          if(do_read(dyn_slave_se_tmp_address,dyn_slave_se_tmp_length,&data))
-            dyn_slave_se_send_status(dyn_slave_se_error|NO_ERROR,dyn_slave_se_tmp_length,data);
-          else
-            dyn_slave_se_send_status(dyn_slave_se_error|INSTRUCTION_ERROR,0x00,0x00000000); 
-        }
-      }
-      if(dyn_slave_se_bulk_read_pending)
-      {
-        if(dyn_slave_se_get_received_id()==dyn_slave_se_bulk_read_previous)
-        {
-          dyn_slave_se_bulk_read_pending=0x00;
-          if(do_read(dyn_slave_se_tmp_address,dyn_slave_se_tmp_length,&data))
-            dyn_slave_se_send_status(dyn_slave_se_error|NO_ERROR,dyn_slave_se_tmp_length,data);
-          else
-            dyn_slave_se_send_status(dyn_slave_se_error|INSTRUCTION_ERROR,0x00,0x00000000); 
-        }
-      }
-    }
-  }
-}
-
-void dyn_slave_se_set_error(uint8_t error)
-{
-  dyn_slave_se_error|=error;
-}
-
-void dyn_slave_se_clear_error(void)
-{
-  dyn_slave_se_error=NO_ERROR;
-}
diff --git a/src/i2c.c b/src/i2c.c
deleted file mode 100644
index 1b44ba0..0000000
--- a/src/i2c.c
+++ /dev/null
@@ -1,217 +0,0 @@
-#include <avr/io.h>
-#include <avr/interrupt.h>
-#include "i2c.h"
-
-#define          I2C_RX_BUFFER_LEN     32
-#define          I2C_TX_BUFFER_LEN     32
-
-/* private variables */
-static volatile i2c_states_t i2c_state;
-static uint8_t i2c_device_address;
-// send/transmit buffer (outgoing data)
-static uint8_t i2c_tx_data[I2C_RX_BUFFER_LEN];
-static uint8_t i2c_tx_data_ptr;
-static uint8_t i2c_tx_length;
-// receive buffer (incoming data)
-static uint8_t i2c_rx_data[I2C_TX_BUFFER_LEN];
-static uint8_t i2c_rx_data_ptr;
-static uint8_t i2c_rx_length;
-
-/* private functions */
-inline void i2c_send_start(void)
-{
-  // send start condition
-  TWCR=(TWCR&TWCR_CMD_MASK)|(1<<TWINT)|(1<<TWSTA);
-}
-
-inline void i2c_send_stop(void)
-{
-  // transmit stop condition
-  // leave with TWEA on for slave receiving
-  TWCR=(TWCR&TWCR_CMD_MASK)|(1<<TWINT)|(1<<TWEA)|(1<<TWSTO);
-}
-
-inline void i2c_wait_for_complete(void)
-{
-  // wait for i2c interface to complete operation
-  while((TWCR&(1<<TWINT))==0x00);
-}
-
-inline void i2c_send_byte(uint8_t data)
-{
-  // save data to the TWDR
-  TWDR=data;
-  // begin send
-  TWCR=(TWCR&TWCR_CMD_MASK)|(1<<TWINT);
-}
-
-inline void i2c_receive_byte(uint8_t ackFlag)
-{
-  // begin receive over i2c
-  if( ackFlag )
-  {
-    // ackFlag = TRUE: ACK the recevied data
-    TWCR=(TWCR&TWCR_CMD_MASK)|(1<<TWINT)|(1<<TWEA);
-  }
-  else
-  {
-    // ackFlag = FALSE: NACK the recevied data
-    TWCR=(TWCR&TWCR_CMD_MASK)|(1<<TWINT);
-  }
-}
-
-inline uint8_t i2c_get_byte(void)
-{
-  // retieve received data byte from i2c TWDR
-  return TWDR;
-}
-
-i2c_states_t i2c_get_state(void)
-{
-  // retieve current i2c status from i2c TWSR
-  return i2c_state;
-}
-
-/* interrupt handlers */
-ISR(TWI_vect)
-{
-  // read status bits
-  uint8_t status = TWSR&TWSR_STATUS_MASK;
-
-  switch(status)
-  {
-    // Master General
-    case TW_START://0x08: Sent start condition
-    case TW_REP_START:// 0x10: Sent repeated start condition
-      // send device address
-      i2c_send_byte(i2c_device_address);
-      break;
-      // Master Transmitter & Receiver status codes
-    case TW_MT_SLA_ACK:// 0x18: Slave address acknowledged
-    case TW_MT_DATA_ACK:// 0x28: Data acknowledged
-      if(i2c_tx_data_ptr < i2c_tx_length)
-      {
-	// send data
-	i2c_send_byte( i2c_tx_data[i2c_tx_data_ptr++] );
-      }
-      else
-      {
-	// transmit stop condition, enable SLA ACK
-	i2c_send_stop();
-	// set state
-	i2c_state = I2C_IDLE;
-      }
-      break;
-    case TW_MR_DATA_NACK:// 0x58: Data received, NACK reply issued
-      // store final received data byte
-      i2c_rx_data[i2c_rx_data_ptr++] = TWDR;
-      // continue to transmit STOP condition
-    case TW_MR_SLA_NACK:// 0x48: Slave address not acknowledged
-    case TW_MT_SLA_NACK:// 0x20: Slave address not acknowledged
-    case TW_MT_DATA_NACK:// 0x30: Data not acknowledged
-      // transmit stop condition, enable SLA ACK
-      i2c_send_stop();
-      // set state
-      i2c_state = I2C_IDLE;
-      break;
-    case TW_MT_ARB_LOST:// 0x38: Bus arbitration lost
-      // release bus
-      TWCR=(TWCR&TWCR_CMD_MASK)|(1<<TWINT);
-      // set state
-      i2c_state = I2C_IDLE;
-      break;
-    case TW_MR_DATA_ACK:// 0x50: Data acknowledged
-      // store received data byte
-      i2c_rx_data[i2c_rx_data_ptr++] = TWDR;
-      // fall-through to see if more bytes will be received
-    case TW_MR_SLA_ACK:// 0x40: Slave address acknowledged
-      if(i2c_rx_data_ptr < (i2c_rx_length-1))
-	// data byte will be received, reply with ACK (more bytes in transfer)
-	i2c_receive_byte(0x01);
-      else
-	// data byte will be received, reply with NACK (final byte in transfer)
-	i2c_receive_byte(0x00);
-      break;
-      // Misc
-    case TW_NO_INFO:// 0xF8: No relevant state information
-      // do nothing
-      break;
-    case TW_BUS_ERROR:// 0x00: Bus error due to illegal start or stop condition
-      // reset internal hardware and release bus
-      TWCR=(TWCR&TWCR_CMD_MASK)|(1<<TWINT)|(1<<TWSTO)|(1<<TWEA);
-      // set state
-      i2c_state = I2C_IDLE;
-      break;
-  }
-}
-
-/* public functions */
-void i2c_init(uint16_t bitrate_khz)
-{
-  /* configure the io ports */
-  //DDRD|=0x03;
-  // set i2c bit rate to 100KHz
-  i2c_set_bitrate(bitrate_khz);
-
-  /* initialize the internal variables */
-  i2c_tx_data_ptr=0;
-  i2c_tx_length=0;
-  i2c_rx_data_ptr=0;
-  i2c_rx_length=0;
-  i2c_state=I2C_IDLE;
-
-  TWCR=(1<<TWEN)|(1<<TWIE)|(1<<TWEA);
-}
-
-void i2c_set_bitrate(uint16_t bitrate_khz)
-{
-  uint8_t bitrate_div;
-
-  TWSR&=~((1<<TWPS0)|(1<<TWPS1));
-  // calculate bitrate division	
-  bitrate_div = ((F_CPU/1000l)/bitrate_khz);
-  if(bitrate_div >= 16)
-    bitrate_div = (bitrate_div-16)/2;
-  TWBR=bitrate_div;
-}
-
-void i2c_master_send(uint8_t deviceAddr, uint8_t length, uint8_t* data)
-{
-  uint8_t i;
-  // wait for interface to be ready
-  while(i2c_state);
-  // set state
-  i2c_state = I2C_MASTER_TX;
-  // save data
-  i2c_device_address = (deviceAddr & 0xFE);	// RW cleared: write operation
-  for(i=0; i<length; i++)
-    i2c_tx_data[i] = *data++;
-  i2c_tx_data_ptr = 0;
-  i2c_tx_length = length;
-  // send start condition
-  i2c_send_start();
-}
-
-void i2c_master_receive(uint8_t deviceAddr, uint8_t length)//, uint8_t* data)
-{
-  //	uint8_t i;
-  // wait for interface to be ready
-  while(i2c_state);
-  // set state
-  i2c_state = I2C_MASTER_RX;
-  // save data
-  i2c_device_address = (deviceAddr|0x01);	// RW set: read operation
-  i2c_rx_data_ptr = 0;
-  i2c_rx_length = length;
-  // send start condition
-  i2c_send_start();
-}
-
-void i2c_get_data(unsigned char length, unsigned char *data)
-{
-  unsigned char i;
-
-  for(i=0;i<length;i++)
-    data[i]=i2c_rx_data[i];
-}
-
diff --git a/src/main.c b/src/main.c
deleted file mode 100755
index 3acf8c9..0000000
--- a/src/main.c
+++ /dev/null
@@ -1,52 +0,0 @@
-#include <avr/io.h>
-#include <util/delay.h>
-#include <avr/interrupt.h>
-#include "dyn_slave_se.h"
-#include "dyn_slave_diff.h"
-#include "mem.h"
-#include "ports.h"
-#include "adc.h"
-#ifdef _PWM
-#include "pwm.h"
-#endif
-#ifdef _DAC
-#include "dac.h"
-#endif
-#include "compass.h"
-#ifdef _UART_TTL
-#include "uart_ttl.h"
-#endif
-#ifdef _UART_USB
-#include "uart_usb.h"
-#endif
-
-int16_t main(void) 
-{
-  ram_init();
-  dyn_slave_se_init(ram_data[Baud_Rate],ram_data[ID]);
-  dyn_slave_diff_init(ram_data[Baud_Rate],ram_data[ID]);
-  init_ports();
-  adc_init();
-  #ifdef _PWM
-  pwm_init();
-  #endif
-  #ifdef _DAC
-  dac_init();
-  #endif
-  compass_init();
-  #ifdef _UART_TTL
-  uart_ttl_init();
-  #endif
-  #ifdef _UART_USB
-  uart_usb_init();
-  #endif
-  sei();
-
-  while (1) 
-  {
-    adc_loop();
-    compass_loop();
-    dyn_slave_se_loop();
-    dyn_slave_diff_loop();
-  }
-}
diff --git a/src/mem.c b/src/mem.c
deleted file mode 100644
index b6e29bc..0000000
--- a/src/mem.c
+++ /dev/null
@@ -1,48 +0,0 @@
-#include "mem.h"
-#include <avr/eeprom.h>
-
-// dynamixel RAM variables
-uint8_t ram_data[RAM_SIZE];
-
-// Dynamixel EEPROM variables
-uint8_t EEMEM eeprom_data[17]={0x1C,0x00,0x00,0xC0,0x01,0xFA,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x02};
-
-void ram_init(void)
-{
-  uint8_t i;
-
-  for(i=0;i<=Return_Delay_Time;i++)
-    ram_data[i]=eeprom_read_byte(&eeprom_data[i]);
-  for(;i<RAM_SIZE;i++)
-    ram_data[i]=0x00;
-}
-
-uint8_t ram_read(uint8_t address, uint8_t length, uint8_t **data)
-{
-  if((address+length)>RAM_SIZE)
-    return 0x00;
-  else
-  {
-    (*data)=&ram_data[address];
-    return 0x01;
-  }
-}
-
-uint8_t ram_write(uint8_t address, uint8_t length, uint8_t *data)
-{
-  uint8_t i,num=0;
-
-  if((address+length)>RAM_SIZE)
-    return 0x00;
-  else
-  {
-    for(i=address;i<address+length;i++)
-    {
-      if(i<=Return_Delay_Time)
-        eeprom_write_byte(&eeprom_data[i],data[num]);
-      ram_data[i]=data[num];
-      num++;
-    }
-    return 0x01;
-  }
-}
diff --git a/src/ports.c b/src/ports.c
deleted file mode 100644
index ad16ecc..0000000
--- a/src/ports.c
+++ /dev/null
@@ -1,136 +0,0 @@
-#include <avr/io.h>
-#include "ports.h"
-#include "mem.h"
-
-TGPIO gpio_bits[NUM_GPIO]={{&DDRA,&PORTA,&PINA,0},
-                           {&DDRA,&PORTA,&PINA,1},
-                           {&DDRA,&PORTA,&PINA,2},
-                           {&DDRA,&PORTA,&PINA,3},
-                           {&DDRA,&PORTA,&PINA,4},
-                           {&DDRA,&PORTA,&PINA,5},
-                           {&DDRA,&PORTA,&PINA,6}, 
-                           {&DDRA,&PORTA,&PINA,7},
-                           {&DDRG,&PORTG,&PING,2},
-                           {&DDRC,&PORTC,&PINC,7},
-                           {&DDRC,&PORTC,&PINC,6},
-                           {&DDRC,&PORTC,&PINC,5},
-                           {&DDRC,&PORTC,&PINC,4},
-                           {&DDRC,&PORTC,&PINC,3},
-                           {&DDRC,&PORTC,&PINC,2},
-                           {&DDRC,&PORTC,&PINC,1},
-                           {&DDRC,&PORTC,&PINC,0},
-                           {&DDRG,&PORTG,&PING,1},
-                           {&DDRG,&PORTG,&PING,0}};
-
-void init_ports(void)
-{
-  //auxiliar LED
-  DDRE|=0x04;
-  clear_led();
-
-  // general purpose input/output
-  // all inputs by default
-  DDRA=0x00;
-  DDRC=0x00;
-  DDRG&=0xF8;
-
-  // input selector
-  DDRG&=0xE7;
-}
-
-void config_port(uint8_t port_id,uint8_t dir)
-{
-  if(port_id>=0 && port_id<NUM_GPIO)
-  {
-    if(dir==OUTPUT)// configure as an output
-    {
-      *(gpio_bits[port_id].dir_reg)|=0x01<<gpio_bits[port_id].bit;
-      ram_data[GPIO0_config+port_id*2]=0x01;
-    }
-    else// configure as an input
-    {
-      *(gpio_bits[port_id].dir_reg)&=~(0x01<<gpio_bits[port_id].bit);
-      ram_data[GPIO0_config+port_id*2]=0x00;
-    }
-  }
-}
-
-uint8_t get_port_config(uint8_t port_id)
-{
-  uint8_t dir;
-
-  if(port_id>=0 && port_id<NUM_GPIO)
-  {
-    dir=(*(gpio_bits[port_id].dir_reg)&(0x01<<gpio_bits[port_id].bit));
-    if(dir==0x00)
-      return INPUT;
-    else
-      return OUTPUT;
-  }
-  else
-    return INPUT;
-}
-
-void set_port(uint8_t port_id)
-{
-  if(port_id>=0 && port_id<NUM_GPIO)
-  {
-    *(gpio_bits[port_id].write_reg)|=0x01<<gpio_bits[port_id].bit;
-    ram_data[GPIO0_data+port_id*2]=0x01;
-  }
-}
-
-void clear_port(uint8_t port_id)
-{
-  if(port_id>=0 && port_id<NUM_GPIO)
-  {
-    *(gpio_bits[port_id].write_reg)&=~(0x01<<gpio_bits[port_id].bit);
-    ram_data[GPIO0_data+port_id*2]=0x00;
-  }
-}
-
-uint8_t read_port(uint8_t port_id)
-{
-  uint8_t value;
-  if(port_id>=0 && port_id<NUM_GPIO)
-  {
-    value=((*(gpio_bits[port_id].read_reg))&(0x01<<gpio_bits[port_id].bit));
-    if(value==0x00)
-    {
-      ram_data[GPIO0_data+port_id]=0x00;
-      return 0x00;
-    }
-    else
-    {
-      ram_data[GPIO0_data+port_id]=0x01;
-      return 0x01;
-    }
-  }
-  else
-    return 0x00;
-}
-
-void set_led(void)
-{
-  PORTE&=0xFB;
-  ram_data[LED]=0x01;
-}
-
-void clear_led(void)
-{
-  PORTE|=0x04;
-  ram_data[LED]=0x00;
-}
-
-void toggle_led(void)
-{
-  PORTE^=0x04;
-  ram_data[LED]^=0x01;
-}
-
-uint8_t get_selector_value(void)
-{
-  ram_data[SWITCHES]=(PING&0x18)>>3;
-  return ((PING&0x18)>>3);
-}
-
diff --git a/src/pwm.c b/src/pwm.c
deleted file mode 100644
index 3d882ca..0000000
--- a/src/pwm.c
+++ /dev/null
@@ -1,162 +0,0 @@
-#include "pwm.h"
-#include "mem.h"
-#include "ports.h"
-
-#define      DEFAULT_PWM_FREQ     50// Hz
-#define      DEFAULT_PWM_DUTY     50// %
-
-#define      PWM_MAX_CHANNELS     4
-
-/* private variables */
-uint32_t pwm_top_value;
-uint8_t pwm_prescaler_mask;
-uint8_t pwm_running;
-uint8_t pwm_duty_cycle[PWM_MAX_CHANNELS];
-
-/* public functions */
-void pwm_init(void)
-{
-  /* configure the IO pins */
-  DDRE|=0x38;
-  DDRB|=0x80;
-
-  /* initialize internal variables */
-  pwm_top_value=40000;
-  ram_data[PWM_FREQ_L]=50;
-  ram_data[PWM_FREQ_H]=0;
-  pwm_prescaler_mask=2;
-  pwm_running=0x00;
-
-  pwm_set_duty_cycle(pwm0,DEFAULT_PWM_DUTY);
-  pwm_set_duty_cycle(pwm1,DEFAULT_PWM_DUTY);
-  pwm_set_duty_cycle(pwm2,DEFAULT_PWM_DUTY);
-  pwm_set_duty_cycle(pwm3,DEFAULT_PWM_DUTY);
-
-  /* configure the timer 3 */
-  TCNT3H=0x00;
-  TCNT3L=0x00;
-  /* set the timer mode */
-  TCCR3A=(1<<WGM31);// all three channels in fast PWM mode, output disabled
-  TCCR3B=(1<<WGM33)|(1<<WGM32);// no clock source, fast PWM mode
-  // no interrupts enabled
-}
-
-void pwm_start(void)
-{
-  TCNT3H=0x00;
-  TCNT3L=0x00;
-  // set the prescaler value to the correct value
-  /* set the prescaler value */
-  TCCR3B&=0xF8;
-  TCCR3B|=pwm_prescaler_mask;
-  /* set the top value */
-  ICR3H=(pwm_top_value>>8)&0xFF;
-  ICR3L=(pwm_top_value)&0xFF;
-  pwm_running=0x01;
-  ram_data[PWM_CONTROL]|=0x04;
-}
-
-void pwm_stop(void)
-{
-  /* set the prescaler to 0 (no clock source) */
-  TCCR3B&=0xF8;
-  pwm_running=0x00;
-  ram_data[PWM_CONTROL]&=0xFB;
-}
-
-void pwm_enable_ch(pwm_id_t id)
-{
-  switch(id)
-  {
-    case pwm0: TCCR3A|=(1<<COMA1);
-               ram_data[PWM_CONTROL]|=0x10;
-               break;
-    case pwm1: TCCR3A|=(1<<COMB1);
-               ram_data[PWM_CONTROL]|=0x20;
-               break;
-    case pwm2: TCCR3A|=(1<<COMC1);
-               ram_data[PWM_CONTROL]|=0x40;
-               break;
-    case pwm3: break;
-  }
-}
-
-void pwm_disable_ch(pwm_id_t id)
-{
-  switch(id)
-  {
-    case pwm0: TCCR3A&=~(1<<COMA1);
-               ram_data[PWM_CONTROL]&=0xEF;
-               break;
-    case pwm1: TCCR3A&=~(1<<COMB1);
-               ram_data[PWM_CONTROL]&=0xDF;
-               break;
-    case pwm2: TCCR3A&=~(1<<COMC1);
-               ram_data[PWM_CONTROL]&=0xBF;
-               break;
-    case pwm3: break;
-  }
-}
-
-void pwm_set_frequency(uint16_t freq_hz)
-{
-  uint32_t prescaler_values[5]={1,8,64,256,1024};
-  uint32_t den;
-  uint8_t i;
-
-  for(i=0;i<5;i++)
-  {
-    den=freq_hz*prescaler_values[i];
-    pwm_top_value=(((uint32_t)16000000)/den)-1;
-    if(pwm_top_value<65536)
-    {
-      /* adjust the duty cyle  */
-      pwm_set_duty_cycle(pwm0,pwm_duty_cycle[0]);
-      pwm_set_duty_cycle(pwm1,pwm_duty_cycle[1]);
-      pwm_set_duty_cycle(pwm2,pwm_duty_cycle[2]);
-      pwm_set_duty_cycle(pwm3,pwm_duty_cycle[3]);
-      if(pwm_running)
-      {
-        /* set the prescaler value */
-        TCCR3B&=0xF8;
-        TCCR3B|=(i+1);
-        /* set the top value */
-        ICR3H=(pwm_top_value>>8)&0xFF;
-        ICR3L=(pwm_top_value)&0xFF;
-      }
-      else 
-        pwm_prescaler_mask=(i+1);
-      ram_data[PWM_FREQ_L]=freq_hz%256;
-      ram_data[PWM_FREQ_H]=freq_hz/256;
-      break;
-    }
-  }
-}
-
-void pwm_set_duty_cycle(pwm_id_t id,uint8_t duty)
-{
-  uint16_t compare_value;
-
-  compare_value=(pwm_top_value/100)*duty;
-
-  switch(id)
-  {
-    case pwm0: OCR3AH=(compare_value>>8)&0xFF;
-               OCR3AL=(compare_value&0xFF);
-               pwm_duty_cycle[0]=duty;
-               ram_data[PWM_CH0_DUTY]=duty;
-               break;
-    case pwm1: OCR3BH=(compare_value>>8)&0xFF;
-               OCR3BL=(compare_value&0xFF);
-               pwm_duty_cycle[1]=duty;
-               ram_data[PWM_CH1_DUTY]=duty;
-               break;
-    case pwm2: OCR3CH=(compare_value>>8)&0xFF;
-               OCR3CL=(compare_value&0xFF);
-               pwm_duty_cycle[2]=duty;
-               ram_data[PWM_CH2_DUTY]=duty;
-               break;
-    case pwm3: break;
-  } 
-}
-
diff --git a/src/uart_ttl.c b/src/uart_ttl.c
deleted file mode 100644
index ef05e72..0000000
--- a/src/uart_ttl.c
+++ /dev/null
@@ -1,246 +0,0 @@
-#include <avr/io.h>
-#include <avr/interrupt.h>
-#include "uart_ttl.h"
-#include "mem.h"
-
-#define UART_TTL_DEFAULT_BAUDRATE 9600
-
-#define UART_TTL_RX_BUFFER_SIZE   0x20
-
-#define UART_TTL_TX_PORT          PORTE
-#define UART_TTL_TX_DDR           DDRE
-#define UART_TTL_TX_PIN           PE6 
-
-#define UART_TLL_RX_PORT          PORTE
-#define UART_TTL_RX_DDR           DDRE
-#define UART_TLL_RX_PORTIN        PINE
-#define UART_TTL_RX_PIN           PE7 
-
-// uartsw transmit status and data variables
-volatile uint8_t uart_ttl_tx_busy;
-volatile uint8_t uart_ttl_tx_data;
-volatile uint8_t uart_ttl_tx_bit_num;
-
-// baud rate common to transmit and receive
-volatile uint16_t uart_ttl_baudrate_div;
-
-// uartsw receive status and data variables
-volatile uint8_t uart_ttl_rx_busy;
-volatile uint8_t uart_ttl_rx_data;
-volatile uint8_t uart_ttl_rx_bit_num;
-
-/* rx buffer */
-unsigned char uart_ttl_rx_data_buffer[UART_TTL_RX_BUFFER_SIZE];
-unsigned char uart_ttl_rx_read_ptr;
-unsigned char uart_ttl_rx_write_ptr;
-unsigned char uart_ttl_rx_num_data;
-
-/* private functions */
-
-/* interrupt handlers */
-ISR(TIMER3_CAPT_vect)//RX
-{
-  uint16_t capture;
-  // clear ICP interrupt flag
-  ETIFR|=(1<<ICF3);
- 
-  if(!uart_ttl_rx_busy)
-  {
-    // disable input capture interrutps
-    ETIMSK&=~(1<<TICIE3);
-    capture=TCNT3+uart_ttl_baudrate_div + uart_ttl_baudrate_div/2;
-    // schedule data bit sampling 1.5 bit periods from now
-    OCR3BH=(capture>>8)&0xFF;
-    OCR3BL=capture&0xFF;
-    // clear OC1B interrupt flag
-    ETIFR|=(1<<OCF3B);
-    // enable OC1B interrupt
-    ETIMSK|=(1<<OCIE3B);
-    // set start bit flag
-    uart_ttl_rx_busy = 0x01;
-    // reset bit counter
-    uart_ttl_rx_bit_num = 0;
-    // reset data
-    uart_ttl_rx_data = 0;
-  }
-}
-
-ISR(TIMER3_COMPB_vect)//RX
-{
-  uint16_t capture;
-
-  // clear OC1B interrupt flag
-  ETIFR|=(1<<OCF3B);
-  // shift data byte to make room for new bit
-  uart_ttl_rx_data = uart_ttl_rx_data>>1;
-
-  if(UART_TLL_RX_PORTIN&(1<<UART_TTL_RX_PIN))
-    uart_ttl_rx_data |= 0x80;
-
-  // increment bit counter
-  uart_ttl_rx_bit_num++;
-  // schedule next bit sample
-  capture=OCR3B+uart_ttl_baudrate_div;
-  OCR3BH=(capture>>8)&0xFF;
-  OCR3BL=capture&0xFF;
-
-  // check if we have a full byte
-  if(uart_ttl_rx_bit_num >= 8)
-  {
-    // save data in receive buffer
-    uart_ttl_rx_data_buffer[uart_ttl_rx_write_ptr]=uart_ttl_rx_data;
-    uart_ttl_rx_write_ptr=(uart_ttl_rx_write_ptr+1)%UART_TTL_RX_BUFFER_SIZE;
-    uart_ttl_rx_num_data++;
-    // disable OC1B interrupt
-    ETIMSK&=~(1<<OCIE3B);
-    // enable ICP interrupt
-    ETIMSK|=(1<<TICIE3);
-    // clear start bit flag
-    uart_ttl_rx_busy = 0x00;
-  }
-}
-
-ISR(TIMER3_COMPA_vect)//TX
-{
-  uint16_t capture;
-
-  // clear OC1B interrupt flag
-  ETIFR|=(1<<OCF3A);
-  if(uart_ttl_tx_bit_num)
-  {
-    if(uart_ttl_tx_bit_num>1)
-    {
-      // transmit data bits (inverted, LSB first)
-      if((uart_ttl_tx_data&0x01))
-        UART_TTL_TX_PORT|=(1<<UART_TTL_TX_PIN);
-      else
-        UART_TTL_TX_PORT&=~(1<<UART_TTL_TX_PIN);
-      // shift bits down
-      uart_ttl_tx_data = uart_ttl_tx_data>>1;
-    }
-    else
-      UART_TTL_TX_PORT|=(1<<UART_TTL_TX_PIN);
-    // schedule the next bit
-    capture=OCR3A+uart_ttl_baudrate_div;
-    OCR3AH=(capture>>8)&0xFF;
-    OCR3AL=capture&0xFF;
-    // count down
-    uart_ttl_tx_bit_num--;
-  }
-  else
-  {
-    // enable OC1A interrupt
-    ETIMSK&=~(1<<OCIE3A);
-    uart_ttl_tx_busy = 0x00;
-  }
-}
-
-/* public functions */
-void uart_ttl_init(void)
-{
-  // configure GPIO ports
-  UART_TTL_TX_DDR|=(1<<UART_TTL_TX_PIN);// output
-  UART_TTL_RX_DDR&=~(1<<UART_TTL_RX_PIN);//input
-  // set input to 0
-  UART_TLL_RX_PORT&=~(1<<UART_TTL_RX_PIN);
-  // initialize baud rate
-  uart_ttl_set_baudrate(UART_TTL_DEFAULT_BAUDRATE);
-  ram_data[UART_TTL_BAUDRATE_L]=UART_TTL_DEFAULT_BAUDRATE%256;
-  ram_data[UART_TTL_BAUDRATE_H]=UART_TTL_DEFAULT_BAUDRATE/256;
-
-  // setup the transmitter
-  uart_ttl_tx_busy = 0x00;
-  ETIMSK&=~(1<<OCIE3A);
-
-  // setup the receiver
-  uart_ttl_rx_busy = 0x00;
-  ETIMSK&=~(1<<OCIE3B);
-  // trigger on falling edge 
-  TCCR3B&=~(1<<ICES3);
-  // disable ICP interrupt
-  ETIMSK&=~(1<<TICIE3);
-
-  /* initlaize buffer variables */
-  uart_ttl_rx_read_ptr=0;
-  uart_ttl_rx_write_ptr=0;
-  uart_ttl_rx_num_data=0;
-}
-
-void uart_ttl_start(void)
-{
-  ETIMSK&=~(1<<OCIE3A);
-  ETIMSK&=~(1<<OCIE3B);
-  // clear ICP interrupt flag
-  ETIFR|=(1<<ICF3);
-  ETIMSK|=(1<<TICIE3);
-  ram_data[UART_TTL_CONTROL]|=0x20;
-}
-
-void uart_ttl_stop(void)
-{
-  // disable interrupts
-  ETIMSK&=~(1<<OCIE3A);
-  ETIMSK&=~(1<<OCIE3B);
-  ETIMSK&=~(1<<TICIE3);
-  ram_data[UART_TTL_CONTROL]&=0xDF;
-}
-
-void uart_ttl_set_baudrate(uint32_t baudrate)
-{
-  TCCR3B&=0xF8;
-  TCCR3B|=0x01;
-  // calculate division factor for requested baud rate, and set it
-  uart_ttl_baudrate_div = (uint16_t)((F_CPU+(baudrate/2L))/(baudrate*1L));
-}
-
-void uart_ttl_send_byte(uint8_t data)
-{
-  uint16_t capture;
-
-  // wait until uart is ready
-  while(uart_ttl_tx_busy);
-  // set busy flag
-  uart_ttl_tx_busy = 0x01;
-  // save data
-  uart_ttl_tx_data = data;
-  // set number of bits (+1 for stop bit)
-  uart_ttl_tx_bit_num = 9;
-
-  UART_TTL_TX_PORT&=~(1<<UART_TTL_TX_PIN);
-
-  capture=TCNT3+uart_ttl_baudrate_div;
-  OCR3AH=(capture>>8)&0xFF;
-  OCR3AL=capture&0xFF;
-  // clear interrupts
-  ETIFR|=(1<<OCF3A);
-  // enable OC1A interrupt
-  ETIMSK|=(1<<OCIE3A);
-}
-
-uint8_t uart_ttl_is_sending(void)
-{
-  return uart_ttl_tx_busy;
-}
-
-uint8_t uart_ttl_receive_byte(uint8_t* data)
-{
-  // make sure we have a receive buffer
-  if(uart_ttl_rx_num_data>0)
-  {
-    *data=uart_ttl_rx_data_buffer[uart_ttl_rx_read_ptr];
-    uart_ttl_rx_read_ptr=(uart_ttl_rx_read_ptr+1)%UART_TTL_RX_BUFFER_SIZE;
-    uart_ttl_rx_num_data--;
-    // make sure we have data
-    return 0x01;
-  }
-  else
-    return 0x00;
-}
-
-uint8_t uart_ttl_is_data_available(void)
-{
-  if(uart_ttl_rx_num_data>0)
-    return 0x01;
-  else
-    return 0x00;
-}
diff --git a/src/uart_usb.c b/src/uart_usb.c
deleted file mode 100644
index 8c82b88..0000000
--- a/src/uart_usb.c
+++ /dev/null
@@ -1,246 +0,0 @@
-#include <avr/io.h>
-#include <avr/interrupt.h>
-#include "uart_usb.h"
-#include "mem.h"
-
-#define UART_USB_DEFAULT_BAUDRATE 9600
-
-#define UART_USB_RX_BUFFER_SIZE   0x20
-
-#define UART_USB_TX_PORT          PORTD
-#define UART_USB_TX_DDR           DDRD
-#define UART_USB_TX_PIN           PD5 
-
-#define UART_USB_RX_PORT          PORTD
-#define UART_USB_RX_DDR           DDRD
-#define UART_USB_RX_PORTIN        PIND
-#define UART_USB_RX_PIN           PD4 
-
-// uartsw transmit status and data variables
-volatile uint8_t uart_usb_tx_busy;
-volatile uint8_t uart_usb_tx_data;
-volatile uint8_t uart_usb_tx_bit_num;
-
-// baud rate common to transmit and receive
-volatile uint16_t uart_usb_baudrate_div;
-
-// uartsw receive status and data variables
-volatile uint8_t uart_usb_rx_busy;
-volatile uint8_t uart_usb_rx_data;
-volatile uint8_t uart_usb_rx_bit_num;
-
-/* rx buffer */
-unsigned char uart_usb_rx_data_buffer[UART_USB_RX_BUFFER_SIZE];
-unsigned char uart_usb_rx_read_ptr;
-unsigned char uart_usb_rx_write_ptr;
-unsigned char uart_usb_rx_num_data;
-
-/* private functions */
-
-/* interrupt handlers */
-ISR(TIMER1_CAPT_vect)//RX
-{
-  uint16_t capture;
-  // clear ICP interrupt flag
-  TIFR|=(1<<ICF1);
-  
-  if(!uart_usb_rx_busy)
-  {
-    // disable input capture interrutps
-    TIMSK&=~(1<<TICIE1);
-    capture=TCNT1+uart_usb_baudrate_div + uart_usb_baudrate_div/2;
-    // schedule data bit sampling 1.5 bit periods from now
-    OCR1BH=(capture>>8)&0xFF;
-    OCR1BL=capture&0xFF;
-    // clear OC1B interrupt flag
-    TIFR|=(1<<OCF1B);
-    // enable OC1B interrupt
-    TIMSK|=(1<<OCIE1B);
-    // set start bit flag
-    uart_usb_rx_busy = 0x01;
-    // reset bit counter
-    uart_usb_rx_bit_num = 0;
-    // reset data
-    uart_usb_rx_data = 0;
-  }
-}
-
-ISR(TIMER1_COMPB_vect)//RX
-{
-  uint16_t capture;
-
-  // clear OC1B interrupt flag
-  TIFR|=(1<<OCF1B);
-  // shift data byte to make room for new bit
-  uart_usb_rx_data = uart_usb_rx_data>>1;
-
-  if(UART_USB_RX_PORTIN&(1<<UART_USB_RX_PIN))
-    uart_usb_rx_data |= 0x80;
-
-  // increment bit counter
-  uart_usb_rx_bit_num++;
-  // schedule next bit sample
-  capture=OCR1B+uart_usb_baudrate_div;
-  OCR1BH=(capture>>8)&0xFF;
-  OCR1BL=capture&0xFF;
-
-  // check if we have a full byte
-  if(uart_usb_rx_bit_num >= 8)
-  {
-    // save data in receive buffer
-    uart_usb_rx_data_buffer[uart_usb_rx_write_ptr]=uart_usb_rx_data;
-    uart_usb_rx_write_ptr=(uart_usb_rx_write_ptr+1)%UART_USB_RX_BUFFER_SIZE;
-    uart_usb_rx_num_data++;
-    // disable OC1B interrupt
-    TIMSK&=~(1<<OCIE1B);
-    // enable ICP interrupt
-    TIMSK|=(1<<TICIE1);
-    // clear start bit flag
-    uart_usb_rx_busy = 0x00;
-  }
-}
-
-ISR(TIMER1_COMPA_vect)//TX
-{
-  uint16_t capture;
-
-  // clear OC1B interrupt flag
-  TIFR|=(1<<OCF1A);
-  if(uart_usb_tx_bit_num)
-  {
-    if(uart_usb_tx_bit_num>1)
-    {
-      // transmit data bits (inverted, LSB first)
-      if((uart_usb_tx_data&0x01))
-        UART_USB_TX_PORT|=(1<<UART_USB_TX_PIN);
-      else
-        UART_USB_TX_PORT&=~(1<<UART_USB_TX_PIN);
-      // shift bits down
-      uart_usb_tx_data = uart_usb_tx_data>>1;
-    }
-    else
-      UART_USB_TX_PORT|=(1<<UART_USB_TX_PIN);
-    // schedule the next bit
-    capture=OCR1A+uart_usb_baudrate_div;
-    OCR1AH=(capture>>8)&0xFF;
-    OCR1AL=capture&0xFF;
-    // count down
-    uart_usb_tx_bit_num--;
-  }
-  else
-  {
-    // enable OC1A interrupt
-    TIMSK&=~(1<<OCIE1A);
-    uart_usb_tx_busy = 0x00;
-  }
-}
-
-/* public functions */
-void uart_usb_init(void)
-{
-  // configure GPIO ports
-  UART_USB_TX_DDR|=(1<<UART_USB_TX_PIN);// output
-  UART_USB_RX_DDR&=~(1<<UART_USB_RX_PIN);//input
-  // set input to 0
-  UART_USB_RX_PORT&=~(1<<UART_USB_RX_PIN);
-  // initialize baud rate
-  uart_usb_set_baudrate(UART_USB_DEFAULT_BAUDRATE);
-  ram_data[UART_TTL_BAUDRATE_L]=UART_USB_DEFAULT_BAUDRATE%256;
-  ram_data[UART_TTL_BAUDRATE_H]=UART_USB_DEFAULT_BAUDRATE/256;
-
-  // setup the transmitter
-  uart_usb_tx_busy = 0x00;
-  TIMSK&=~(1<<OCIE1A);
-
-  // setup the receiver
-  uart_usb_rx_busy = 0x00;
-  TIMSK&=~(1<<OCIE1B);
-  // trigger on falling edge 
-  TCCR1B&=~(1<<ICES1);
-  // enable ICP interrupt
-  TIMSK|=(1<<TICIE1);
-
-  /* initlaize buffer variables */
-  uart_usb_rx_read_ptr=0;
-  uart_usb_rx_write_ptr=0;
-  uart_usb_rx_num_data=0;
-}
-
-void uart_usb_start(void)
-{
-  TIMSK&=~(1<<OCIE1A);
-  TIMSK&=~(1<<OCIE1B);
-  // clear ICP interrupt flag
-  TIFR|=(1<<ICF1);
-  TIMSK|=(1<<TICIE1);
-  ram_data[UART_USB_CONTROL]|=0x20;
-}
-
-void uart_usb_stop(void)
-{
-  // disable interrupts
-  TIMSK&=~(1<<OCIE1A);
-  TIMSK&=~(1<<OCIE1B);
-  TIMSK&=~(1<<TICIE1);
-  ram_data[UART_USB_CONTROL]&=0xDF;
-}
-
-void uart_usb_set_baudrate(uint32_t baudrate)
-{
-  TCCR1B&=0xF8;
-  TCCR1B|=0x01;
-  // calculate division factor for requested baud rate, and set it
-  uart_usb_baudrate_div = (uint16_t)((F_CPU+(baudrate/2L))/(baudrate*1L));
-}
-
-void uart_usb_send_byte(uint8_t data)
-{
-  uint16_t capture;
-
-  // wait until uart is ready
-  while(uart_usb_tx_busy);
-  // set busy flag
-  uart_usb_tx_busy = 0x01;
-  // save data
-  uart_usb_tx_data = data;
-  // set number of bits (+1 for stop bit)
-  uart_usb_tx_bit_num = 9;
-
-  UART_USB_TX_PORT&=~(1<<UART_USB_TX_PIN);
-
-  capture=TCNT1+uart_usb_baudrate_div;
-  OCR1AH=(capture>>8)&0xFF;
-  OCR1AL=capture&0xFF;
-  // clear interrupts
-  TIFR|=(1<<OCF1A);
-  // enable OC1A interrupt
-  TIMSK|=(1<<OCIE1A);
-}
-
-uint8_t uart_usb_is_sending(void)
-{
-  return uart_usb_tx_busy;
-}
-
-uint8_t uart_usb_receive_byte(uint8_t* data)
-{
-  // make sure we have a receive buffer
-  if(uart_usb_rx_num_data>0)
-  {
-    *data=uart_usb_rx_data_buffer[uart_usb_rx_read_ptr];
-    uart_usb_rx_read_ptr=(uart_usb_rx_read_ptr+1)%UART_USB_RX_BUFFER_SIZE;
-    uart_usb_rx_num_data--;
-    // make sure we have data
-    return 0x01;
-  }
-  else
-    return 0x00;
-}
-
-uint8_t uart_usb_is_data_available(void)
-{
-  if(uart_usb_rx_num_data>0)
-    return 0x01;
-  else
-    return 0x00;
-}
diff --git a/timer128.c b/timer128.c
new file mode 100755
index 0000000..eb60873
--- /dev/null
+++ b/timer128.c
@@ -0,0 +1,687 @@
+/*! \file timer128.c \brief System Timer function library for Mega128. */
+//*****************************************************************************
+//
+// File Name	: 'timer128.c'
+// Title		: System Timer function library for Mega128
+// Author		: Pascal Stang - Copyright (C) 2000-2003
+// Created		: 11/22/2000
+// Revised		: 02/24/2003
+// Version		: 1.2
+// Target MCU	: Atmel AVR Series
+// Editor Tabs	: 4
+//
+// This code is distributed under the GNU Public License
+//		which can be found at http://www.gnu.org/licenses/gpl.txt
+//
+//*****************************************************************************
+
+#include <avr/io.h>
+#include <avr/interrupt.h>
+#include <avr/pgmspace.h>
+#include <avr/sleep.h>
+
+#include "global.h"
+#include "timer128.h"
+
+// Program ROM constants
+// the prescale division values stored in order of timer control register index
+// STOP, CLK, CLK/8, CLK/64, CLK/256, CLK/1024
+const unsigned short __attribute__ ((progmem)) TimerPrescaleFactor[] = {0,1,8,64,256,1024};
+// the prescale division values stored in order of timer control register index
+// STOP, CLK, CLK/8, CLK/32, CLK/64, CLK/128, CLK/256, CLK/1024
+const unsigned short __attribute__ ((progmem)) TimerRTCPrescaleFactor[] = {0,1,8,32,64,128,256,1024};
+
+// Global variables
+// time registers
+volatile unsigned long TimerPauseReg;
+volatile unsigned long Timer0Reg0;
+volatile unsigned long Timer0Reg1;
+volatile unsigned long Timer2Reg0;
+volatile unsigned long Timer2Reg1;
+
+typedef void (*voidFuncPtr)(void);
+volatile static voidFuncPtr TimerIntFunc[TIMER_NUM_INTERRUPTS];
+
+// delay for a minimum of <us> microseconds 
+// the time resolution is dependent on the time the loop takes 
+// e.g. with 4Mhz and 5 cycles per loop, the resolution is 1.25 us 
+void delay_us(unsigned short time_us) 
+{
+	unsigned short delay_loops;
+	register unsigned short i;
+
+	delay_loops = (time_us+3)/5*CYCLES_PER_US; // +3 for rounding up (dirty) 
+
+	// one loop takes 5 cpu cycles 
+	for (i=0; i < delay_loops; i++) {};
+}
+/*
+void delay_ms(unsigned char time_ms)
+{
+	unsigned short delay_count = F_CPU / 4000;
+
+	unsigned short cnt;
+	asm volatile ("\n"
+                  "L_dl1%=:\n\t"
+                  "mov %A0, %A2\n\t"
+                  "mov %B0, %B2\n"
+                  "L_dl2%=:\n\t"
+                  "sbiw %A0, 1\n\t"
+                  "brne L_dl2%=\n\t"
+                  "dec %1\n\t" "brne L_dl1%=\n\t":"=&w" (cnt)
+                  :"r"(time_ms), "r"((unsigned short) (delay_count))
+	);
+}
+*/
+void timerInit(void)
+{
+	u08 intNum;
+	// detach all user functions from interrupts
+	for(intNum=0; intNum<TIMER_NUM_INTERRUPTS; intNum++)
+		timerDetach(intNum);
+
+	// initialize all timers
+	timer0Init();
+	timer1Init();
+	timer2Init();
+	timer3Init();
+}
+
+void timer0Init()
+{
+	// initialize timer 0
+	timer0SetPrescaler( TIMER0PRESCALE );	// set prescaler
+	outb(TCNT0, 0);							// reset TCNT0
+	sbi(TIMSK, TOIE0);						// enable TCNT0 overflow interrupt
+
+	timer0ClearOverflowCount();				// initialize time registers
+}
+
+void timer1Init(void)
+{
+	// initialize timer 1
+	timer1SetPrescaler( TIMER1PRESCALE );	// set prescaler
+	outb(TCNT1H, 0);						// reset TCNT1
+	outb(TCNT1L, 0);
+	sbi(TIMSK, TOIE1);						// enable TCNT1 overflow
+}
+
+void timer2Init(void)
+{
+	// initialize timer 2
+	timer2SetPrescaler( TIMER2PRESCALE );	// set prescaler
+	outb(TCNT2, 0);							// reset TCNT2
+	sbi(TIMSK, TOIE2);						// enable TCNT2 overflow
+
+	timer2ClearOverflowCount();				// initialize time registers
+}
+
+void timer3Init(void)
+{
+	// initialize timer 3
+	timer3SetPrescaler( TIMER3PRESCALE );	// set prescaler
+	outb(TCNT3H, 0);						// reset TCNT3
+	outb(TCNT3L, 0);
+	sbi(ETIMSK, TOIE3);						// enable TCNT3 overflow
+}
+
+void timer0SetPrescaler(u08 prescale)
+{
+	// set prescaler on timer 0
+	outb(TCCR0, (inb(TCCR0) & ~TIMER_PRESCALE_MASK) | prescale);
+}
+
+void timer1SetPrescaler(u08 prescale)
+{
+	// set prescaler on timer 1
+	outb(TCCR1B, (inb(TCCR1B) & ~TIMER_PRESCALE_MASK) | prescale);
+}
+
+void timer2SetPrescaler(u08 prescale)
+{
+	// set prescaler on timer 2
+	outb(TCCR2, (inb(TCCR2) & ~TIMER_PRESCALE_MASK) | prescale);
+}
+
+void timer3SetPrescaler(u08 prescale)
+{
+	// set prescaler on timer 2
+	outb(TCCR3B, (inb(TCCR3B) & ~TIMER_PRESCALE_MASK) | prescale);
+}
+
+u16 timer0GetPrescaler(void)
+{
+	// get the current prescaler setting
+	return (pgm_read_word(TimerPrescaleFactor+(inb(TCCR0) & TIMER_PRESCALE_MASK)));
+}
+
+u16 timer1GetPrescaler(void)
+{
+	// get the current prescaler setting
+	return (pgm_read_word(TimerPrescaleFactor+(inb(TCCR1B) & TIMER_PRESCALE_MASK)));
+}
+
+u16 timer2GetPrescaler(void)
+{
+	// get the current prescaler setting
+	return (pgm_read_word(TimerPrescaleFactor+(inb(TCCR2) & TIMER_PRESCALE_MASK)));
+}
+
+u16 timer3GetPrescaler(void)
+{
+	// get the current prescaler setting
+	return (pgm_read_word(TimerPrescaleFactor+(inb(TCCR3B) & TIMER_PRESCALE_MASK)));
+}
+
+void timerAttach(u08 interruptNum, void (*userFunc)(void) )
+{
+	// make sure the interrupt number is within bounds
+	if(interruptNum < TIMER_NUM_INTERRUPTS)
+	{
+		// set the interrupt function to run
+		// the supplied user's function
+		TimerIntFunc[interruptNum] = userFunc;
+	}
+}
+
+void timerDetach(u08 interruptNum)
+{
+	// make sure the interrupt number is within bounds
+	if(interruptNum < TIMER_NUM_INTERRUPTS)
+	{
+		// set the interrupt function to run nothing
+		TimerIntFunc[interruptNum] = 0;
+	}
+}
+
+void timerPause(unsigned short pause_ms)
+{
+	// pauses for exactly <pause_ms> number of milliseconds
+	u08 timerThres;
+	u32 ticRateHz;
+	u32 pause;
+
+	// capture current pause timer value
+	timerThres = inb(TCNT2);
+	// reset pause timer overflow count
+	TimerPauseReg = 0;
+	// calculate delay for [pause_ms] milliseconds
+	// prescaler division = 1<<(pgm_read_byte(TimerPrescaleFactor+inb(TCCR2)))
+	ticRateHz = F_CPU/timer2GetPrescaler();
+	// precision management
+	// prevent overflow and precision underflow
+	//	-could add more conditions to improve accuracy
+	if( ((ticRateHz < 429497) && (pause_ms <= 10000)) )
+		pause = (pause_ms*ticRateHz)/1000;
+	else
+		pause = pause_ms*(ticRateHz/1000);
+	
+	// loop until time expires
+	while( ((TimerPauseReg<<8) | inb(TCNT2)) < (pause+timerThres) )
+	{
+		if( TimerPauseReg < (pause>>8));
+		{
+			// save power by idling the processor
+			set_sleep_mode(SLEEP_MODE_IDLE);
+			sleep_mode();
+		}
+	}
+}
+
+void timer0ClearOverflowCount(void)
+{
+	// clear the timer overflow counter registers
+	Timer0Reg0 = 0;	// initialize time registers
+	Timer0Reg1 = 0;	// initialize time registers
+}
+
+long timer0GetOverflowCount(void)
+{
+	// return the current timer overflow count
+	// (this is since the last timer0ClearOverflowCount() command was called)
+	return Timer0Reg0;
+}
+
+void timer2ClearOverflowCount(void)
+{
+	// clear the timer overflow counter registers
+	Timer2Reg0 = 0;	// initialize time registers
+	Timer2Reg1 = 0;	// initialize time registers
+}
+
+long timer2GetOverflowCount(void)
+{
+	// return the current timer overflow count
+	// (this is since the last timer2ClearOverflowCount() command was called)
+	return Timer2Reg0;
+}
+
+
+void timer1PWMInit(u08 bitRes)
+{
+	// configures timer1 for use with PWM output
+	// on pins OC1A, OC1B, and OC1C
+
+	// enable Timer1 as 8,9,10bit PWM
+	if(bitRes == 9)
+	{	// 9bit mode
+		sbi(TCCR1A,WGMA1);
+		cbi(TCCR1A,WGMA0);
+	}
+	else if( bitRes == 10 )
+	{	// 10bit mode
+		sbi(TCCR1A,WGMA1);
+		sbi(TCCR1A,WGMA0);
+	}
+	else
+	{	// default 8bit mode
+		cbi(TCCR1A,WGMA1);
+		sbi(TCCR1A,WGMA0);
+	}
+
+	// set clear-timer-on-compare-match
+	//cbi(TCCR1B,CTC1);
+	// clear output compare value A
+	outb(OCR1AH, 0);
+	outb(OCR1AL, 0);
+	// clear output compare value B
+	outb(OCR1BH, 0);
+	outb(OCR1BL, 0);
+	// clear output compare value C
+	outb(OCR1CH, 0);
+	outb(OCR1CL, 0);
+}
+
+void timer1PWMInitICR(u16 topcount)
+{
+	// set PWM mode with ICR top-count
+	cbi(TCCR1A,WGM10);
+	sbi(TCCR1A,WGM11);
+	sbi(TCCR1B,WGM12);
+	sbi(TCCR1B,WGM13);
+	
+	// set top count value
+	ICR1H = (u08)(topcount>>8);
+	ICR1L = (u08)topcount;
+	
+	// clear output compare value A
+	outb(OCR1AH, 0);
+	outb(OCR1AL, 0);
+	// clear output compare value B
+	outb(OCR1BH, 0);
+	outb(OCR1BL, 0);
+	// clear output compare value C
+	outb(OCR1CH, 0);
+	outb(OCR1CL, 0);
+}
+
+void timer1PWMOff(void)
+{
+	// turn off PWM on Timer1
+	cbi(TCCR1A,WGMA1);
+	cbi(TCCR1A,WGMA0);
+	// clear (disable) clear-timer-on-compare-match
+	//cbi(TCCR1B,CTC1);
+	// set PWM1A/B/C (OutputCompare action) to none
+	timer1PWMAOff();
+	timer1PWMBOff();
+	timer1PWMCOff();
+}
+
+void timer1PWMAOn(void)
+{
+	// turn on channel A (OC1A) PWM output
+	// set OC1A as non-inverted PWM
+	sbi(TCCR1A,COMA1);
+	cbi(TCCR1A,COMA0);
+}
+
+void timer1PWMBOn(void)
+{
+	// turn on channel B (OC1B) PWM output
+	// set OC1B as non-inverted PWM
+	sbi(TCCR1A,COMB1);
+	cbi(TCCR1A,COMB0);
+}
+
+void timer1PWMCOn(void)
+{
+	// turn on channel C (OC1C) PWM output
+	// set OC1C as non-inverted PWM
+	sbi(TCCR1A,COMC1);
+	cbi(TCCR1A,COMC0);
+}
+
+void timer1PWMAOff(void)
+{
+	// turn off channel A (OC1A) PWM output
+	// set OC1A (OutputCompare action) to none
+	cbi(TCCR1A,COMA1);
+	cbi(TCCR1A,COMA0);
+}
+
+void timer1PWMBOff(void)
+{
+	// turn off channel B (OC1B) PWM output
+	// set OC1B (OutputCompare action) to none
+	cbi(TCCR1A,COMB1);
+	cbi(TCCR1A,COMB0);
+}
+
+void timer1PWMCOff(void)
+{
+	// turn off channel C (OC1C) PWM output
+	// set OC1C (OutputCompare action) to none
+	cbi(TCCR1A,COMC1);
+	cbi(TCCR1A,COMC0);
+}
+
+void timer1PWMASet(u16 pwmDuty)
+{
+	// set PWM (output compare) duty for channel A
+	// this PWM output is generated on OC1A pin
+	// NOTE:	pwmDuty should be in the range 0-255 for 8bit PWM
+	//			pwmDuty should be in the range 0-511 for 9bit PWM
+	//			pwmDuty should be in the range 0-1023 for 10bit PWM
+	outb(OCR1AH, (pwmDuty>>8));		// set the high 8bits of OCR1A
+	outb(OCR1AL, (pwmDuty&0x00FF));	// set the low 8bits of OCR1A
+}
+
+void timer1PWMBSet(u16 pwmDuty)
+{
+	// set PWM (output compare) duty for channel B
+	// this PWM output is generated on OC1B pin
+	// NOTE:	pwmDuty should be in the range 0-255 for 8bit PWM
+	//			pwmDuty should be in the range 0-511 for 9bit PWM
+	//			pwmDuty should be in the range 0-1023 for 10bit PWM
+	outb(OCR1BH, (pwmDuty>>8));		// set the high 8bits of OCR1B
+	outb(OCR1BL, (pwmDuty&0x00FF));	// set the low 8bits of OCR1B
+}
+
+void timer1PWMCSet(u16 pwmDuty)
+{
+	// set PWM (output compare) duty for channel C
+	// this PWM output is generated on OC1C pin
+	// NOTE:	pwmDuty should be in the range 0-255 for 8bit PWM
+	//			pwmDuty should be in the range 0-511 for 9bit PWM
+	//			pwmDuty should be in the range 0-1023 for 10bit PWM
+	outb(OCR1CH, (pwmDuty>>8));		// set the high 8bits of OCR1C
+	outb(OCR1CL, (pwmDuty&0x00FF));	// set the low 8bits of OCR1C
+}
+
+
+void timer3PWMInit(u08 bitRes)
+{
+	// configures timer1 for use with PWM output
+	// on pins OC3A, OC3B, and OC3C
+
+	// enable Timer3 as 8,9,10bit PWM
+	if(bitRes == 9)
+	{	// 9bit mode
+		sbi(TCCR3A,WGMA1);
+		cbi(TCCR3A,WGMA0);
+	}
+	else if( bitRes == 10 )
+	{	// 10bit mode
+		sbi(TCCR3A,WGMA1);
+		sbi(TCCR3A,WGMA0);
+	}
+	else
+	{	// default 8bit mode
+		cbi(TCCR3A,WGMA1);
+		sbi(TCCR3A,WGMA0);
+	}
+
+	// set clear-timer-on-compare-match
+	//cbi(TCCR3B,CTC1);
+	// clear output compare value A
+	outb(OCR3AH, 0);
+	outb(OCR3AL, 0);
+	// clear output compare value B
+	outb(OCR3BH, 0);
+	outb(OCR3BL, 0);
+	// clear output compare value B
+	outb(OCR3CH, 0);
+	outb(OCR3CL, 0);
+}
+
+void timer3PWMInitICR(u16 topcount)
+{
+	// set PWM mode with ICR top-count
+	cbi(TCCR3A,WGM30);
+	sbi(TCCR3A,WGM31);
+	sbi(TCCR3B,WGM32);
+	sbi(TCCR3B,WGM33);
+	
+	// set top count value
+	ICR3H = (u08)(topcount>>8);
+	ICR3L = (u08)topcount;
+	
+	// clear output compare value A
+	outb(OCR3AH, 0);
+	outb(OCR3AL, 0);
+	// clear output compare value B
+	outb(OCR3BH, 0);
+	outb(OCR3BL, 0);
+	// clear output compare value C
+	outb(OCR3CH, 0);
+	outb(OCR3CL, 0);
+}
+
+void timer3PWMOff(void)
+{
+	// turn off PWM mode on Timer3
+	cbi(TCCR3A,WGMA1);
+	cbi(TCCR3A,WGMA0);
+	// clear (disable) clear-timer-on-compare-match
+	//cbi(TCCR3B,CTC1);
+	// set OC3A/B/C (OutputCompare action) to none
+	timer3PWMAOff();
+	timer3PWMBOff();
+	timer3PWMCOff();
+}
+
+void timer3PWMAOn(void)
+{
+	// turn on channel A (OC3A) PWM output
+	// set OC3A as non-inverted PWM
+	sbi(TCCR3A,COMA1);
+	cbi(TCCR3A,COMA0);
+}
+
+void timer3PWMBOn(void)
+{
+	// turn on channel B (OC3B) PWM output
+	// set OC3B as non-inverted PWM
+	sbi(TCCR3A,COMB1);
+	cbi(TCCR3A,COMB0);
+}
+
+void timer3PWMCOn(void)
+{
+	// turn on channel C (OC3C) PWM output
+	// set OC3C as non-inverted PWM
+	sbi(TCCR3A,COMC1);
+	cbi(TCCR3A,COMC0);
+}
+
+void timer3PWMAOff(void)
+{
+	// turn off channel A (OC3A) PWM output
+	// set OC3A (OutputCompare action) to none
+	cbi(TCCR3A,COMA1);
+	cbi(TCCR3A,COMA0);
+}
+
+void timer3PWMBOff(void)
+{
+	// turn off channel B (OC3B) PWM output
+	// set OC3B (OutputCompare action) to none
+	cbi(TCCR3A,COMB1);
+	cbi(TCCR3A,COMB0);
+}
+
+void timer3PWMCOff(void)
+{
+	// turn off channel C (OC3C) PWM output
+	// set OC3C (OutputCompare action) to none
+	cbi(TCCR3A,COMC1);
+	cbi(TCCR3A,COMC0);
+}
+
+void timer3PWMASet(u16 pwmDuty)
+{
+	// set PWM (output compare) duty for channel A
+	// this PWM output is generated on OC3A pin
+	// NOTE:	pwmDuty should be in the range 0-255 for 8bit PWM
+	//			pwmDuty should be in the range 0-511 for 9bit PWM
+	//			pwmDuty should be in the range 0-1023 for 10bit PWM
+	outb(OCR3AH, (pwmDuty>>8));		// set the high 8bits of OCR3A
+	outb(OCR3AL, (pwmDuty&0x00FF));	// set the low 8bits of OCR3A
+}
+
+void timer3PWMBSet(u16 pwmDuty)
+{
+	// set PWM (output compare) duty for channel B
+	// this PWM output is generated on OC3B pin
+	// NOTE:	pwmDuty should be in the range 0-255 for 8bit PWM
+	//			pwmDuty should be in the range 0-511 for 9bit PWM
+	//			pwmDuty should be in the range 0-1023 for 10bit PWM
+	outb(OCR3BH, (pwmDuty>>8));		// set the high 8bits of OCR3B
+	outb(OCR3BL, (pwmDuty&0x00FF));	// set the low 8bits of OCR3B
+}
+
+void timer3PWMCSet(u16 pwmDuty)
+{
+	// set PWM (output compare) duty for channel B
+	// this PWM output is generated on OC3C pin
+	// NOTE:	pwmDuty should be in the range 0-255 for 8bit PWM
+	//			pwmDuty should be in the range 0-511 for 9bit PWM
+	//			pwmDuty should be in the range 0-1023 for 10bit PWM
+	outb(OCR3CH, (pwmDuty>>8));		// set the high 8bits of OCR3C
+	outb(OCR3CL, (pwmDuty&0x00FF));	// set the low 8bits of OCR3C
+}
+
+
+//! Interrupt handler for tcnt0 overflow interrupt
+TIMER_INTERRUPT_HANDLER(TIMER0_OVF_vect)
+{
+	Timer0Reg0++;		// increment low-order counter
+	if(!Timer0Reg0)		// if low-order counter rollover
+		Timer0Reg1++;	// increment high-order counter	
+
+	// if a user function is defined, execute it too
+	if(TimerIntFunc[TIMER0OVERFLOW_INT])
+		TimerIntFunc[TIMER0OVERFLOW_INT]();
+}
+
+//! Interrupt handler for Timer1 overflow interrupt
+TIMER_INTERRUPT_HANDLER(TIMER1_OVF_vect)
+{
+	// if a user function is defined, execute it
+	if(TimerIntFunc[TIMER1OVERFLOW_INT])
+		TimerIntFunc[TIMER1OVERFLOW_INT]();
+}
+
+//! Interrupt handler for Timer2 overflow interrupt
+TIMER_INTERRUPT_HANDLER(TIMER2_OVF_vect)
+{
+	Timer2Reg0++;		// increment low-order counter
+	if(!Timer2Reg0)		// if low-order counter rollover
+		Timer2Reg1++;	// increment high-order counter	
+
+	// increment pause counter
+	TimerPauseReg++;
+
+	// if a user function is defined, execute it
+	if(TimerIntFunc[TIMER2OVERFLOW_INT])
+		TimerIntFunc[TIMER2OVERFLOW_INT]();
+}
+
+//! Interrupt handler for Timer3 overflow interrupt
+TIMER_INTERRUPT_HANDLER(TIMER3_OVF_vect)
+{
+	// if a user function is defined, execute it
+	if(TimerIntFunc[TIMER3OVERFLOW_INT])
+		TimerIntFunc[TIMER3OVERFLOW_INT]();
+}
+
+//! Interrupt handler for OutputCompare0 match (OC0) interrupt
+TIMER_INTERRUPT_HANDLER(TIMER0_COMP_vect)
+{
+	// if a user function is defined, execute it
+	if(TimerIntFunc[TIMER0OUTCOMPARE_INT])
+		TimerIntFunc[TIMER0OUTCOMPARE_INT]();
+}
+
+//! Interrupt handler for OutputCompare1A match (OC1A) interrupt
+TIMER_INTERRUPT_HANDLER(TIMER1_COMPA_vect)
+{
+	// if a user function is defined, execute it
+	if(TimerIntFunc[TIMER1OUTCOMPAREA_INT])
+		TimerIntFunc[TIMER1OUTCOMPAREA_INT]();
+}
+
+//! Interrupt handler for OutputCompare1B match (OC1B) interrupt
+TIMER_INTERRUPT_HANDLER(TIMER1_COMPB_vect)
+{
+	// if a user function is defined, execute it
+	if(TimerIntFunc[TIMER1OUTCOMPAREB_INT])
+		TimerIntFunc[TIMER1OUTCOMPAREB_INT]();
+}
+
+//! Interrupt handler for OutputCompare1C match (OC1C) interrupt
+TIMER_INTERRUPT_HANDLER(TIMER1_COMPC_vect)
+{
+	// if a user function is defined, execute it
+	if(TimerIntFunc[TIMER1OUTCOMPAREC_INT])
+		TimerIntFunc[TIMER1OUTCOMPAREC_INT]();
+}
+
+//! Interrupt handler for InputCapture1(IC1) interrupt
+TIMER_INTERRUPT_HANDLER(TIMER1_CAPT_vect)
+{
+	// if a user function is defined, execute it
+	if(TimerIntFunc[TIMER1INPUTCAPTURE_INT])
+		TimerIntFunc[TIMER1INPUTCAPTURE_INT]();
+}
+
+//! Interrupt handler for OutputCompare2 match (OC2) interrupt
+TIMER_INTERRUPT_HANDLER(TIMER2_COMP_vect)
+{
+	// if a user function is defined, execute it
+	if(TimerIntFunc[TIMER2OUTCOMPARE_INT])
+		TimerIntFunc[TIMER2OUTCOMPARE_INT]();
+}
+
+//! Interrupt handler for OutputCompare3A match (OC3A) interrupt
+TIMER_INTERRUPT_HANDLER(TIMER3_COMPA_vect)
+{
+	// if a user function is defined, execute it
+	if(TimerIntFunc[TIMER3OUTCOMPAREA_INT])
+		TimerIntFunc[TIMER3OUTCOMPAREA_INT]();
+}
+
+//! Interrupt handler for OutputCompare3B match (OC3B) interrupt
+TIMER_INTERRUPT_HANDLER(TIMER3_COMPB_vect)
+{
+	// if a user function is defined, execute it
+	if(TimerIntFunc[TIMER3OUTCOMPAREB_INT])
+		TimerIntFunc[TIMER3OUTCOMPAREB_INT]();
+}
+
+//! Interrupt handler for OutputCompare3C match (OC3C) interrupt
+TIMER_INTERRUPT_HANDLER(TIMER3_COMPC_vect)
+{
+	// if a user function is defined, execute it
+	if(TimerIntFunc[TIMER3OUTCOMPAREC_INT])
+		TimerIntFunc[TIMER3OUTCOMPAREC_INT]();
+}
+
+//! Interrupt handler for InputCapture3 (IC3) interrupt
+TIMER_INTERRUPT_HANDLER(TIMER3_CAPT_vect)
+{
+	// if a user function is defined, execute it
+	if(TimerIntFunc[TIMER3INPUTCAPTURE_INT])
+		TimerIntFunc[TIMER3INPUTCAPTURE_INT]();
+}
diff --git a/timer128.h b/timer128.h
new file mode 100755
index 0000000..99ff893
--- /dev/null
+++ b/timer128.h
@@ -0,0 +1,300 @@
+/*! \file timer128.h \brief System Timer function library for Mega128. */
+//*****************************************************************************
+//
+// File Name	: 'timer128.h'
+// Title		: System Timer function library for Mega128
+// Author		: Pascal Stang - Copyright (C) 2000-2003
+// Created		: 11/22/2000
+// Revised		: 02/10/2003
+// Version		: 1.1
+// Target MCU	: Atmel AVR Series
+// Editor Tabs	: 4
+//
+// This code is distributed under the GNU Public License
+//		which can be found at http://www.gnu.org/licenses/gpl.txt
+//
+///	\ingroup driver_avr
+/// \defgroup timer128 Timer Function Library for ATmega128 (timer128.c)
+/// \code #include "timer128.h" \endcode
+/// \par Overview
+///		This library provides functions for use with the timers internal to the
+///		AVR ATmega128.  Functions include initialization, set prescaler,
+///		calibrated pause function (in milliseconds), attaching and detaching
+///		of user functions to interrupts, overflow counters, and PWM.
+///
+/// \par About Timers
+///		The Atmel AVR-series processors each contain at least one
+///		hardware timer/counter.  Many of the processors contain 2 or 3
+///		timers.  Generally speaking, a timer is a hardware counter inside
+///		the processor which counts at a rate related to the main CPU clock
+///		frequency.  Because the counter value increasing (counting up) at
+///		a precise rate, we can use it as a timer to create or measure 
+///		precise delays, schedule events, or generate signals of a certain
+///		frequency or pulse-width.
+/// \par
+///		As an example, the ATmega163 processor has 3 timer/counters.
+///		Timer0, Timer1, and Timer2 are 8, 16, and 8 bits wide respectively.
+///		This means that they overflow, or roll over back to zero, at a
+///		count value of 256 for 8bits or 65536 for 16bits.  A prescaler is
+///		avaiable for each timer, and the prescaler allows you to pre-divide
+///		the main CPU clock rate down to a slower speed before feeding it to
+///		the counting input of a timer.  For example, if the CPU clock
+///		frequency is 3.69MHz, and Timer0's prescaler is set to divide-by-8,
+///		then Timer0 will "tic" at 3690000/8 = 461250Hz.  Because Timer0 is
+///		an 8bit timer, it will count to 256 in just 256/461250Hz = 0.555ms.
+///		In fact, when it hits 255, it will overflow and start again at
+///		zero.  In this case, Timer0 will overflow 461250/256 = 1801.76
+///		times per second.
+/// \par
+///		Timer0 can be used a number of ways simultaneously.  First, the
+///		value of the timer can be read by accessing the CPU register \c TCNT0.
+///		We could, for example, figure out how long it takes to execute a
+///		C command by recording the value of \c TCNT0 before and after
+///		execution, then subtract (after-before) = time elapsed.  Or we can
+///		enable the overflow interrupt which goes off every time T0
+///		overflows and count out longer delays (multiple overflows), or
+///		execute a special periodic function at every overflow.
+/// \par
+///		The other timers (Timer1 and Timer2) offer all the abilities of
+///		Timer0 and many more features.  Both T1 and T2 can operate as
+///		general-purpose timers, but T1 has special hardware allowing it to
+///		generate PWM signals, while T2 is specially designed to help count
+///		out real time (like hours, minutes, seconds).  See the
+///		Timer/Counter section of the processor datasheet for more info.
+///
+//*****************************************************************************
+//@{
+
+#ifndef TIMER128_H
+#define TIMER128_H
+
+#include "global.h"
+
+// constants/macros/typdefs
+
+// Timer/clock prescaler values and timer overflow rates
+// tics = rate at which the timer counts up
+// 8bitoverflow = rate at which the timer overflows 8bits (or reaches 256)
+// 16bit [overflow] = rate at which the timer overflows 16bits (65536)
+// 
+// overflows can be used to generate periodic interrupts
+//
+// for 8MHz crystal
+// 0 = STOP (Timer not counting)
+// 1 = CLOCK		tics= 8MHz			8bitoverflow= 31250Hz		16bit= 122.070Hz
+// 2 = CLOCK/8		tics= 1MHz			8bitoverflow= 3906.25Hz		16bit=  15.259Hz
+// 3 = CLOCK/64		tics= 125kHz		8bitoverflow=  488.28Hz		16bit=   1.907Hz
+// 4 = CLOCK/256	tics= 31250Hz		8bitoverflow=  122.07Hz		16bit=	0.477Hz
+// 5 = CLOCK/1024	tics= 7812.5Hz		8bitoverflow=   30.52Hz		16bit=   0.119Hz
+// 6 = External Clock on T(x) pin (falling edge)
+// 7 = External Clock on T(x) pin (rising edge)
+
+// for 4MHz crystal
+// 0 = STOP (Timer not counting)
+// 1 = CLOCK		tics= 4MHz			8bitoverflow= 15625Hz		16bit=  61.035Hz
+// 2 = CLOCK/8		tics= 500kHz		8bitoverflow= 1953.125Hz	16bit=   7.629Hz
+// 3 = CLOCK/64		tics= 62500Hz		8bitoverflow=  244.141Hz	16bit=   0.954Hz
+// 4 = CLOCK/256	tics= 15625Hz		8bitoverflow=   61.035Hz	16bit=   0.238Hz
+// 5 = CLOCK/1024	tics= 3906.25Hz		8bitoverflow=   15.259Hz	16bit=   0.060Hz
+// 6 = External Clock on T(x) pin (falling edge)
+// 7 = External Clock on T(x) pin (rising edge)
+
+// for 3.69MHz crystal
+// 0 = STOP (Timer not counting)
+// 1 = CLOCK		tics= 3.69MHz		8bitoverflow= 14414Hz		16bit=  56.304Hz
+// 2 = CLOCK/8		tics= 461250Hz		8bitoverflow= 1801.758Hz	16bit=   7.038Hz
+// 3 = CLOCK/64		tics= 57625.25Hz	8bitoverflow=  225.220Hz	16bit=   0.880Hz
+// 4 = CLOCK/256	tics= 14414.063Hz	8bitoverflow=   56.305Hz	16bit=   0.220Hz
+// 5 = CLOCK/1024	tics=  3603.516Hz	8bitoverflow=   14.076Hz	16bit=   0.055Hz
+// 6 = External Clock on T(x) pin (falling edge)
+// 7 = External Clock on T(x) pin (rising edge)
+
+// for 32.768KHz crystal on timer 2 (use for real-time clock)
+// 0 = STOP
+// 1 = CLOCK		tics= 32.768kHz	8bitoverflow= 128Hz
+// 2 = CLOCK/8		tics= 4096kHz		8bitoverflow=  16Hz
+// 3 = CLOCK/64		tics= 512Hz			8bitoverflow=   2Hz
+// 4 = CLOCK/256	tics= 128Hz			8bitoverflow=   0.5Hz
+// 5 = CLOCK/1024	tics= 32Hz			8bitoverflow=   0.125Hz
+
+#define TIMER_CLK_STOP			0x00	///< Timer Stopped
+#define TIMER_CLK_DIV1			0x01	///< Timer clocked at F_CPU
+#define TIMER_CLK_DIV8			0x02	///< Timer clocked at F_CPU/8
+#define TIMER_CLK_DIV64			0x03	///< Timer clocked at F_CPU/64
+#define TIMER_CLK_DIV256		0x04	///< Timer clocked at F_CPU/256
+#define TIMER_CLK_DIV1024		0x05	///< Timer clocked at F_CPU/1024
+#define TIMER_CLK_T_FALL		0x06	///< Timer clocked at T falling edge
+#define TIMER_CLK_T_RISE		0x07	///< Timer clocked at T rising edge
+#define TIMER_PRESCALE_MASK		0x07	///< Timer Prescaler Bit-Mask
+
+#define TIMERRTC_CLK_STOP		0x00	///< RTC Timer Stopped
+#define TIMERRTC_CLK_DIV1		0x01	///< RTC Timer clocked at F_CPU
+#define TIMERRTC_CLK_DIV8		0x02	///< RTC Timer clocked at F_CPU/8
+#define TIMERRTC_CLK_DIV32		0x03	///< RTC Timer clocked at F_CPU/32
+#define TIMERRTC_CLK_DIV64		0x04	///< RTC Timer clocked at F_CPU/64
+#define TIMERRTC_CLK_DIV128		0x05	///< RTC Timer clocked at F_CPU/128
+#define TIMERRTC_CLK_DIV256		0x06	///< RTC Timer clocked at F_CPU/256
+#define TIMERRTC_CLK_DIV1024	0x07	///< RTC Timer clocked at F_CPU/1024
+#define TIMERRTC_PRESCALE_MASK	0x07	///< RTC Timer Prescaler Bit-Mask
+
+// default prescale settings for the timers
+// these settings are applied when you call
+// timerInit or any of the timer<x>Init
+#define TIMER0PRESCALE		TIMER_CLK_DIV64  	///< timer 0 prescaler default
+#define TIMER1PRESCALE		TIMER_CLK_DIV64		///< timer 1 prescaler default
+#define TIMER2PRESCALE		TIMER_CLK_DIV8		///< timer 2 prescaler default
+#define TIMER3PRESCALE		TIMER_CLK_DIV64		///< timer 3 prescaler default
+
+// interrupt macros for attaching user functions to timer interrupts
+// use these with timerAttach( intNum, function )
+// timer 0
+#define TIMER0OVERFLOW_INT			0
+#define TIMER0OUTCOMPARE_INT		1
+// timer 1
+#define TIMER1OVERFLOW_INT			2
+#define TIMER1OUTCOMPAREA_INT		3
+#define TIMER1OUTCOMPAREB_INT		4
+#define TIMER1OUTCOMPAREC_INT		5
+#define TIMER1INPUTCAPTURE_INT		6
+// timer 2
+#define TIMER2OVERFLOW_INT			7
+#define TIMER2OUTCOMPARE_INT		8
+// timer 3
+#define TIMER3OVERFLOW_INT			9
+#define TIMER3OUTCOMPAREA_INT		10
+#define TIMER3OUTCOMPAREB_INT		11
+#define TIMER3OUTCOMPAREC_INT		12
+#define TIMER3INPUTCAPTURE_INT		13
+
+#define TIMER_NUM_INTERRUPTS		14
+
+// type of interrupt handler to use for timers
+// *do not change unless you know what you're doing
+// Value may be SIGNAL or INTERRUPT
+#ifndef TIMER_INTERRUPT_HANDLER
+#define TIMER_INTERRUPT_HANDLER		SIGNAL
+#endif
+
+// functions
+#define delay		delay_us
+#define delay_ms	timerPause
+void delay_us(unsigned short time_us);
+
+// initializes timing system
+// runs all timer init functions
+// sets all timers to default prescale values #defined in systimer.c
+void timerInit(void);
+
+// default initialization routines for each timer
+void timer0Init(void);
+void timer1Init(void);
+void timer2Init(void);
+void timer3Init(void);
+
+// Clock prescaler set/get commands for each timer/counter
+// For setting the prescaler, you should use one of the #defines
+// above like TIMER_CLK_DIVx, where [x] is the division rate
+// you want.
+// When getting the current prescaler setting, the return value
+// will be the [x] division value currently set.
+void timer0SetPrescaler(u08 prescale);		///< set timer0 prescaler division index
+void timer1SetPrescaler(u08 prescale);		///< set timer1 prescaler division index
+void timer2SetPrescaler(u08 prescale);		///< set timer2 prescaler division index
+void timer3SetPrescaler(u08 prescale);		///< set timer3 prescaler division index
+u16  timer0GetPrescaler(void);				///< get timer0 prescaler division rate
+u16  timer1GetPrescaler(void);				///< get timer1 prescaler division rate
+u16  timer2GetPrescaler(void);				///< get timer2 prescaler division rate
+u16  timer3GetPrescaler(void);				///< get timer3 prescaler division rate
+
+
+// TimerAttach and Detach commands
+//		These functions allow the attachment (or detachment) of any user function
+//		to a timer interrupt.  "Attaching" one of your own functions to a timer
+//		interrupt means that it will be called whenever that interrupt happens.
+//		Using attach is better than rewriting the actual INTERRUPT() function
+//		because your code will still work and be compatible if the timer library
+//		is updated.  Also, using Attach allows your code and any predefined timer
+//		code to work together and at the same time.  (ie. "attaching" your own
+//		function to the timer0 overflow doesn't prevent timerPause from working,
+//		but rather allows you to share the interrupt.)
+//
+//		timerAttach(TIMER1OVERFLOW_INT, myOverflowFunction);
+//		timerDetach(TIMER1OVERFLOW_INT)
+//
+//		timerAttach causes the myOverflowFunction() to be attached, and therefore
+//		execute, whenever an overflow on timer1 occurs.  timerDetach removes the
+//		association and executes no user function when the interrupt occurs.
+//		myOverflowFunction must be defined with no return value and no arguments:
+//
+//		void myOverflowFunction(void) { ... }
+
+void timerAttach(u08 interruptNum, void (*userFunc)(void) );
+void timerDetach(u08 interruptNum);
+
+
+// timing commands
+// timerPause pauses for the number of milliseconds specified in <pause_ms>
+void timerPause(unsigned short pause_ms);
+
+// overflow counters
+// to be documented
+void timer0ClearOverflowCount(void);
+long timer0GetOverflowCount(void);
+void timer2ClearOverflowCount(void);
+long timer2GetOverflowCount(void);
+
+// PWM initialization and set commands for timerX (where X is either 1 or 3)
+// timerXPWMInit()
+//		configures the timerX hardware for PWM mode on pins OCXA, OCXB, and OCXC.
+//		bitRes should be 8,9,or 10 for 8,9,or 10bit PWM resolution
+//
+// timerXPWMOff()
+//		turns off all timerX PWM output and set timer mode to normal state
+//
+// timerXPWMAOn(), timerXPWMBOn(), timerXPWMCOn()
+//		turn on output of PWM signals to OCXA,B,C pins
+//		NOTE: Until you define the OCXA,B,C pins as outputs, and run
+//		this "on" command, no PWM output will be output
+//
+// timerXPWMAOff(), timerXPWMBOff(), timerXPWMCOff()
+//		turn off output of PWM signals to OCXA,B,C pins
+//
+// timerXPWMASet(), timer1PWMBSet(), timerXPWMCSet()
+//		sets the PWM duty cycle for each channel
+//	NOTE:	<pwmDuty> should be in the range 0-255 for 8bit PWM
+//			<pwmDuty> should be in the range 0-511 for 9bit PWM
+//			<pwmDuty> should be in the range 0-1023 for 10bit PWM
+// NOTE: the PWM frequency can be controlled in increments by setting the
+//			prescaler for timer1
+
+void timer1PWMInit(u08 bitRes);		///< initialize and set timer1 mode to PWM
+void timer1PWMInitICR(u16 topcount);///< initialize and set timer1 mode to PWM with specific top count
+void timer1PWMOff(void);			///< turn off all timer1 PWM output and set timer mode to normal
+void timer1PWMAOn(void);			///< turn on timer1 Channel A (OC1A) PWM output
+void timer1PWMBOn(void);			///< turn on timer1 Channel B (OC1B) PWM output
+void timer1PWMCOn(void);			///< turn on timer1 Channel C (OC1C) PWM output
+void timer1PWMAOff(void);			///< turn off timer1 Channel A (OC1A) PWM output
+void timer1PWMBOff(void);			///< turn off timer1 Channel B (OC1B) PWM output
+void timer1PWMCOff(void);			///< turn off timer1 Channel C (OC1C) PWM output
+void timer1PWMASet(u16 pwmDuty);	///< set duty of timer1 Channel A (OC1A) PWM output
+void timer1PWMBSet(u16 pwmDuty);	///< set duty of timer1 Channel B (OC1B) PWM output
+void timer1PWMCSet(u16 pwmDuty);	///< set duty of timer1 Channel C (OC1C) PWM output
+
+void timer3PWMInit(u08 bitRes);		///< initialize and set timer3 mode to PWM
+void timer3PWMInitICR(u16 topcount);///< initialize and set timer3 mode to PWM with specific top count
+void timer3PWMOff(void);			///< turn off all timer3 PWM output and set timer mode to normal
+void timer3PWMAOn(void);			///< turn on timer3 Channel A (OC3A) PWM output
+void timer3PWMBOn(void);			///< turn on timer3 Channel B (OC3B) PWM output
+void timer3PWMCOn(void);			///< turn on timer3 Channel C (OC3C) PWM output
+void timer3PWMAOff(void);			///< turn off timer3 Channel A (OC3A) PWM output
+void timer3PWMBOff(void);			///< turn off timer3 Channel B (OC3B) PWM output
+void timer3PWMCOff(void);			///< turn off timer3 Channel C (OC3C) PWM output
+void timer3PWMASet(u16 pwmDuty);	///< set duty of timer3 Channel A (OC3A) PWM output
+void timer3PWMBSet(u16 pwmDuty);	///< set duty of timer3 Channel B (OC3B) PWM output
+void timer3PWMCSet(u16 pwmDuty);	///< set duty of timer3 Channel C (OC3C) PWM output
+
+//@}
+
+// Pulse generation commands have been moved to the pulse.c library
+
+#endif
diff --git a/uartsw.c b/uartsw.c
new file mode 100755
index 0000000..d7281d9
--- /dev/null
+++ b/uartsw.c
@@ -0,0 +1,375 @@
+/*! \file uartsw.c \brief Software Interrupt-driven UART Driver. */
+//*****************************************************************************
+//
+// File Name	: 'uartsw.c'
+// Title		: Software Interrupt-driven UART Driver
+// Author		: Pascal Stang - Copyright (C) 2002-2004
+// Created		: 7/20/2002
+// Revised		: 4/27/2004
+// Version		: 0.1
+// Target MCU	: Atmel AVR Series (intended for the ATmega16 and ATmega32)
+// Editor Tabs	: 4
+//
+// This code is distributed under the GNU Public License
+//		which can be found at http://www.gnu.org/licenses/gpl.txt
+//
+//*****************************************************************************
+
+#include <avr/io.h>
+#include <avr/interrupt.h>
+
+#include "global.h"
+#include "timer128.h"
+#include "uartsw.h"
+
+// Program ROM constants
+
+// Global variables
+
+// uartsw transmit status and data variables
+static volatile u08 UartswTxBusy;
+static volatile u08 UartswTxData;
+static volatile u08 UartswTxBitNum;
+
+// baud rate common to transmit and receive
+static volatile u16 UartswBaudRateDiv;
+
+// uartsw receive status and data variables
+static volatile u08 UartswRxBusy;
+static volatile u08 UartswRxData;
+static volatile u08 UartswRxBitNum;
+// receive buffer
+static cBuffer uartswRxBuffer;               ///< uartsw receive buffer
+// automatically allocate space in ram for each buffer
+static unsigned char uartswRxData[UARTSW_RX_BUFFER_SIZE];
+
+// functions
+
+//! enable and initialize the software uart
+void uartswInit(void)
+{
+    // initialize the buffers
+	uartswInitBuffers();
+	// initialize the ports
+	sbi(UARTSW_TX_DDR, UARTSW_TX_PIN);
+	cbi(UARTSW_RX_DDR, UARTSW_RX_PIN);
+	cbi(UARTSW_RX_PORT, UARTSW_RX_PIN);
+	// initialize baud rate
+	uartswSetBaudRate(9600);
+
+	// setup the transmitter
+	UartswTxBusy = FALSE;
+	// disable OC1A interrupt
+	cbi(TIMSK, OCIE1A);
+	// attach TxBit service routine to OC1A
+	timerAttach(TIMER1OUTCOMPAREA_INT, uartswTxBitService);
+
+	// setup the receiver
+	UartswRxBusy = FALSE;
+	// disable OC1B interrupt
+	cbi(TIMSK, OCIE1B);
+	// attach RxBit service routine to OC1B
+	timerAttach(TIMER1OUTCOMPAREB_INT, uartswRxBitService);
+	// attach RxBit service routine to ICP
+	timerAttach(TIMER1INPUTCAPTURE_INT, uartswRxBitService);
+	#ifdef UARTSW_INVERT 
+	// trigger on rising edge 
+	sbi(TCCR1B, ICES1); 
+	#else 
+	// trigger on falling edge 
+	cbi(TCCR1B, ICES1); 
+	#endif	
+	// enable ICP interrupt
+	sbi(TIMSK, TICIE1);
+
+    // flush queue
+    bufferFlush(&uartswRxBuffer);
+}
+
+//! create and initialize the uart buffers
+void uartswInitBuffers(void)
+{
+	// initialize the UART receive buffer
+	bufferInit(&uartswRxBuffer, uartswRxData, UARTSW_RX_BUFFER_SIZE);
+}
+
+//! turns off software UART
+void uartswOff(void)
+{
+	// disable interrupts
+	cbi(TIMSK, OCIE1A);
+	cbi(TIMSK, OCIE1B);
+	cbi(TIMSK, TICIE1);
+	// detach the service routines
+	timerDetach(TIMER1OUTCOMPAREA_INT);
+	timerDetach(TIMER1OUTCOMPAREB_INT);
+	timerDetach(TIMER1INPUTCAPTURE_INT);
+}
+
+void uartswSetBaudRate(u32 baudrate)
+{
+	// set timer prescaler
+	timer1SetPrescaler(TIMER_CLK_DIV1);
+	// calculate division factor for requested baud rate, and set it
+	UartswBaudRateDiv = (u16)((F_CPU+(baudrate/2L))/(baudrate*1L));
+}
+
+//! returns the receive buffer structure 
+cBuffer* uartswGetRxBuffer(void)
+{
+	// return rx buffer pointer
+	return &uartswRxBuffer;
+}
+
+void uartswSendByte(u08 data)
+{
+	// wait until uart is ready
+	while(UartswTxBusy);
+	// set busy flag
+	UartswTxBusy = TRUE;
+	// save data
+	UartswTxData = data;
+	// set number of bits (+1 for stop bit)
+	UartswTxBitNum = 9;
+	
+	// set the start bit
+	#ifdef UARTSW_INVERT
+	sbi(UARTSW_TX_PORT, UARTSW_TX_PIN);
+	#else
+	cbi(UARTSW_TX_PORT, UARTSW_TX_PIN);
+	#endif
+
+	// schedule the next bit
+	outw(OCR1A, inw(TCNT1) + UartswBaudRateDiv);
+	// enable OC1A interrupt
+	sbi(TIMSK, OCIE1A);
+}
+
+//! gets a byte (if available) from the uart receive buffer
+u08 uartswReceiveByte(u08* rxData)
+{
+	// make sure we have a receive buffer
+	if(uartswRxBuffer.size)
+	{
+		// make sure we have data
+		if(uartswRxBuffer.datalength)
+		{
+			// get byte from beginning of buffer
+			*rxData = bufferGetFromFront(&uartswRxBuffer);
+			return TRUE;
+		}
+		else
+		{
+			// no data
+			return FALSE;
+		}
+	}
+	else
+	{
+		// no buffer
+		return FALSE;
+	}
+}
+
+void uartswTxBitService(void)
+{
+	if(UartswTxBitNum)
+	{
+		// there are bits still waiting to be transmitted
+		if(UartswTxBitNum > 1)
+		{
+			// transmit data bits (inverted, LSB first)
+			#ifdef UARTSW_INVERT
+			if( !(UartswTxData & 0x01) )
+			#else
+			if( (UartswTxData & 0x01) )
+			#endif
+				sbi(UARTSW_TX_PORT, UARTSW_TX_PIN);
+			else
+				cbi(UARTSW_TX_PORT, UARTSW_TX_PIN);
+			// shift bits down
+			UartswTxData = UartswTxData>>1;
+		}
+		else
+		{
+			// transmit stop bit
+			#ifdef UARTSW_INVERT
+			cbi(UARTSW_TX_PORT, UARTSW_TX_PIN);
+			#else
+			sbi(UARTSW_TX_PORT, UARTSW_TX_PIN);
+			#endif
+		}
+		// schedule the next bit
+		outw(OCR1A, inw(OCR1A) + UartswBaudRateDiv);
+		// count down
+		UartswTxBitNum--;
+	}
+	else
+	{
+		// transmission is done
+		// clear busy flag
+		UartswTxBusy = FALSE;
+	}
+}
+
+void uartswRxBitService(void)
+{
+	// this function runs on either:
+	// - a rising edge interrupt
+	// - OC1B
+	if(!UartswRxBusy)
+	{
+		// this is a start bit
+		// disable ICP interrupt
+		cbi(TIMSK, TICIE1);
+		// schedule data bit sampling 1.5 bit periods from now
+		outw(OCR1B, inw(TCNT1) + UartswBaudRateDiv + UartswBaudRateDiv/2);
+		// clear OC1B interrupt flag
+		sbi(TIFR, OCF1B);
+		// enable OC1B interrupt
+		sbi(TIMSK, OCIE1B);
+		// set start bit flag
+		UartswRxBusy = TRUE;
+		// reset bit counter
+		UartswRxBitNum = 0;
+		// reset data
+		UartswRxData = 0;
+	}
+	else
+	{
+		// start bit has already been received
+		// we're in the data bits
+		
+		// shift data byte to make room for new bit
+		UartswRxData = UartswRxData>>1;
+
+		// sample the data line
+		#ifdef UARTSW_INVERT
+		if( !(inb(UARTSW_RX_PORTIN) & (1<<UARTSW_RX_PIN)) )
+		#else
+		if( (inb(UARTSW_RX_PORTIN) & (1<<UARTSW_RX_PIN)) )
+		#endif
+		{
+			// serial line is marking
+			// record '1' bit
+			UartswRxData |= 0x80;
+		}
+
+		// increment bit counter
+		UartswRxBitNum++;
+		// schedule next bit sample
+		outw(OCR1B, inw(OCR1B) + UartswBaudRateDiv);
+
+		// check if we have a full byte
+		if(UartswRxBitNum >= 8)
+		{
+			// save data in receive buffer
+			bufferAddToEnd(&uartswRxBuffer, UartswRxData);
+			// disable OC1B interrupt
+			cbi(TIMSK, OCIE1B);
+			// clear ICP interrupt flag
+			sbi(TIFR, ICF1);
+			// enable ICP interrupt
+			sbi(TIMSK, TICIE1);
+			// clear start bit flag
+			UartswRxBusy = FALSE;
+		}
+	}
+}
+
+/*
+void uartswRxBitService(void)
+{
+	u16 thisBitTime;
+	u08 bitperiods;
+	u08 i;
+
+	// bit transition was detected
+	// record bit's edge time
+	thisBitTime = inw(ICR1);
+
+	cbi(PORTB, 0);
+
+	if(!UartswRxStartBit)
+	{
+		// this is a start bit
+		// switch to falling-edge trigger
+		cbi(TCCR1B, ICES1);
+		// record bit time
+		UartswRxBitTime = thisBitTime;
+		// set start bit flag
+		UartswRxStartBit = TRUE;
+		// reset bit counter
+		UartswRxBitNum = 0;
+		// reset data
+		UartswRxData = 0;
+	}
+	else
+	{
+		// start bit has already been received
+		// we're in the data bits
+		
+		// how many bit periods since last edge?
+		bitperiods = (thisBitTime - UartswRxBitTime + UartswBaudRateDiv/2)/UartswBaudRateDiv;
+		// set last edge time
+		UartswRxBitTime = thisBitTime;
+
+		if(bitperiods > 10)
+		{
+			// switch to trigger on rising edge
+			sbi(TCCR1B, ICES1);
+			// clear start bit flag
+			UartswRxStartBit = FALSE;
+		}
+		else
+		{
+
+
+		if( inb(TCCR1B) & (1<<ICES1) )
+		{
+			// just triggered on a rising edge
+			// previous bits were zero
+			// shift in the data (data bits are inverted)
+			for(i=0; i<bitperiods; i++)
+			{
+				UartswRxData = UartswRxData<<1;
+				UartswRxData |= 0x01;
+			}
+			// switch to trigger on falling edge
+			cbi(TCCR1B, ICES1);
+		}
+		else
+		{
+			// just triggered on a falling edge
+			// previous bits were one
+			// shift in the data (data bits are inverted)
+			for(i=0; i<bitperiods; i++)
+			{
+				UartswRxData = UartswRxData<<1;
+			}
+			// switch to trigger on rising edge
+			sbi(TCCR1B, ICES1);
+		}
+		
+		// increment bit counter
+		UartswRxBitNum += bitperiods;
+		
+		// check if we have a full byte + start bit
+		if(bitperiods > 8)
+		{
+			// save data in receive buffer
+			bufferAddToEnd(&uartswRxBuffer, UartswRxData);
+			// switch to trigger on rising edge
+			sbi(TCCR1B, ICES1);
+			// clear start bit flag
+			UartswRxStartBit = FALSE;
+		}
+		}
+	}
+
+	// turn off debug LEDs
+	delay(10);
+	sbi(PORTB, 0);
+	sbi(PORTB, 1);
+}
+*/
diff --git a/uartsw.h b/uartsw.h
new file mode 100755
index 0000000..da02bb3
--- /dev/null
+++ b/uartsw.h
@@ -0,0 +1,78 @@
+/*! \file uartsw.h \brief Software Interrupt-driven UART Driver. */
+//*****************************************************************************
+//
+// File Name	: 'uartsw.h'
+// Title		: Software Interrupt-driven UART Driver
+// Author		: Pascal Stang - Copyright (C) 2002-2004
+// Created		: 7/20/2002
+// Revised		: 4/27/2004
+// Version		: 0.1
+// Target MCU	: Atmel AVR Series (intended for the ATmega16 and ATmega32)
+// Editor Tabs	: 4
+//
+///	\ingroup driver_sw
+/// \defgroup uartsw Software Interrupt-driven UART Driver (uartsw.c)
+/// \code #include "uartsw.h" \endcode
+/// \par Overview
+///		This uart library emulates the operation of a UART (serial port) using
+///	the AVR's hardware timers, I/O pins, and some software.
+///
+///	Specifically, this code uses:
+///		-Timer 1 Output Compare A for transmit timing
+///		-Timer 1 Output Compare B for receive timing
+///		-Timer 1 Input Capture for receive triggering
+///
+///	The above resources cannot be used for other purposes while this software
+///	UART is enabled.  The overflow interrupt from Timer1 can still be used for
+///	other timing, but the prescaler for Timer1 must not be changed.
+///
+///	Serial output from this UART can be routed to any I/O pin.  Serial input
+///	for this UART must come from the Timer1 Input Capture (IC1) I/O pin.
+///	These options should be configured by editing your local copy of
+///	"uartswconf.h".
+//
+// This code is distributed under the GNU Public License
+//		which can be found at http://www.gnu.org/licenses/gpl.txt
+//
+//*****************************************************************************
+
+#ifndef UARTSW_H
+#define UARTSW_H
+
+#include "global.h"
+#include "buffer.h"
+
+// include configuration
+#include "uartswconf.h"
+
+// constants/macros/typdefs
+
+// functions
+
+//! enable and initialize the software uart
+void uartswInit(void);
+//! create and initialize the uart buffers
+void uartswInitBuffers(void);
+//! turns off software UART
+void uartswOff(void);
+//! returns the receive buffer structure 
+cBuffer* uartswGetRxBuffer(void);
+//! sets the uart baud rate
+void uartswSetBaudRate(u32 baudrate);
+//! sends a single byte over the uart
+void uartswSendByte(u08 data);
+
+//! gets a single byte from the uart receive buffer
+// Function returns TRUE if data was available, FALSE if not.
+// Actual data is returned in variable pointed to by "data".
+// example usage:
+// char myReceivedByte;
+// uartswReceiveByte( &myReceivedByte );
+u08 uartswReceiveByte(u08* rxData);
+
+//! internal transmit bit handler
+void uartswTxBitService(void);
+//! internal receive bit handler
+void uartswRxBitService(void);
+
+#endif
diff --git a/uartswconf.h b/uartswconf.h
new file mode 100755
index 0000000..2a465b1
--- /dev/null
+++ b/uartswconf.h
@@ -0,0 +1,69 @@
+/*! \file uartswconf.h \brief Interrupt-driven Software UART Driver Configuration. */
+//*****************************************************************************
+//
+// File Name	: 'uartswconf.h'
+// Title		: Interrupt-driven Software UART Driver Configuration
+// Author		: Pascal Stang - Copyright (C) 2002-2004
+// Created		: 7/20/2002
+// Revised		: 4/27/2004
+// Version		: 0.1
+// Target MCU	: Atmel AVR Series (intended for the ATmega16 and ATmega32)
+// Editor Tabs	: 4
+//
+// Description	:
+//		This uart library emulates the operation of a UART (serial port) using
+//	the AVR's hardware timers, I/O pins, and some software.
+//
+//	Specifically, this code uses:
+//		-Timer 1 Output Compare A for transmit timing
+//		-Timer 1 Output Compare B for receive timing
+//		-Timer 1 Input Capture for receive triggering
+//
+//	The above resources cannot be used for other purposes while this software
+//	UART is enabled.  The overflow interrupt from Timer1 can still be used for
+//	other timing, but the prescaler for Timer1 must not be changed.
+//
+//	Serial output from this UART can be routed to any I/O pin.  Serial input
+//	for this UART must come from the Timer1 Input Capture (IC1) I/O pin.
+//	These options should be configured by editing your local copy of
+//	"uartswconf.h".
+//
+// This code is distributed under the GNU Public License
+//		which can be found at http://www.gnu.org/licenses/gpl.txt
+//
+//*****************************************************************************
+
+#ifndef UARTSWCONF_H
+#define UARTSWCONF_H
+
+// constants/macros/typdefs
+
+#define UARTSW_RX_BUFFER_SIZE	0x20	///< UART receive buffer size in bytes
+
+//#define UARTSW_INVERT					///< define to invert polarity of RX/TX signals
+// when non-inverted, the serial line is appropriate for passing though
+// an RS232 driver like the MAX232.  When inverted, the serial line can
+// directly drive/receive RS232 signals to/from a DB9 connector.  Be sure
+// to use a current-limiting resistor and perhaps a diode-clamp circuit when
+// connecting incoming RS232 signals to a microprocessor I/O pin.
+
+// if non-inverted, the serial line idles high (logic 1) between bytes
+// if inverted, the serial line idles low (logic 0) between bytes
+
+
+// UART transmit pin defines
+#define UARTSW_TX_PORT			PORTD	///< UART Transmit Port
+#define UARTSW_TX_DDR			DDRD	///< UART Transmit DDR
+#define UARTSW_TX_PIN			PD5		///< UART Transmit Pin
+
+// UART receive pin defines
+// This pin must correspond to the
+// Timer1 Input Capture (ICP or IC1) pin for your processor
+
+// Current config is for a atmega8
+#define UARTSW_RX_PORT			PORTD	///< UART Receive Port
+#define UARTSW_RX_DDR			DDRD	///< UART Receive DDR
+#define UARTSW_RX_PORTIN		PIND	///< UART Receive Port Input
+#define UARTSW_RX_PIN			PD4		///< UART Receive Pin
+
+#endif
diff --git a/utils.h b/utils.h
new file mode 100755
index 0000000..4ea2228
--- /dev/null
+++ b/utils.h
@@ -0,0 +1,6 @@
+#ifndef _UTILS_H
+#define _UTILS_H
+
+#define NULL 0x00
+
+#endif
-- 
GitLab