diff --git a/as5013-test/as5013-test.c b/as5013-test/as5013-test.c
new file mode 100644
index 0000000000000000000000000000000000000000..24390f8fb5603642305e64b9b99817851651048a
--- /dev/null
+++ b/as5013-test/as5013-test.c
@@ -0,0 +1,97 @@
+//
+// xmega twi for as5013 2d linear magnetic encoder
+// sec, 2017
+
+#include "serial.h"
+#include <avr/io.h>
+#include <util/delay.h>
+#include <avr/pgmspace.h>
+#include <avr/interrupt.h>
+#include "twi_master_driver.h"
+
+#define SLAVE_ADDRESS    0x41
+#define CPU_SPEED       32000000
+#define TWI_BAUDRATE  100000
+#define TWI_BAUDSETTING TWI_BAUD(CPU_SPEED, TWI_BAUDRATE)
+TWI_Master_t twiMaster;    /*!< TWI master module. */
+
+USART_data_t USART_data;
+
+uint32_t value; //magnetic encoder reading
+unsigned char Data_LSB, Data_MSB; //high byte and low byte of reading
+
+
+uint8_t address_data[2]  = {0x00, 0x01};
+uint8_t speed_mode_data[2] = {0x02, 0x04}; //set into slow mode, value=4
+uint8_t sensitivity_mode_data[2] = {0x0B, 0x02}; //set into highest sensitivity value=2
+bool result = true;
+
+
+
+
+int main(void) {
+   // set up clock
+   OSC.CTRL = OSC_RC32MEN_bm; // enable 32MHz clock
+   while (!(OSC.STATUS & OSC_RC32MRDY_bm)); // wait for clock to be ready
+   CCP = CCP_IOREG_gc; // enable protected register change
+   CLK.CTRL = CLK_SCLKSEL_RC32M_gc; // switch to 32MHz clock
+
+   //set up usart
+   PORTD.DIRSET = PIN3_bm; //TXD0
+   PORTD.DIRCLR = PIN2_bm; //RXD0
+   USART_InterruptDriver_Initialize(&USART_data, &USARTD0, USART_DREINTLVL_LO_gc);
+   USART_Format_Set(USART_data.usart, USART_CHSIZE_8BIT_gc,
+                     USART_PMODE_DISABLED_gc, 0);
+   USART_RxdInterruptLevel_Set(USART_data.usart, USART_RXCINTLVL_LO_gc);
+   //take f_sysclk/(BSEL+1) ~= f_baud*16 with zero scale.  See manual or spreadsheet for scale defs
+   USART_Baudrate_Set(&USARTD0, 123 , -4); //230400 baud with .08% error
+   USART_Rx_Enable(USART_data.usart);
+   USART_Tx_Enable(USART_data.usart);
+   //enable interrupts
+   PMIC.CTRL |= PMIC_LOLVLEX_bm;
+
+   //set up twi
+   TWI_MasterInit(&twiMaster, &TWIC, TWI_MASTER_INTLVL_LO_gc, TWI_BAUDSETTING);
+   //PORTC.DIRCLR = PIN0_bm | PIN1_bm; //TXD0
+
+   sei();
+
+
+   //set as5013 speed mode
+   //result = TWI_MasterWrite(&twiMaster, SLAVE_ADDRESS, &speed_mode_data[0], 2);
+   //while (twiMaster.status != TWIM_STATUS_READY) {}
+
+   //set as5011 sensitivity
+   //result = TWI_MasterWrite(&twiMaster, SLAVE_ADDRESS, &sensitivity_mode_data[0],2);
+   //while (twiMaster.status != TWIM_STATUS_READY) {}
+
+
+   while(1){
+
+      result = TWI_MasterWriteRead(&twiMaster, SLAVE_ADDRESS, &address_data[0], 1,2); // Read D7..0
+      while (twiMaster.status != TWIM_STATUS_READY) {}
+      if (result) {
+         Data_LSB = twiMaster.readData[0];
+         Data_MSB = twiMaster.readData[1];
+
+      }
+      else { Data_LSB = 255; Data_MSB = 255;}
+
+      //value = ((Data_MSB & 0x03)<<8) + Data_LSB;
+
+      usart_send_byte(&USART_data,1);
+      usart_send_byte(&USART_data,2);
+      usart_send_byte(&USART_data,3);
+      usart_send_byte(&USART_data,4);
+      //usart_send_uint32(&USART_data,value);
+      usart_send_byte(&USART_data,Data_LSB);
+      //usart_send_byte(&USART_data,twiMaster.result);
+      usart_send_byte(&USART_data,(Data_MSB & 0x03));
+      usart_send_byte(&USART_data,10);
+      _delay_ms(100);
+   }
+}
+
+ISR(USARTD0_RXC_vect){USART_RXComplete(&USART_data);}
+ISR(USARTD0_DRE_vect){USART_DataRegEmpty(&USART_data);}
+ISR(TWIC_TWIM_vect){TWI_MasterInterruptHandler(&twiMaster);}
diff --git a/as5013-test/as5013-test.make b/as5013-test/as5013-test.make
new file mode 100644
index 0000000000000000000000000000000000000000..e6a7fe2dbf3bc093e0ea476f57a07b213eac5d0c
--- /dev/null
+++ b/as5013-test/as5013-test.make
@@ -0,0 +1,19 @@
+PROJECT=as5013-test
+SOURCES=$(PROJECT).c
+MMCU=atxmega16e5
+F_CPU = 32000000
+TARGET = x16e5
+PROGRAMMER= atmelice_pdi
+
+CFLAGS=-mmcu=$(MMCU) -Wall -Os -DF_CPU=$(F_CPU)
+
+$(PROJECT).hex: $(PROJECT).out
+	avr-objcopy -O ihex $(PROJECT).out $(PROJECT).c.hex;\
+	avr-size --mcu=$(MMCU) --format=avr $(PROJECT).out
+ 
+$(PROJECT).out: $(SOURCES)
+	avr-gcc $(CFLAGS) -I./ -o $(PROJECT).out $(SOURCES)
+ 
+program: $(PROJECT).hex
+	avrdude -p $(TARGET) -c $(PROGRAMMER) -U flash:w:$(PROJECT).c.hex
+
diff --git a/as5013-test/serial.h b/as5013-test/serial.h
new file mode 100644
index 0000000000000000000000000000000000000000..4d7312a5ca4cbc6b7815e702b2d655cff1ebd21a
--- /dev/null
+++ b/as5013-test/serial.h
@@ -0,0 +1,227 @@
+#include <avr/io.h>
+#include <util/delay.h>
+#include <avr/pgmspace.h>
+
+#define output(directions,pin) (directions |= pin) // set port direction for output
+#define set(port,pin) (port |= pin) // set port pin
+#define clear(port,pin) (port &= (~pin)) // clear port pin
+#define pin_test(pins,pin) (pins & pin) // test for port pin
+#define bit_test(byte,bit) (byte & (1 << bit)) // test for bit set
+
+/* USART buffer defines. */
+/* \brief  Receive buffer size: 2,4,8,16,32,64,128 or 256 bytes. */
+#define USART_RX_BUFFER_SIZE 128
+/* \brief Transmit buffer size: 2,4,8,16,32,64,128 or 256 bytes */
+#define USART_TX_BUFFER_SIZE 128
+/* \brief Receive buffer mask. */
+#define USART_RX_BUFFER_MASK ( USART_RX_BUFFER_SIZE - 1 )
+/* \brief Transmit buffer mask. */
+#define USART_TX_BUFFER_MASK ( USART_TX_BUFFER_SIZE - 1 )
+
+#if ( USART_RX_BUFFER_SIZE & USART_RX_BUFFER_MASK )
+#error RX buffer size is not a power of 2
+#endif
+#if ( USART_TX_BUFFER_SIZE & USART_TX_BUFFER_MASK )
+#error TX buffer size is not a power of 2
+#endif
+
+/* \brief USART transmit and receive ring buffer. */
+typedef struct USART_Buffer
+{
+   /* \brief Receive buffer. */
+   volatile uint8_t RX[USART_RX_BUFFER_SIZE];
+   /* \brief Transmit buffer. */
+   volatile uint8_t TX[USART_TX_BUFFER_SIZE];
+   /* \brief Receive buffer head. */
+   volatile uint8_t RX_Head;
+   /* \brief Receive buffer tail. */
+   volatile uint8_t RX_Tail;
+   /* \brief Transmit buffer head. */
+   volatile uint8_t TX_Head;
+   /* \brief Transmit buffer tail. */
+   volatile uint8_t TX_Tail;
+} USART_Buffer_t;
+
+
+/*! \brief Struct used when interrupt driven driver is used.
+*
+*  Struct containing pointer to a usart, a buffer and a location to store Data
+*  register interrupt level temporary.
+*/
+typedef struct Usart_and_buffer
+{
+   /* \brief Pointer to USART module to use. */
+   USART_t * usart;
+   /* \brief Data register empty interrupt level. */
+   USART_DREINTLVL_t dreIntLevel;
+   /* \brief Data buffer. */
+   USART_Buffer_t buffer;
+} USART_data_t;
+
+#define USART_RxdInterruptLevel_Set(_usart, _rxdIntLevel)                      \
+   ((_usart)->CTRLA = ((_usart)->CTRLA & ~USART_RXCINTLVL_gm) | _rxdIntLevel)
+#define USART_Format_Set(_usart, _charSize, _parityMode, _twoStopBits)         \
+   (_usart)->CTRLC = (uint8_t) _charSize | _parityMode |                      \
+                     (_twoStopBits ? USART_SBMODE_bm : 0)
+#define USART_Baudrate_Set(_usart, _bselValue, _bScaleFactor)                  \
+   (_usart)->BAUDCTRLA =(uint8_t)_bselValue;                                           \
+   (_usart)->BAUDCTRLB =(_bScaleFactor << USART_BSCALE0_bp)|(_bselValue >> 8)
+#define USART_Rx_Enable(_usart) ((_usart)->CTRLB |= USART_RXEN_bm)
+#define USART_Rx_Disable(_usart) ((_usart)->CTRLB &= ~USART_RXEN_bm)
+#define USART_Tx_Enable(_usart)  ((_usart)->CTRLB |= USART_TXEN_bm)
+#define USART_Tx_Disable(_usart) ((_usart)->CTRLB &= ~USART_TXEN_bm)
+
+
+
+_Bool USART_TXBuffer_FreeSpace(USART_data_t * usart_data)
+{
+   /* Make copies to make sure that volatile access is specified. */
+   uint8_t tempHead = (usart_data->buffer.TX_Head + 1) & USART_TX_BUFFER_MASK;
+   uint8_t tempTail = usart_data->buffer.TX_Tail;
+
+   /* There are data left in the buffer unless Head and Tail are equal. */
+   return (tempHead != tempTail);
+}
+_Bool USART_TXBuffer_PutByte(USART_data_t * usart_data, uint8_t data)
+{
+   uint8_t tempCTRLA;
+   uint8_t tempTX_Head;
+   _Bool TXBuffer_FreeSpace;
+   USART_Buffer_t * TXbufPtr;
+
+   TXbufPtr = &usart_data->buffer;
+   TXBuffer_FreeSpace = USART_TXBuffer_FreeSpace(usart_data);
+
+
+   if(TXBuffer_FreeSpace)
+   {
+      tempTX_Head = TXbufPtr->TX_Head;
+      TXbufPtr->TX[tempTX_Head]= data;
+      /* Advance buffer head. */
+      TXbufPtr->TX_Head = (tempTX_Head + 1) & USART_TX_BUFFER_MASK;
+
+      /* Enable DRE interrupt. */
+      tempCTRLA = usart_data->usart->CTRLA;
+      tempCTRLA = (tempCTRLA & ~USART_DREINTLVL_gm) | usart_data->dreIntLevel;
+      usart_data->usart->CTRLA = tempCTRLA;
+   }
+   return TXBuffer_FreeSpace;
+}
+_Bool USART_RXBufferData_Available(USART_data_t * usart_data)
+{
+   /* Make copies to make sure that volatile access is specified. */
+   uint8_t tempHead = usart_data->buffer.RX_Head;
+   uint8_t tempTail = usart_data->buffer.RX_Tail;
+
+   /* There are data left in the buffer unless Head and Tail are equal. */
+   return (tempHead != tempTail);
+}
+uint8_t USART_RXBuffer_GetByte(USART_data_t * usart_data)
+{
+   USART_Buffer_t * bufPtr;
+   uint8_t ans;
+   bufPtr = &usart_data->buffer;
+   ans = (bufPtr->RX[bufPtr->RX_Tail]);
+
+   /* Advance buffer tail. */
+   bufPtr->RX_Tail = (bufPtr->RX_Tail + 1) & USART_RX_BUFFER_MASK;
+   return ans;
+}
+_Bool USART_RXComplete(USART_data_t * usart_data)
+{
+   USART_Buffer_t * bufPtr;
+   _Bool ans;
+
+   bufPtr = &usart_data->buffer;
+   /* Advance buffer head. */
+   uint8_t tempRX_Head = (bufPtr->RX_Head + 1) & USART_RX_BUFFER_MASK;
+
+   /* Check for overflow. */
+   uint8_t tempRX_Tail = bufPtr->RX_Tail;
+   uint8_t data = usart_data->usart->DATA;
+
+   if (tempRX_Head == tempRX_Tail) {
+      ans = 0;
+   }else{
+      ans = 1;
+      usart_data->buffer.RX[usart_data->buffer.RX_Head] = data;
+      usart_data->buffer.RX_Head = tempRX_Head;
+   }
+   return ans;
+}
+void USART_DataRegEmpty(USART_data_t * usart_data)
+{
+   USART_Buffer_t * bufPtr;
+   bufPtr = &usart_data->buffer;
+
+   /* Check if all data is transmitted. */
+   uint8_t tempTX_Tail = usart_data->buffer.TX_Tail;
+   if (bufPtr->TX_Head == tempTX_Tail){
+       /* Disable DRE interrupts. */
+      uint8_t tempCTRLA = usart_data->usart->CTRLA;
+      tempCTRLA = (tempCTRLA & ~USART_DREINTLVL_gm) | USART_DREINTLVL_OFF_gc;
+      usart_data->usart->CTRLA = tempCTRLA;
+
+   }else{
+      /* Start transmitting. */
+      uint8_t data = bufPtr->TX[usart_data->buffer.TX_Tail];
+      usart_data->usart->DATA = data;
+
+      /* Advance buffer tail. */
+      bufPtr->TX_Tail = (bufPtr->TX_Tail + 1) & USART_TX_BUFFER_MASK;
+   }
+}
+void USART_InterruptDriver_Initialize(USART_data_t * usart_data,
+                                      USART_t * usart,
+                                      USART_DREINTLVL_t dreIntLevel)
+{
+   usart_data->usart = usart;
+   usart_data->dreIntLevel = dreIntLevel;
+
+   usart_data->buffer.RX_Tail = 0;
+   usart_data->buffer.RX_Head = 0;
+   usart_data->buffer.TX_Tail = 0;
+   usart_data->buffer.TX_Head = 0;
+}
+void USART_InterruptDriver_DreInterruptLevel_Set(USART_data_t * usart_data,
+                                                 USART_DREINTLVL_t dreIntLevel)
+{
+   usart_data->dreIntLevel = dreIntLevel;
+}
+
+void usart_send_byte(USART_data_t * usart_data, char msg){
+   while(!USART_TXBuffer_FreeSpace(usart_data)){}
+   USART_TXBuffer_PutByte(usart_data,msg);
+}
+void usart_send_uint32(USART_data_t * usart_data, uint32_t n){
+   unsigned char * nn = (unsigned char *)&n;
+   usart_send_byte(usart_data, nn[0] );
+   usart_send_byte(usart_data, nn[1] );
+   usart_send_byte(usart_data, nn[2] );
+   usart_send_byte(usart_data, nn[3] );
+}
+void usart_send_int32(USART_data_t * usart_data, int32_t n){
+   unsigned char * nn = ( unsigned char *)&n;
+   usart_send_byte(usart_data, nn[0] );
+   usart_send_byte(usart_data, nn[1] );
+   usart_send_byte(usart_data, nn[2] );
+   usart_send_byte(usart_data, nn[3] );   
+}
+uint32_t parse_uint32(char* b){return *(uint32_t *) b;}
+int32_t parse_int32(char* b){return *(int32_t *) b;}
+uint16_t parse_uint16(char* b){return *(uint16_t *) b;}
+
+
+/*
+void usart_write_buffer(char* buffer){
+   //write \n terminated buffer over usart
+   int j=0;
+   do{
+      usart_send_byte( buffer[j] );
+      j++;
+   } while( j < PACKET_SIZE);
+   //} while( buffer[j-1] != 10);
+}
+*/
+
+
diff --git a/as5013-test/twi_master_driver.c b/as5013-test/twi_master_driver.c
new file mode 100644
index 0000000000000000000000000000000000000000..c7f9695ac97609d9288c01556d8bc49a713f2602
--- /dev/null
+++ b/as5013-test/twi_master_driver.c
@@ -0,0 +1,399 @@
+/* This file has been prepared for Doxygen automatic documentation generation.*/
+/*! \file *********************************************************************
+ *
+ * \brief
+ *      XMEGA TWI master driver source file.
+ *
+ *      This file contains the function implementations the XMEGA master TWI
+ *      driver.
+ *
+ *      The driver is not intended for size and/or speed critical code, since
+ *      most functions are just a few lines of code, and the function call
+ *      overhead would decrease code performance. The driver is intended for
+ *      rapid prototyping and documentation purposes for getting started with
+ *      the XMEGA TWI master module.
+ *
+ *      For size and/or speed critical code, it is recommended to copy the
+ *      function contents directly into your application instead of making
+ *      a function call.
+ *
+ *      Several functions use the following construct:
+ *          "some_register = ... | (some_parameter ? SOME_BIT_bm : 0) | ..."
+ *      Although the use of the ternary operator ( if ? then : else ) is
+ *      discouraged, in some occasions the operator makes it possible to write
+ *      pretty clean and neat code. In this driver, the construct is used to
+ *      set or not set a configuration bit based on a boolean input parameter,
+ *      such as the "some_parameter" in the example above.
+ *
+ * \par Application note:
+ *      AVR1308: Using the XMEGA TWI
+ *
+ * \par Documentation
+ *      For comprehensive code documentation, supported compilers, compiler
+ *      settings and supported devices see readme.html
+ *
+ * \author
+ *      Atmel Corporation: http://www.atmel.com \n
+ *      Support email: avr@atmel.com
+ *
+ * $Revision: 1569 $
+ * $Date: 2008-04-22 13:03:43 +0200 (ti, 22 apr 2008) $  \n
+ *
+ * Copyright (c) 2008, Atmel Corporation All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright notice,
+ * this list of conditions and the following disclaimer.
+ *
+ * 2. Redistributions in binary form must reproduce the above copyright notice,
+ * this list of conditions and the following disclaimer in the documentation
+ * and/or other materials provided with the distribution.
+ *
+ * 3. The name of ATMEL may not be used to endorse or promote products derived
+ * from this software without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR IMPLIED
+ * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
+ * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE EXPRESSLY AND
+ * SPECIFICALLY DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR ANY DIRECT,
+ * INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
+ * (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+ * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
+ * ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+ * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF
+ * THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ *****************************************************************************/
+
+#include "twi_master_driver.h"
+
+
+/*! \brief Initialize the TWI module.
+ *
+ *  TWI module initialization function.
+ *  Enables master read and write interrupts.
+ *  Remember to enable interrupts globally from the main application.
+ *
+ *  \param twi                      The TWI_Master_t struct instance.
+ *  \param module                   The TWI module to use.
+ *  \param intLevel                 Master interrupt level.
+ *  \param baudRateRegisterSetting  The baud rate register value.
+ */
+void TWI_MasterInit(TWI_Master_t *twi,
+                    TWI_t *module,
+                    TWI_MASTER_INTLVL_t intLevel,
+                    uint8_t baudRateRegisterSetting)
+{
+	twi->interface = module;
+	twi->interface->MASTER.CTRLA = intLevel |
+	                               TWI_MASTER_RIEN_bm |
+	                               TWI_MASTER_WIEN_bm |
+	                               TWI_MASTER_ENABLE_bm;
+	twi->interface->MASTER.BAUD = baudRateRegisterSetting;
+	twi->interface->MASTER.STATUS = TWI_MASTER_BUSSTATE_IDLE_gc;
+}
+
+
+/*! \brief Returns the TWI bus state.
+ *
+ *  Returns the TWI bus state (type defined in device headerfile),
+ *  unknown, idle, owner or busy.
+ *
+ *  \param twi The TWI_Master_t struct instance.
+ *
+ *  \retval TWI_MASTER_BUSSTATE_UNKNOWN_gc Bus state is unknown.
+ *  \retval TWI_MASTER_BUSSTATE_IDLE_gc    Bus state is idle.
+ *  \retval TWI_MASTER_BUSSTATE_OWNER_gc   Bus state is owned by the master.
+ *  \retval TWI_MASTER_BUSSTATE_BUSY_gc    Bus state is busy.
+ */
+TWI_MASTER_BUSSTATE_t TWI_MasterState(TWI_Master_t *twi)
+{
+	TWI_MASTER_BUSSTATE_t twi_status;
+	twi_status = (TWI_MASTER_BUSSTATE_t) (twi->interface->MASTER.STATUS &
+	                                      TWI_MASTER_BUSSTATE_gm);
+	return twi_status;
+}
+
+
+/*! \brief Returns true if transaction is ready.
+ *
+ *  This function returns a boolean whether the TWI Master is ready
+ *  for a new transaction.
+ *
+ *  \param twi The TWI_Master_t struct instance.
+ *
+ *  \retval true  If transaction could be started.
+ *  \retval false If transaction could not be started.
+ */
+bool TWI_MasterReady(TWI_Master_t *twi)
+{
+	bool twi_status = (twi->status & TWIM_STATUS_READY);
+	return twi_status;
+}
+
+
+/*! \brief TWI write transaction.
+ *
+ *  This function is TWI Master wrapper for a write-only transaction.
+ *
+ *  \param twi          The TWI_Master_t struct instance.
+ *  \param address      Slave address.
+ *  \param writeData    Pointer to data to write.
+ *  \param bytesToWrite Number of data bytes to write.
+ *
+ *  \retval true  If transaction could be started.
+ *  \retval false If transaction could not be started.
+ */
+bool TWI_MasterWrite(TWI_Master_t *twi,
+                     uint8_t address,
+                     uint8_t *writeData,
+                     uint8_t bytesToWrite)
+{
+	bool twi_status = TWI_MasterWriteRead(twi, address, writeData, bytesToWrite, 0);
+	return twi_status;
+}
+
+
+/*! \brief TWI read transaction.
+ *
+ *  This function is a TWI Maste wrapper for read-only transaction.
+ *
+ *  \param twi            The TWI_Master_t struct instance.
+ *  \param address        The slave address.
+ *  \param bytesToRead    The number of bytes to read.
+ *
+ *  \retval true  If transaction could be started.
+ *  \retval false If transaction could not be started.
+ */
+bool TWI_MasterRead(TWI_Master_t *twi,
+                    uint8_t address,
+                    uint8_t bytesToRead)
+{
+	bool twi_status = TWI_MasterWriteRead(twi, address, 0, 0, bytesToRead);
+	return twi_status;
+}
+
+
+/*! \brief TWI write and/or read transaction.
+ *
+ *  This function is a TWI Master write and/or read transaction. The function
+ *  can be used to both write and/or read bytes to/from the TWI Slave in one
+ *  transaction.
+ *
+ *  \param twi            The TWI_Master_t struct instance.
+ *  \param address        The slave address.
+ *  \param writeData      Pointer to data to write.
+ *  \param bytesToWrite   Number of bytes to write.
+ *  \param bytesToRead    Number of bytes to read.
+ *
+ *  \retval true  If transaction could be started.
+ *  \retval false If transaction could not be started.
+ */
+bool TWI_MasterWriteRead(TWI_Master_t *twi,
+                         uint8_t address,
+                         uint8_t *writeData,
+                         uint8_t bytesToWrite,
+                         uint8_t bytesToRead)
+{
+	/*Parameter sanity check. */
+	if (bytesToWrite > TWIM_WRITE_BUFFER_SIZE) {
+		return false;
+	}
+	if (bytesToRead > TWIM_READ_BUFFER_SIZE) {
+		return false;
+	}
+
+	/*Initiate transaction if bus is ready. */
+	if (twi->status == TWIM_STATUS_READY) {
+
+		twi->status = TWIM_STATUS_BUSY;
+		twi->result = TWIM_RESULT_UNKNOWN;
+
+		twi->address = address<<1;
+
+		/* Fill write data buffer. */
+		for (uint8_t bufferIndex=0; bufferIndex < bytesToWrite; bufferIndex++) {
+			twi->writeData[bufferIndex] = writeData[bufferIndex];
+		}
+
+		twi->bytesToWrite = bytesToWrite;
+		twi->bytesToRead = bytesToRead;
+		twi->bytesWritten = 0;
+		twi->bytesRead = 0;
+
+		/* If write command, send the START condition + Address +
+		 * 'R/_W = 0'
+		 */
+		if (twi->bytesToWrite > 0) {
+			uint8_t writeAddress = twi->address & ~0x01;
+			twi->interface->MASTER.ADDR = writeAddress;
+		}
+
+		/* If read command, send the START condition + Address +
+		 * 'R/_W = 1'
+		 */
+		else if (twi->bytesToRead > 0) {
+			uint8_t readAddress = twi->address | 0x01;
+			twi->interface->MASTER.ADDR = readAddress;
+		}
+		return true;
+	} else {
+		return false;
+	}
+}
+
+
+/*! \brief Common TWI master interrupt service routine.
+ *
+ *  Check current status and calls the appropriate handler.
+ *
+ *  \param twi  The TWI_Master_t struct instance.
+ */
+void TWI_MasterInterruptHandler(TWI_Master_t *twi)
+{
+	uint8_t currentStatus = twi->interface->MASTER.STATUS;
+
+	/* If arbitration lost or bus error. */
+	if ((currentStatus & TWI_MASTER_ARBLOST_bm) ||
+	    (currentStatus & TWI_MASTER_BUSERR_bm)) {
+
+		TWI_MasterArbitrationLostBusErrorHandler(twi);
+	}
+
+	/* If master write interrupt. */
+	else if (currentStatus & TWI_MASTER_WIF_bm) {
+		TWI_MasterWriteHandler(twi);
+	}
+
+	/* If master read interrupt. */
+	else if (currentStatus & TWI_MASTER_RIF_bm) {
+		TWI_MasterReadHandler(twi);
+	}
+
+	/* If unexpected state. */
+	else {
+		TWI_MasterTransactionFinished(twi, TWIM_RESULT_FAIL);
+	}
+}
+
+
+/*! \brief TWI master arbitration lost and bus error interrupt handler.
+ *
+ *  Handles TWI responses to lost arbitration and bus error.
+ *
+ *  \param twi  The TWI_Master_t struct instance.
+ */
+void TWI_MasterArbitrationLostBusErrorHandler(TWI_Master_t *twi)
+{
+	uint8_t currentStatus = twi->interface->MASTER.STATUS;
+
+	/* If bus error. */
+	if (currentStatus & TWI_MASTER_BUSERR_bm) {
+		twi->result = TWIM_RESULT_BUS_ERROR;
+	}
+	/* If arbitration lost. */
+	else {
+		twi->result = TWIM_RESULT_ARBITRATION_LOST;
+	}
+
+	/* Clear interrupt flag. */
+	twi->interface->MASTER.STATUS = currentStatus | TWI_MASTER_ARBLOST_bm;
+
+	twi->status = TWIM_STATUS_READY;
+}
+
+
+/*! \brief TWI master write interrupt handler.
+ *
+ *  Handles TWI transactions (master write) and responses to (N)ACK.
+ *
+ *  \param twi The TWI_Master_t struct instance.
+ */
+void TWI_MasterWriteHandler(TWI_Master_t *twi)
+{
+	/* Local variables used in if tests to avoid compiler warning. */
+	uint8_t bytesToWrite  = twi->bytesToWrite;
+	uint8_t bytesToRead   = twi->bytesToRead;
+
+	/* If NOT acknowledged (NACK) by slave cancel the transaction. */
+	if (twi->interface->MASTER.STATUS & TWI_MASTER_RXACK_bm) {
+		twi->interface->MASTER.CTRLC = TWI_MASTER_CMD_STOP_gc;
+		twi->result = TWIM_RESULT_NACK_RECEIVED;
+		twi->status = TWIM_STATUS_READY;
+	}
+
+	/* If more bytes to write, send data. */
+	else if (twi->bytesWritten < bytesToWrite) {
+		uint8_t data = twi->writeData[twi->bytesWritten];
+		twi->interface->MASTER.DATA = data;
+		++twi->bytesWritten;
+	}
+
+	/* If bytes to read, send repeated START condition + Address +
+	 * 'R/_W = 1'
+	 */
+	else if (twi->bytesRead < bytesToRead) {
+		uint8_t readAddress = twi->address | 0x01;
+		twi->interface->MASTER.ADDR = readAddress;
+	}
+
+	/* If transaction finished, send STOP condition and set RESULT OK. */
+	else {
+		twi->interface->MASTER.CTRLC = TWI_MASTER_CMD_STOP_gc;
+		TWI_MasterTransactionFinished(twi, TWIM_RESULT_OK);
+	}
+}
+
+
+/*! \brief TWI master read interrupt handler.
+ *
+ *  This is the master read interrupt handler that takes care of
+ *  reading bytes from the TWI slave.
+ *
+ *  \param twi The TWI_Master_t struct instance.
+ */
+void TWI_MasterReadHandler(TWI_Master_t *twi)
+{
+	/* Fetch data if bytes to be read. */
+	if (twi->bytesRead < TWIM_READ_BUFFER_SIZE) {
+		uint8_t data = twi->interface->MASTER.DATA;
+		twi->readData[twi->bytesRead] = data;
+		twi->bytesRead++;
+	}
+
+	/* If buffer overflow, issue STOP and BUFFER_OVERFLOW condition. */
+	else {
+		twi->interface->MASTER.CTRLC = TWI_MASTER_CMD_STOP_gc;
+		TWI_MasterTransactionFinished(twi, TWIM_RESULT_BUFFER_OVERFLOW);
+	}
+
+	/* Local variable used in if test to avoid compiler warning. */
+	uint8_t bytesToRead = twi->bytesToRead;
+
+	/* If more bytes to read, issue ACK and start a byte read. */
+	if (twi->bytesRead < bytesToRead) {
+		twi->interface->MASTER.CTRLC = TWI_MASTER_CMD_RECVTRANS_gc;
+	}
+
+	/* If transaction finished, issue NACK and STOP condition. */
+	else {
+		twi->interface->MASTER.CTRLC = TWI_MASTER_ACKACT_bm |
+		                               TWI_MASTER_CMD_STOP_gc;
+		TWI_MasterTransactionFinished(twi, TWIM_RESULT_OK);
+	}
+}
+
+
+/*! \brief TWI transaction finished handler.
+ *
+ *  Prepares module for new transaction.
+ *
+ *  \param twi     The TWI_Master_t struct instance.
+ *  \param result  The result of the operation.
+ */
+void TWI_MasterTransactionFinished(TWI_Master_t *twi, uint8_t result)
+{
+	twi->result = result;
+	twi->status = TWIM_STATUS_READY;
+}
diff --git a/as5013-test/twi_master_driver.h b/as5013-test/twi_master_driver.h
new file mode 100644
index 0000000000000000000000000000000000000000..3d4dd060b4501f4c4027ccf3ef1a04cb95ca7660
--- /dev/null
+++ b/as5013-test/twi_master_driver.h
@@ -0,0 +1,490 @@
+/* This file has been prepared for Doxygen automatic documentation generation.*/
+/*! \file *********************************************************************
+ *
+ * \brief  XMEGA TWI master driver header file.
+ *
+ *      This file contains the function prototypes and enumerator definitions
+ *      for various configuration parameters for the XMEGA TWI master driver.
+ *
+ *      The driver is not intended for size and/or speed critical code, since
+ *      most functions are just a few lines of code, and the function call
+ *      overhead would decrease code performance. The driver is intended for
+ *      rapid prototyping and documentation purposes for getting started with
+ *      the XMEGA TWI master module.
+ *
+ *      For size and/or speed critical code, it is recommended to copy the
+ *      function contents directly into your application instead of making
+ *      a function call.
+ *
+ * \par Application note:
+ *      AVR1308: Using the XMEGA TWI
+ *
+ * \par Documentation
+ *      For comprehensive code documentation, supported compilers, compiler
+ *      settings and supported devices see readme.html
+ *
+ * \author
+ *      Atmel Corporation: http://www.atmel.com \n
+ *      Support email: avr@atmel.com
+ *
+ * $Revision: 1569 $
+ * $Date: 2008-04-22 13:03:43 +0200 (ti, 22 apr 2008) $  \n
+ *
+ * Copyright (c) 2008, Atmel Corporation All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright notice,
+ * this list of conditions and the following disclaimer.
+ *
+ * 2. Redistributions in binary form must reproduce the above copyright notice,
+ * this list of conditions and the following disclaimer in the documentation
+ * and/or other materials provided with the distribution.
+ *
+ * 3. The name of ATMEL may not be used to endorse or promote products derived
+ * from this software without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR IMPLIED
+ * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
+ * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE EXPRESSLY AND
+ * SPECIFICALLY DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR ANY DIRECT,
+ * INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
+ * (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+ * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
+ * ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+ * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF
+ * THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ *****************************************************************************/
+#ifndef TWI_MASTER_DRIVER_H
+#define TWI_MASTER_DRIVER_H
+
+#include "avr_compiler.h"
+
+/*! Baud register setting calculation. Formula described in datasheet. */
+#define TWI_BAUD(F_SYS, F_TWI) ((F_SYS / (2 * F_TWI)) - 5)
+
+
+/*! Transaction status defines. */
+#define TWIM_STATUS_READY              0
+#define TWIM_STATUS_BUSY               1
+
+
+/*! Transaction result enumeration. */
+typedef enum TWIM_RESULT_enum {
+	TWIM_RESULT_UNKNOWN          = (0x00<<0),
+	TWIM_RESULT_OK               = (0x01<<0),
+	TWIM_RESULT_BUFFER_OVERFLOW  = (0x02<<0),
+	TWIM_RESULT_ARBITRATION_LOST = (0x03<<0),
+	TWIM_RESULT_BUS_ERROR        = (0x04<<0),
+	TWIM_RESULT_NACK_RECEIVED    = (0x05<<0),
+	TWIM_RESULT_FAIL             = (0x06<<0),
+} TWIM_RESULT_t;
+
+/*! Buffer size defines */
+#define TWIM_WRITE_BUFFER_SIZE         8
+#define TWIM_READ_BUFFER_SIZE          8
+
+
+/*! \brief TWI master driver struct
+ *
+ *  TWI master struct. Holds pointer to TWI module,
+ *  buffers and necessary varibles.
+ */
+typedef struct TWI_Master {
+	TWI_t *interface;                  /*!< Pointer to what interface to use */
+	register8_t address;                            /*!< Slave address */
+	register8_t writeData[TWIM_WRITE_BUFFER_SIZE];  /*!< Data to write */
+	register8_t readData[TWIM_READ_BUFFER_SIZE];    /*!< Read data */
+	register8_t bytesToWrite;                       /*!< Number of bytes to write */
+	register8_t bytesToRead;                        /*!< Number of bytes to read */
+	register8_t bytesWritten;                       /*!< Number of bytes written */
+	register8_t bytesRead;                          /*!< Number of bytes read */
+	register8_t status;                             /*!< Status of transaction */
+	register8_t result;                             /*!< Result of transaction */
+}TWI_Master_t;
+
+
+
+void TWI_MasterInit(TWI_Master_t *twi,
+                    TWI_t *module,
+                    TWI_MASTER_INTLVL_t intLevel,
+                    uint8_t baudRateRegisterSetting);
+TWI_MASTER_BUSSTATE_t TWI_MasterState(TWI_Master_t *twi);
+bool TWI_MasterReady(TWI_Master_t *twi);
+bool TWI_MasterWrite(TWI_Master_t *twi,
+                     uint8_t address,
+                     uint8_t * writeData,
+                     uint8_t bytesToWrite);
+bool TWI_MasterRead(TWI_Master_t *twi,
+                    uint8_t address,
+                    uint8_t bytesToRead);
+bool TWI_MasterWriteRead(TWI_Master_t *twi,
+                         uint8_t address,
+                         uint8_t *writeData,
+                         uint8_t bytesToWrite,
+                         uint8_t bytesToRead);
+void TWI_MasterInterruptHandler(TWI_Master_t *twi);
+void TWI_MasterArbitrationLostBusErrorHandler(TWI_Master_t *twi);
+void TWI_MasterWriteHandler(TWI_Master_t *twi);
+void TWI_MasterReadHandler(TWI_Master_t *twi);
+void TWI_MasterTransactionFinished(TWI_Master_t *twi, uint8_t result);
+
+
+/*! TWI master interrupt service routine.
+ *
+ *  Interrupt service routine for the TWI master. Copy the needed vectors
+ *  into your code.
+ *
+    ISR(TWIC_TWIM_vect)
+    {
+      TWI_MasterInterruptHandler(&twiMaster);
+    }
+
+ *
+ */
+
+
+
+
+
+/*! \brief Initialize the TWI module.
+ *
+ *  TWI module initialization function.
+ *  Enables master read and write interrupts.
+ *  Remember to enable interrupts globally from the main application.
+ *
+ *  \param twi                      The TWI_Master_t struct instance.
+ *  \param module                   The TWI module to use.
+ *  \param intLevel                 Master interrupt level.
+ *  \param baudRateRegisterSetting  The baud rate register value.
+ */
+void TWI_MasterInit(TWI_Master_t *twi,
+                    TWI_t *module,
+                    TWI_MASTER_INTLVL_t intLevel,
+                    uint8_t baudRateRegisterSetting)
+{
+	twi->interface = module;
+	twi->interface->MASTER.CTRLA = intLevel |
+	                               TWI_MASTER_RIEN_bm |
+	                               TWI_MASTER_WIEN_bm |
+	                               TWI_MASTER_ENABLE_bm;
+	twi->interface->MASTER.BAUD = baudRateRegisterSetting;
+	twi->interface->MASTER.STATUS = TWI_MASTER_BUSSTATE_IDLE_gc;
+}
+
+
+/*! \brief Returns the TWI bus state.
+ *
+ *  Returns the TWI bus state (type defined in device headerfile),
+ *  unknown, idle, owner or busy.
+ *
+ *  \param twi The TWI_Master_t struct instance.
+ *
+ *  \retval TWI_MASTER_BUSSTATE_UNKNOWN_gc Bus state is unknown.
+ *  \retval TWI_MASTER_BUSSTATE_IDLE_gc    Bus state is idle.
+ *  \retval TWI_MASTER_BUSSTATE_OWNER_gc   Bus state is owned by the master.
+ *  \retval TWI_MASTER_BUSSTATE_BUSY_gc    Bus state is busy.
+ */
+TWI_MASTER_BUSSTATE_t TWI_MasterState(TWI_Master_t *twi)
+{
+	TWI_MASTER_BUSSTATE_t twi_status;
+	twi_status = (TWI_MASTER_BUSSTATE_t) (twi->interface->MASTER.STATUS &
+	                                      TWI_MASTER_BUSSTATE_gm);
+	return twi_status;
+}
+
+
+/*! \brief Returns true if transaction is ready.
+ *
+ *  This function returns a boolean whether the TWI Master is ready
+ *  for a new transaction.
+ *
+ *  \param twi The TWI_Master_t struct instance.
+ *
+ *  \retval true  If transaction could be started.
+ *  \retval false If transaction could not be started.
+ */
+bool TWI_MasterReady(TWI_Master_t *twi)
+{
+	bool twi_status = (twi->status & TWIM_STATUS_READY);
+	return twi_status;
+}
+
+
+/*! \brief TWI write transaction.
+ *
+ *  This function is TWI Master wrapper for a write-only transaction.
+ *
+ *  \param twi          The TWI_Master_t struct instance.
+ *  \param address      Slave address.
+ *  \param writeData    Pointer to data to write.
+ *  \param bytesToWrite Number of data bytes to write.
+ *
+ *  \retval true  If transaction could be started.
+ *  \retval false If transaction could not be started.
+ */
+bool TWI_MasterWrite(TWI_Master_t *twi,
+                     uint8_t address,
+                     uint8_t *writeData,
+                     uint8_t bytesToWrite)
+{
+	bool twi_status = TWI_MasterWriteRead(twi, address, writeData, bytesToWrite, 0);
+	return twi_status;
+}
+
+
+/*! \brief TWI read transaction.
+ *
+ *  This function is a TWI Maste wrapper for read-only transaction.
+ *
+ *  \param twi            The TWI_Master_t struct instance.
+ *  \param address        The slave address.
+ *  \param bytesToRead    The number of bytes to read.
+ *
+ *  \retval true  If transaction could be started.
+ *  \retval false If transaction could not be started.
+ */
+bool TWI_MasterRead(TWI_Master_t *twi,
+                    uint8_t address,
+                    uint8_t bytesToRead)
+{
+	bool twi_status = TWI_MasterWriteRead(twi, address, 0, 0, bytesToRead);
+	return twi_status;
+}
+
+
+/*! \brief TWI write and/or read transaction.
+ *
+ *  This function is a TWI Master write and/or read transaction. The function
+ *  can be used to both write and/or read bytes to/from the TWI Slave in one
+ *  transaction.
+ *
+ *  \param twi            The TWI_Master_t struct instance.
+ *  \param address        The slave address.
+ *  \param writeData      Pointer to data to write.
+ *  \param bytesToWrite   Number of bytes to write.
+ *  \param bytesToRead    Number of bytes to read.
+ *
+ *  \retval true  If transaction could be started.
+ *  \retval false If transaction could not be started.
+ */
+bool TWI_MasterWriteRead(TWI_Master_t *twi,
+                         uint8_t address,
+                         uint8_t *writeData,
+                         uint8_t bytesToWrite,
+                         uint8_t bytesToRead)
+{
+	/*Parameter sanity check. */
+	if (bytesToWrite > TWIM_WRITE_BUFFER_SIZE) {
+		return false;
+	}
+	if (bytesToRead > TWIM_READ_BUFFER_SIZE) {
+		return false;
+	}
+
+	/*Initiate transaction if bus is ready. */
+	if (twi->status == TWIM_STATUS_READY) {
+
+		twi->status = TWIM_STATUS_BUSY;
+		twi->result = TWIM_RESULT_UNKNOWN;
+
+		twi->address = address<<1;
+
+		/* Fill write data buffer. */
+		for (uint8_t bufferIndex=0; bufferIndex < bytesToWrite; bufferIndex++) {
+			twi->writeData[bufferIndex] = writeData[bufferIndex];
+		}
+
+		twi->bytesToWrite = bytesToWrite;
+		twi->bytesToRead = bytesToRead;
+		twi->bytesWritten = 0;
+		twi->bytesRead = 0;
+
+		/* If write command, send the START condition + Address +
+		 * 'R/_W = 0'
+		 */
+		if (twi->bytesToWrite > 0) {
+			uint8_t writeAddress = twi->address & ~0x01;
+			twi->interface->MASTER.ADDR = writeAddress;
+		}
+
+		/* If read command, send the START condition + Address +
+		 * 'R/_W = 1'
+		 */
+		else if (twi->bytesToRead > 0) {
+			uint8_t readAddress = twi->address | 0x01;
+			twi->interface->MASTER.ADDR = readAddress;
+		}
+		return true;
+	} else {
+		return false;
+	}
+}
+
+
+/*! \brief Common TWI master interrupt service routine.
+ *
+ *  Check current status and calls the appropriate handler.
+ *
+ *  \param twi  The TWI_Master_t struct instance.
+ */
+void TWI_MasterInterruptHandler(TWI_Master_t *twi)
+{
+	uint8_t currentStatus = twi->interface->MASTER.STATUS;
+
+	/* If arbitration lost or bus error. */
+	if ((currentStatus & TWI_MASTER_ARBLOST_bm) ||
+	    (currentStatus & TWI_MASTER_BUSERR_bm)) {
+
+		TWI_MasterArbitrationLostBusErrorHandler(twi);
+	}
+
+	/* If master write interrupt. */
+	else if (currentStatus & TWI_MASTER_WIF_bm) {
+		TWI_MasterWriteHandler(twi);
+	}
+
+	/* If master read interrupt. */
+	else if (currentStatus & TWI_MASTER_RIF_bm) {
+		TWI_MasterReadHandler(twi);
+	}
+
+	/* If unexpected state. */
+	else {
+		TWI_MasterTransactionFinished(twi, TWIM_RESULT_FAIL);
+	}
+}
+
+
+/*! \brief TWI master arbitration lost and bus error interrupt handler.
+ *
+ *  Handles TWI responses to lost arbitration and bus error.
+ *
+ *  \param twi  The TWI_Master_t struct instance.
+ */
+void TWI_MasterArbitrationLostBusErrorHandler(TWI_Master_t *twi)
+{
+	uint8_t currentStatus = twi->interface->MASTER.STATUS;
+
+	/* If bus error. */
+	if (currentStatus & TWI_MASTER_BUSERR_bm) {
+		twi->result = TWIM_RESULT_BUS_ERROR;
+	}
+	/* If arbitration lost. */
+	else {
+		twi->result = TWIM_RESULT_ARBITRATION_LOST;
+	}
+
+	/* Clear interrupt flag. */
+	twi->interface->MASTER.STATUS = currentStatus | TWI_MASTER_ARBLOST_bm;
+
+	twi->status = TWIM_STATUS_READY;
+}
+
+
+/*! \brief TWI master write interrupt handler.
+ *
+ *  Handles TWI transactions (master write) and responses to (N)ACK.
+ *
+ *  \param twi The TWI_Master_t struct instance.
+ */
+void TWI_MasterWriteHandler(TWI_Master_t *twi)
+{
+	/* Local variables used in if tests to avoid compiler warning. */
+	uint8_t bytesToWrite  = twi->bytesToWrite;
+	uint8_t bytesToRead   = twi->bytesToRead;
+
+	/* If NOT acknowledged (NACK) by slave cancel the transaction. */
+	if (twi->interface->MASTER.STATUS & TWI_MASTER_RXACK_bm) {
+		twi->interface->MASTER.CTRLC = TWI_MASTER_CMD_STOP_gc;
+		twi->result = TWIM_RESULT_NACK_RECEIVED;
+		twi->status = TWIM_STATUS_READY;
+	}
+
+	/* If more bytes to write, send data. */
+	else if (twi->bytesWritten < bytesToWrite) {
+		uint8_t data = twi->writeData[twi->bytesWritten];
+		twi->interface->MASTER.DATA = data;
+		++twi->bytesWritten;
+	}
+
+	/* If bytes to read, send repeated START condition + Address +
+	 * 'R/_W = 1'
+	 */
+	else if (twi->bytesRead < bytesToRead) {
+		uint8_t readAddress = twi->address | 0x01;
+		twi->interface->MASTER.ADDR = readAddress;
+	}
+
+	/* If transaction finished, send STOP condition and set RESULT OK. */
+	else {
+		twi->interface->MASTER.CTRLC = TWI_MASTER_CMD_STOP_gc;
+		TWI_MasterTransactionFinished(twi, TWIM_RESULT_OK);
+	}
+}
+
+
+/*! \brief TWI master read interrupt handler.
+ *
+ *  This is the master read interrupt handler that takes care of
+ *  reading bytes from the TWI slave.
+ *
+ *  \param twi The TWI_Master_t struct instance.
+ */
+void TWI_MasterReadHandler(TWI_Master_t *twi)
+{
+	/* Fetch data if bytes to be read. */
+	if (twi->bytesRead < TWIM_READ_BUFFER_SIZE) {
+		uint8_t data = twi->interface->MASTER.DATA;
+		twi->readData[twi->bytesRead] = data;
+		twi->bytesRead++;
+	}
+
+	/* If buffer overflow, issue STOP and BUFFER_OVERFLOW condition. */
+	else {
+		twi->interface->MASTER.CTRLC = TWI_MASTER_CMD_STOP_gc;
+		TWI_MasterTransactionFinished(twi, TWIM_RESULT_BUFFER_OVERFLOW);
+	}
+
+	/* Local variable used in if test to avoid compiler warning. */
+	uint8_t bytesToRead = twi->bytesToRead;
+
+	/* If more bytes to read, issue ACK and start a byte read. */
+	if (twi->bytesRead < bytesToRead) {
+		twi->interface->MASTER.CTRLC = TWI_MASTER_CMD_RECVTRANS_gc;
+	}
+
+	/* If transaction finished, issue NACK and STOP condition. */
+	else {
+		twi->interface->MASTER.CTRLC = TWI_MASTER_ACKACT_bm |
+		                               TWI_MASTER_CMD_STOP_gc;
+		TWI_MasterTransactionFinished(twi, TWIM_RESULT_OK);
+	}
+}
+
+
+/*! \brief TWI transaction finished handler.
+ *
+ *  Prepares module for new transaction.
+ *
+ *  \param twi     The TWI_Master_t struct instance.
+ *  \param result  The result of the operation.
+ */
+void TWI_MasterTransactionFinished(TWI_Master_t *twi, uint8_t result)
+{
+	twi->result = result;
+	twi->status = TWIM_STATUS_READY;
+}
+
+
+
+
+
+
+
+
+
+
+
+#endif /* TWI_MASTER_DRIVER_H */