From e7c861e23441790ce7522b7c0b96849fea315b0b Mon Sep 17 00:00:00 2001
From: Jake <jake.read@cba.mit.edu>
Date: Thu, 3 May 2018 22:19:49 -0400
Subject: [PATCH] add working usb cdc with 48MHz clock

---
 .../usb-adafruit-cdc/board_definitions.h      |  84 +++
 .../usb-adafruit-cdc/board_driver_serial.c    | 104 ++++
 .../usb-adafruit-cdc/board_driver_serial.h    |  89 +++
 .../usb-adafruit-cdc/board_driver_usb.c       | 359 ++++++++++++
 .../usb-adafruit-cdc/board_driver_usb.h       |  45 ++
 .../usb-adafruit-cdc/board_init.c             | 139 +++++
 .../usb-adafruit-cdc/usb-adafruit-cdc/main.c  |  67 +++
 .../usb-adafruit-cdc/sam_ba_cdc.c             |  98 ++++
 .../usb-adafruit-cdc/sam_ba_cdc.h             |  91 +++
 .../usb-adafruit-cdc/sam_ba_monitor.c         | 554 ++++++++++++++++++
 .../usb-adafruit-cdc/sam_ba_monitor.h         |  72 +++
 .../usb-adafruit-cdc/sam_ba_serial.c          | 529 +++++++++++++++++
 .../usb-adafruit-cdc/sam_ba_serial.h          | 143 +++++
 .../usb-adafruit-cdc/sam_ba_usb.c             | 436 ++++++++++++++
 .../usb-adafruit-cdc/sam_ba_usb.h             | 103 ++++
 15 files changed, 2913 insertions(+)
 create mode 100644 embedded/usb-adafruit-cdc/usb-adafruit-cdc/board_definitions.h
 create mode 100644 embedded/usb-adafruit-cdc/usb-adafruit-cdc/board_driver_serial.c
 create mode 100644 embedded/usb-adafruit-cdc/usb-adafruit-cdc/board_driver_serial.h
 create mode 100644 embedded/usb-adafruit-cdc/usb-adafruit-cdc/board_driver_usb.c
 create mode 100644 embedded/usb-adafruit-cdc/usb-adafruit-cdc/board_driver_usb.h
 create mode 100644 embedded/usb-adafruit-cdc/usb-adafruit-cdc/board_init.c
 create mode 100644 embedded/usb-adafruit-cdc/usb-adafruit-cdc/main.c
 create mode 100644 embedded/usb-adafruit-cdc/usb-adafruit-cdc/sam_ba_cdc.c
 create mode 100644 embedded/usb-adafruit-cdc/usb-adafruit-cdc/sam_ba_cdc.h
 create mode 100644 embedded/usb-adafruit-cdc/usb-adafruit-cdc/sam_ba_monitor.c
 create mode 100644 embedded/usb-adafruit-cdc/usb-adafruit-cdc/sam_ba_monitor.h
 create mode 100644 embedded/usb-adafruit-cdc/usb-adafruit-cdc/sam_ba_serial.c
 create mode 100644 embedded/usb-adafruit-cdc/usb-adafruit-cdc/sam_ba_serial.h
 create mode 100644 embedded/usb-adafruit-cdc/usb-adafruit-cdc/sam_ba_usb.c
 create mode 100644 embedded/usb-adafruit-cdc/usb-adafruit-cdc/sam_ba_usb.h

diff --git a/embedded/usb-adafruit-cdc/usb-adafruit-cdc/board_definitions.h b/embedded/usb-adafruit-cdc/usb-adafruit-cdc/board_definitions.h
new file mode 100644
index 0000000..f17f687
--- /dev/null
+++ b/embedded/usb-adafruit-cdc/usb-adafruit-cdc/board_definitions.h
@@ -0,0 +1,84 @@
+/*
+  Copyright (c) 2015 Arduino LLC.  All right reserved.
+  Copyright (c) 2015 Atmel Corporation/Thibaut VIARD.  All right reserved.
+
+  This library is free software; you can redistribute it and/or
+  modify it under the terms of the GNU Lesser General Public
+  License as published by the Free Software Foundation; either
+  version 2.1 of the License, or (at your option) any later version.
+
+  This library is distributed in the hope that it will be useful,
+  but WITHOUT ANY WARRANTY; without even the implied warranty of
+  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
+  See the GNU Lesser General Public License for more details.
+
+  You should have received a copy of the GNU Lesser General Public
+  License along with this library; if not, write to the Free Software
+  Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA  02110-1301  USA
+*/
+
+#ifndef _BOARD_DEFINITIONS_H_
+#define _BOARD_DEFINITIONS_H_
+/*
+ * USB device definitions
+ */
+#define STRING_PRODUCT "Metro M4"
+#define USB_VID_HIGH   0x23
+#define USB_VID_LOW    0x9A
+#define USB_PID_HIGH   0x00
+#define USB_PID_LOW    0x20
+
+
+/*
+ * If BOOT_DOUBLE_TAP_ADDRESS is defined the bootloader is started by
+ * quickly tapping two times on the reset button.
+ * BOOT_DOUBLE_TAP_ADDRESS must point to a free SRAM cell that must not
+ * be touched from the loaded application.
+ */
+#define BOOT_DOUBLE_TAP_ADDRESS           (HSRAM_ADDR + HSRAM_SIZE - 4)
+#define BOOT_DOUBLE_TAP_DATA              (*((volatile uint32_t *)BOOT_DOUBLE_TAP_ADDRESS))
+
+/*
+ * If BOOT_LOAD_PIN is defined the bootloader is started if the selected
+ * pin is tied LOW.
+ */
+//#define BOOT_LOAD_PIN                     PIN_PA21 // Pin 7
+//#define BOOT_LOAD_PIN                     PIN_PA15 // Pin 5
+
+#define GPIO(port, pin) ((((port)&0x7u) << 5) + ((pin)&0x1Fu))
+
+#define BOOK_USART_MASK					  APBAMASK
+#define BOOT_USART_MODULE                 SERCOM0
+#define BOOT_USART_BUS_CLOCK_INDEX        MCLK_APBAMASK_SERCOM0
+#define BOOT_GCLK_ID_CORE				  SERCOM0_GCLK_ID_CORE
+#define BOOT_GCLK_ID_SLOW				  SERCOM0_GCLK_ID_SLOW
+#define BOOT_USART_PAD_SETTINGS           UART_RX_PAD3_TX_PAD2
+#define BOOT_USART_PAD3                   PINMUX_UNUSED
+#define BOOT_USART_PAD2                   PINMUX_UNUSED
+
+#define BOOT_USART_PAD1                   PINMUX_PA10C_SERCOM0_PAD2
+#define BOOT_USART_PAD0                   PINMUX_PA11C_SERCOM0_PAD3
+
+/* Master clock frequency */
+#define CPU_FREQUENCY                     (120000000ul)
+#define VARIANT_MCK                       CPU_FREQUENCY
+
+/* Frequency of the board main oscillator */
+#define VARIANT_MAINOSC                   (32768ul)
+
+/* Calibration values for DFLL48 pll */
+#define NVM_SW_CALIB_DFLL48M_COARSE_VAL   (58)
+#define NVM_SW_CALIB_DFLL48M_FINE_VAL     (64)
+
+#define BOARD_LED_PORT                    (0)
+#define BOARD_LED_PIN                     (21)
+
+#define BOARD_LEDRX_PORT                  (1)
+#define BOARD_LEDRX_PIN                   (6)
+
+#define BOARD_LEDTX_PORT                  (0)
+#define BOARD_LEDTX_PIN                   (27)
+
+#define BOOT_PIN_MASK (1U << (BOOT_LOAD_PIN & 0x1f))
+
+#endif // _BOARD_DEFINITIONS_H_
diff --git a/embedded/usb-adafruit-cdc/usb-adafruit-cdc/board_driver_serial.c b/embedded/usb-adafruit-cdc/usb-adafruit-cdc/board_driver_serial.c
new file mode 100644
index 0000000..c474c5b
--- /dev/null
+++ b/embedded/usb-adafruit-cdc/usb-adafruit-cdc/board_driver_serial.c
@@ -0,0 +1,104 @@
+ /*
+  Copyright (c) 2015 Arduino LLC.  All right reserved.
+  Copyright (c) 2015 Atmel Corporation/Thibaut VIARD.  All right reserved.
+
+  This library is free software; you can redistribute it and/or
+  modify it under the terms of the GNU Lesser General Public
+  License as published by the Free Software Foundation; either
+  version 2.1 of the License, or (at your option) any later version.
+
+  This library is distributed in the hope that it will be useful,
+  but WITHOUT ANY WARRANTY; without even the implied warranty of
+  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
+  See the GNU Lesser General Public License for more details.
+
+  You should have received a copy of the GNU Lesser General Public
+  License along with this library; if not, write to the Free Software
+  Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA  02110-1301  USA
+*/
+
+#include "board_driver_serial.h"
+
+bool uart_drv_error_flag = false;
+
+void uart_basic_init(Sercom *sercom, uint16_t baud_val, enum uart_pad_settings pad_conf)
+{
+	/* Wait for synchronization */
+	while(sercom->USART.SYNCBUSY.bit.ENABLE);
+	/* Disable the SERCOM UART module */
+	sercom->USART.CTRLA.bit.ENABLE = 0;
+	/* Wait for synchronization */
+	while(sercom->USART.SYNCBUSY.bit.SWRST);
+	/* Perform a software reset */
+	sercom->USART.CTRLA.bit.SWRST = 1;
+	/* Wait for synchronization */
+	while(sercom->USART.CTRLA.bit.SWRST);
+	/* Wait for synchronization */
+	while(sercom->USART.SYNCBUSY.bit.SWRST || sercom->USART.SYNCBUSY.bit.ENABLE);
+	/* Update the UART pad settings, mode and data order settings */
+	sercom->USART.CTRLA.reg = pad_conf | SERCOM_USART_CTRLA_MODE(1) | SERCOM_USART_CTRLA_DORD;
+	/* Wait for synchronization */
+	while(sercom->USART.SYNCBUSY.bit.CTRLB);
+	/* Enable transmit and receive and set data size to 8 bits */
+	sercom->USART.CTRLB.reg = SERCOM_USART_CTRLB_RXEN | SERCOM_USART_CTRLB_TXEN | SERCOM_USART_CTRLB_CHSIZE(0);
+	/* Load the baud value */
+	sercom->USART.BAUD.reg = baud_val;
+	///* Wait for synchronization */
+	while(sercom->USART.SYNCBUSY.bit.ENABLE);
+	/* Enable SERCOM UART */
+	sercom->USART.CTRLA.bit.ENABLE = 1;
+}
+
+void uart_disable(Sercom *sercom)
+{
+	/* Wait for synchronization */
+	while(sercom->USART.SYNCBUSY.bit.ENABLE);
+	/* Disable SERCOM UART */
+	sercom->USART.CTRLA.bit.ENABLE = 0;
+}
+
+void uart_write_byte(Sercom *sercom, uint8_t data)
+{
+	/* Wait for Data Register Empty flag */
+	while(!sercom->USART.INTFLAG.bit.DRE);
+	/* Write the data to DATA register */
+	sercom->USART.DATA.reg = (uint16_t)data;
+}
+
+uint8_t uart_read_byte(Sercom *sercom)
+{
+	/* Wait for Receive Complete flag */
+	while(!sercom->USART.INTFLAG.bit.RXC);
+	/* Check for errors */
+	if (sercom->USART.STATUS.bit.PERR || sercom->USART.STATUS.bit.FERR || sercom->USART.STATUS.bit.BUFOVF)
+		/* Set the error flag */
+		uart_drv_error_flag = true;
+	/* Return the read data */
+	return((uint8_t)sercom->USART.DATA.reg);
+}
+
+void uart_write_buffer_polled(Sercom *sercom, uint8_t *ptr, uint16_t length)
+{
+	/* Do the following for specified length */
+	do {
+		/* Wait for Data Register Empty flag */
+		while(!sercom->USART.INTFLAG.bit.DRE);
+		/* Send data from the buffer */
+		sercom->USART.DATA.reg = (uint16_t)*ptr++;
+	} while (length--);
+}
+
+void uart_read_buffer_polled(Sercom *sercom, uint8_t *ptr, uint16_t length)
+{
+	/* Do the following for specified length */
+	do {
+		/* Wait for Receive Complete flag */
+		while(!sercom->USART.INTFLAG.bit.RXC);
+		/* Check for errors */
+		if (sercom->USART.STATUS.bit.PERR || sercom->USART.STATUS.bit.FERR || sercom->USART.STATUS.bit.BUFOVF)
+			/* Set the error flag */
+			uart_drv_error_flag = true;
+		/* Store the read data to the buffer */
+		*ptr++ = (uint8_t)sercom->USART.DATA.reg;
+	} while (length--);
+}
diff --git a/embedded/usb-adafruit-cdc/usb-adafruit-cdc/board_driver_serial.h b/embedded/usb-adafruit-cdc/usb-adafruit-cdc/board_driver_serial.h
new file mode 100644
index 0000000..809f7ec
--- /dev/null
+++ b/embedded/usb-adafruit-cdc/usb-adafruit-cdc/board_driver_serial.h
@@ -0,0 +1,89 @@
+/*
+  Copyright (c) 2015 Arduino LLC.  All right reserved.
+  Copyright (c) 2015 Atmel Corporation/Thibaut VIARD.  All right reserved.
+
+  This library is free software; you can redistribute it and/or
+  modify it under the terms of the GNU Lesser General Public
+  License as published by the Free Software Foundation; either
+  version 2.1 of the License, or (at your option) any later version.
+
+  This library is distributed in the hope that it will be useful,
+  but WITHOUT ANY WARRANTY; without even the implied warranty of
+  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
+  See the GNU Lesser General Public License for more details.
+
+  You should have received a copy of the GNU Lesser General Public
+  License along with this library; if not, write to the Free Software
+  Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA  02110-1301  USA
+*/
+
+#ifndef UART_DRIVER_H
+#define UART_DRIVER_H
+
+#include <stdio.h>
+#include <stdbool.h>
+#include <sam.h>
+
+#define PINMUX_UNUSED          0xFFFFFFFF
+
+/* SERCOM UART available pad settings */
+enum uart_pad_settings {
+	UART_RX_PAD0_TX_PAD2 = SERCOM_USART_CTRLA_RXPO(0) | SERCOM_USART_CTRLA_TXPO(1),
+	UART_RX_PAD1_TX_PAD2 = SERCOM_USART_CTRLA_RXPO(1) | SERCOM_USART_CTRLA_TXPO(1),
+	UART_RX_PAD2_TX_PAD0 = SERCOM_USART_CTRLA_RXPO(2),
+	UART_RX_PAD3_TX_PAD0 = SERCOM_USART_CTRLA_RXPO(3),
+	UART_RX_PAD1_TX_PAD0 = SERCOM_USART_CTRLA_RXPO(1),
+	UART_RX_PAD3_TX_PAD2 = SERCOM_USART_CTRLA_RXPO(3) | SERCOM_USART_CTRLA_TXPO(1),
+};
+
+/**
+ * \brief Initializes the UART
+ *
+ * \param Pointer to SERCOM instance
+ * \param Baud value corresponding to the desired baudrate
+ * \param SERCOM pad settings
+ */
+void uart_basic_init(Sercom *sercom, uint16_t baud_val, enum uart_pad_settings pad_conf);
+
+/**
+ * \brief Disables UART interface
+ *
+ * \param Pointer to SERCOM instance
+ */
+void uart_disable(Sercom *sercom);
+
+/**
+ * \brief Sends a single byte through UART interface
+ *
+ * \param Pointer to SERCOM instance
+ * \param Data to send
+ */
+void uart_write_byte(Sercom *sercom, uint8_t data);
+
+/**
+ * \brief Reads a single character from UART interface
+ *
+ * \param Pointer to SERCOM instance
+ * \return Data byte read
+ */
+uint8_t uart_read_byte(Sercom *sercom);
+
+/**
+ * \brief Sends buffer on UART interface
+ *
+ * \param Pointer to SERCOM instance
+ * \param Pointer to data to send
+ * \param Number of bytes to send
+ */
+void uart_write_buffer_polled(Sercom *sercom, uint8_t *ptr, uint16_t length);
+
+/**
+ * \brief Reads data on UART interface
+ *
+ * \param Pointer to SERCOM instance
+ * \param Pointer to store read data
+ * \param Number of bytes to read
+ */
+void uart_read_buffer_polled(Sercom *sercom, uint8_t *ptr, uint16_t length);
+
+#endif
diff --git a/embedded/usb-adafruit-cdc/usb-adafruit-cdc/board_driver_usb.c b/embedded/usb-adafruit-cdc/usb-adafruit-cdc/board_driver_usb.c
new file mode 100644
index 0000000..2e45b9c
--- /dev/null
+++ b/embedded/usb-adafruit-cdc/usb-adafruit-cdc/board_driver_usb.c
@@ -0,0 +1,359 @@
+/*
+  Copyright (c) 2015 Arduino LLC.  All right reserved.
+  Copyright (c) 2015 Atmel Corporation/Thibaut VIARD.  All right reserved.
+
+  This library is free software; you can redistribute it and/or
+  modify it under the terms of the GNU Lesser General Public
+  License as published by the Free Software Foundation; either
+  version 2.1 of the License, or (at your option) any later version.
+
+  This library is distributed in the hope that it will be useful,
+  but WITHOUT ANY WARRANTY; without even the implied warranty of
+  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
+  See the GNU Lesser General Public License for more details.
+
+  You should have received a copy of the GNU Lesser General Public
+  License along with this library; if not, write to the Free Software
+  Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA  02110-1301  USA
+*/
+
+#include <string.h>
+#include "board_driver_usb.h"
+#include "sam_ba_usb.h"
+#include "sam_ba_cdc.h"
+
+#define NVM_USB_PAD_TRANSN_POS 32
+#define NVM_USB_PAD_TRANSN_SIZE 5
+#define NVM_USB_PAD_TRANSP_POS 37
+#define NVM_USB_PAD_TRANSP_SIZE 5
+#define NVM_USB_PAD_TRIM_POS 42
+#define NVM_USB_PAD_TRIM_SIZE 3
+
+__attribute__((__aligned__(4))) UsbDeviceDescriptor usb_endpoint_table[MAX_EP]; // Initialized to zero in USB_Init
+__attribute__((__aligned__(4))) uint8_t udd_ep_out_cache_buffer[2][64]; //1 for CTRL, 1 for BULK
+__attribute__((__aligned__(4))) uint8_t udd_ep_in_cache_buffer[2][64]; //1 for CTRL, 1 for BULK
+
+static volatile bool read_job = false;
+
+/*----------------------------------------------------------------------------
+ * \brief
+ */
+P_USB_CDC USB_Open(P_USB_CDC pCdc, Usb *pUsb)
+{
+  pCdc->pUsb = pUsb;
+  pCdc->currentConfiguration = 0;
+  pCdc->currentConnection    = 0;
+  pCdc->IsConfigured = USB_IsConfigured;
+//  pCdc->Write        = USB_Write;
+//  pCdc->Read         = USB_Read;
+
+  pCdc->pUsb->HOST.CTRLA.bit.ENABLE = true;
+  
+  while( pCdc->pUsb->HOST.SYNCBUSY.reg & USB_SYNCBUSY_ENABLE ); //wait for sync
+
+  return pCdc;
+}
+
+
+/**
+ * \brief Load USB calibration value from NVM
+ */
+static void USB_load_calib(void)
+{
+	Usb *    hw = USB;
+	uint32_t pad_transn
+	    = (*((uint32_t *)(NVMCTRL_SW0) + (NVM_USB_PAD_TRANSN_POS / 32)) >> (NVM_USB_PAD_TRANSN_POS % 32))
+	      & ((1 << NVM_USB_PAD_TRANSN_SIZE) - 1);
+	uint32_t pad_transp
+	    = (*((uint32_t *)(NVMCTRL_SW0) + (NVM_USB_PAD_TRANSP_POS / 32)) >> (NVM_USB_PAD_TRANSP_POS % 32))
+	      & ((1 << NVM_USB_PAD_TRANSP_SIZE) - 1);
+	uint32_t pad_trim = (*((uint32_t *)(NVMCTRL_SW0) + (NVM_USB_PAD_TRIM_POS / 32)) >> (NVM_USB_PAD_TRIM_POS % 32))
+	                    & ((1 << NVM_USB_PAD_TRIM_SIZE) - 1);
+	if (pad_transn == 0 || pad_transn == 0x1F) {
+		pad_transn = 9;
+	}
+	if (pad_transp == 0 || pad_transp == 0x1F) {
+		pad_transp = 25;
+	}
+	if (pad_trim == 0 || pad_trim == 0x7) {
+		pad_trim = 6;
+	}
+
+	hw->DEVICE.PADCAL.reg = USB_PADCAL_TRANSN(pad_transn) | USB_PADCAL_TRANSP(pad_transp) | USB_PADCAL_TRIM(pad_trim);
+
+	hw->DEVICE.QOSCTRL.bit.CQOS = 3;
+	hw->DEVICE.QOSCTRL.bit.DQOS = 3;
+}
+
+/*----------------------------------------------------------------------------
+ * \brief Initializes USB
+ */
+void USB_Init(void)
+{
+  uint32_t pad_transn, pad_transp, pad_trim;
+
+  /* Enable USB clock */
+  MCLK->APBBMASK.bit.USB_ = 1;
+
+  /* Set up the USB DP/DN pins */
+  PORT->Group[0].PINCFG[PIN_PA24H_USB_DM].bit.PMUXEN = 1;
+  PORT->Group[0].PMUX[PIN_PA24H_USB_DM/2].reg &= ~(0xF << (4 * (PIN_PA24H_USB_DM & 0x01u)));
+  PORT->Group[0].PMUX[PIN_PA24H_USB_DM/2].reg |= MUX_PA24H_USB_DM << (4 * (PIN_PA24H_USB_DM & 0x01u));
+  PORT->Group[0].PINCFG[PIN_PA25H_USB_DP].bit.PMUXEN = 1;
+  PORT->Group[0].PMUX[PIN_PA25H_USB_DP/2].reg &= ~(0xF << (4 * (PIN_PA25H_USB_DP & 0x01u)));
+  PORT->Group[0].PMUX[PIN_PA25H_USB_DP/2].reg |= MUX_PA25H_USB_DP << (4 * (PIN_PA25H_USB_DP & 0x01u));
+
+  /* ----------------------------------------------------------------------------------------------
+   * Put Generic Clock Generator 0 as source for Generic Clock Multiplexer 6 (USB reference)
+   *
+	*/
+  GCLK->PCHCTRL[USB_GCLK_ID].reg = GCLK_PCHCTRL_GEN_GCLK0_Val | (1 << GCLK_PCHCTRL_CHEN_Pos);
+  MCLK->APBBMASK.reg |= MCLK_APBBMASK_USB;
+  while(GCLK->SYNCBUSY.bit.GENCTRL0)
+  {
+    /* Wait for synchronization */
+  }
+
+  /* Reset */
+  USB->DEVICE.CTRLA.bit.SWRST = 1;
+  while (USB->DEVICE.SYNCBUSY.bit.SWRST)
+  {
+    /* Sync wait */
+  }
+
+  USB_load_calib();
+
+  /* Set the configuration */
+  /* Set mode to Device mode */
+  USB->HOST.CTRLA.bit.MODE = 0;
+  /* Enable Run in Standby */
+  USB->HOST.CTRLA.bit.RUNSTDBY = true;
+  /* Set the descriptor address */
+  USB->HOST.DESCADD.reg = (uint32_t)(&usb_endpoint_table[0]);
+  /* Set speed configuration to Full speed */
+  USB->DEVICE.CTRLB.bit.SPDCONF = USB_DEVICE_CTRLB_SPDCONF_FS_Val;
+  /* Attach to the USB host */
+  USB->DEVICE.CTRLB.reg &= ~USB_DEVICE_CTRLB_DETACH;
+
+  /* Initialize endpoint table RAM location to a known value 0 */
+  memset((uint8_t *)(&usb_endpoint_table[0]), 0, sizeof(usb_endpoint_table));
+}
+
+uint32_t USB_Write(Usb *pUsb, const char *pData, uint32_t length, uint8_t ep_num)
+{
+  uint32_t data_address;
+  uint8_t buf_index;
+
+  /* Set buffer index */
+  buf_index = (ep_num == 0) ? 0 : 1;
+
+  /* Check for requirement for multi-packet or auto zlp */
+  if (length >= (1 << (usb_endpoint_table[ep_num].DeviceDescBank[1].PCKSIZE.bit.SIZE + 3)))
+  {
+    /* Update the EP data address */
+    data_address = (uint32_t) pData;
+    /* Enable auto zlp */
+    usb_endpoint_table[ep_num].DeviceDescBank[1].PCKSIZE.bit.AUTO_ZLP = true;
+  }
+  else
+  {
+    /* Copy to local buffer */
+    memcpy(udd_ep_in_cache_buffer[buf_index], pData, length);
+    /* Update the EP data address */
+    data_address = (uint32_t) &udd_ep_in_cache_buffer[buf_index];
+  }
+
+  /* Set the buffer address for ep data */
+  usb_endpoint_table[ep_num].DeviceDescBank[1].ADDR.reg = data_address;
+  /* Set the byte count as zero */
+  usb_endpoint_table[ep_num].DeviceDescBank[1].PCKSIZE.bit.BYTE_COUNT = length;
+  /* Set the multi packet size as zero for multi-packet transfers where length > ep size */
+  usb_endpoint_table[ep_num].DeviceDescBank[1].PCKSIZE.bit.MULTI_PACKET_SIZE = 0;
+  /* Clear the transfer complete flag  */
+  pUsb->DEVICE.DeviceEndpoint[ep_num].EPINTFLAG.reg = USB_DEVICE_EPINTFLAG_TRCPT1;
+  /* Set the bank as ready */
+  pUsb->DEVICE.DeviceEndpoint[ep_num].EPSTATUSSET.bit.BK1RDY = true;
+
+  /* Wait for transfer to complete */
+  while ( (pUsb->DEVICE.DeviceEndpoint[ep_num].EPINTFLAG.bit.TRCPT1) == 0 );
+
+  return length;
+}
+
+/*----------------------------------------------------------------------------
+ * \brief Read available data from Endpoint OUT
+ */
+uint32_t USB_Read(Usb *pUsb, char *pData, uint32_t length)
+{
+  uint32_t packetSize = 0;
+
+  if (!read_job)
+  {
+    /* Set the buffer address for ep data */
+    usb_endpoint_table[USB_EP_OUT].DeviceDescBank[0].ADDR.reg = (uint32_t)&udd_ep_out_cache_buffer[USB_EP_OUT-1];
+    /* Set the byte count as zero */
+    usb_endpoint_table[USB_EP_OUT].DeviceDescBank[0].PCKSIZE.bit.BYTE_COUNT = 0;
+    /* Set the byte count as zero */
+    usb_endpoint_table[USB_EP_OUT].DeviceDescBank[0].PCKSIZE.bit.MULTI_PACKET_SIZE = 0;
+    /* Start the reception by clearing the bank 0 ready bit */
+    pUsb->DEVICE.DeviceEndpoint[USB_EP_OUT].EPSTATUSCLR.bit.BK0RDY = true;
+    /* set the user flag */
+    read_job = true;
+  }
+
+  /* Check for Transfer Complete 0 flag */
+  if ( pUsb->DEVICE.DeviceEndpoint[USB_EP_OUT].EPINTFLAG.bit.TRCPT0 )
+  {
+    /* Set packet size */
+    packetSize = SAM_BA_MIN(usb_endpoint_table[USB_EP_OUT].DeviceDescBank[0].PCKSIZE.bit.BYTE_COUNT, length);
+    /* Copy read data to user buffer */
+    memcpy(pData, udd_ep_out_cache_buffer[USB_EP_OUT-1], packetSize);
+    /* Clear the Transfer Complete 0 flag */
+    pUsb->DEVICE.DeviceEndpoint[USB_EP_OUT].EPINTFLAG.reg = USB_DEVICE_EPINTFLAG_TRCPT0;
+    /* Clear the user flag */
+    read_job = false;
+  }
+
+  return packetSize;
+}
+
+uint32_t USB_Read_blocking(Usb *pUsb, char *pData, uint32_t length)
+{
+  if (read_job)
+  {
+    /* Stop the reception by setting the bank 0 ready bit */
+    pUsb->DEVICE.DeviceEndpoint[USB_EP_OUT].EPSTATUSSET.bit.BK0RDY = true;
+    /* Clear the user flag */
+    read_job = false;
+  }
+
+  /* Set the buffer address for ep data */
+  usb_endpoint_table[USB_EP_OUT].DeviceDescBank[0].ADDR.reg = ((uint32_t)pData);
+  /* Set the byte count as zero */
+  usb_endpoint_table[USB_EP_OUT].DeviceDescBank[0].PCKSIZE.bit.BYTE_COUNT = 0;
+  /* Set the multi packet size as zero for multi-packet transfers where length > ep size */
+  usb_endpoint_table[USB_EP_OUT].DeviceDescBank[0].PCKSIZE.bit.MULTI_PACKET_SIZE = length;
+  /* Clear the bank 0 ready flag */
+  pUsb->DEVICE.DeviceEndpoint[USB_EP_OUT].EPSTATUSCLR.bit.BK0RDY = true;
+  /* Wait for transfer to complete */
+  while (!( pUsb->DEVICE.DeviceEndpoint[USB_EP_OUT].EPINTFLAG.bit.TRCPT0 ));
+  /* Clear Transfer complete 0 flag */
+  pUsb->DEVICE.DeviceEndpoint[USB_EP_OUT].EPINTFLAG.reg = USB_DEVICE_EPINTFLAG_TRCPT0;
+
+  return length;
+}
+
+/*----------------------------------------------------------------------------
+ * \brief Test if the device is configured and handle enumeration
+ */
+uint8_t USB_IsConfigured(P_USB_CDC pCdc)
+{
+  Usb *pUsb = pCdc->pUsb;
+
+  /* Check for End of Reset flag */
+  if (pUsb->DEVICE.INTFLAG.reg & USB_DEVICE_INTFLAG_EORST)
+  {
+    /* Clear the flag */
+    pUsb->DEVICE.INTFLAG.reg = USB_DEVICE_INTFLAG_EORST;
+    /* Set Device address as 0 */
+    pUsb->DEVICE.DADD.reg = USB_DEVICE_DADD_ADDEN | 0;
+    /* Configure endpoint 0 */
+    /* Configure Endpoint 0 for Control IN and Control OUT */
+    pUsb->DEVICE.DeviceEndpoint[0].EPCFG.reg = USB_DEVICE_EPCFG_EPTYPE0(1) | USB_DEVICE_EPCFG_EPTYPE1(1);
+    pUsb->DEVICE.DeviceEndpoint[0].EPSTATUSSET.reg = USB_DEVICE_EPSTATUSSET_BK0RDY;
+    pUsb->DEVICE.DeviceEndpoint[0].EPSTATUSCLR.reg = USB_DEVICE_EPSTATUSCLR_BK1RDY;
+    /* Configure control OUT Packet size to 64 bytes */
+    usb_endpoint_table[0].DeviceDescBank[0].PCKSIZE.bit.SIZE = 3;
+    /* Configure control IN Packet size to 64 bytes */
+    usb_endpoint_table[0].DeviceDescBank[1].PCKSIZE.bit.SIZE = 3;
+    /* Configure the data buffer address for control OUT */
+    usb_endpoint_table[0].DeviceDescBank[0].ADDR.reg = (uint32_t)&udd_ep_out_cache_buffer[0];
+    /* Configure the data buffer address for control IN */
+    usb_endpoint_table[0].DeviceDescBank[1].ADDR.reg = (uint32_t)&udd_ep_in_cache_buffer[0];
+    /* Set Multipacket size to 8 for control OUT and byte count to 0*/
+    usb_endpoint_table[0].DeviceDescBank[0].PCKSIZE.bit.MULTI_PACKET_SIZE = 8;
+    usb_endpoint_table[0].DeviceDescBank[0].PCKSIZE.bit.BYTE_COUNT = 0;
+    pUsb->DEVICE.DeviceEndpoint[0].EPSTATUSCLR.reg = USB_DEVICE_EPSTATUSCLR_BK0RDY;
+
+    // Reset current configuration value to 0
+    pCdc->currentConfiguration = 0;
+  }
+  else
+  {
+    if (pUsb->DEVICE.DeviceEndpoint[0].EPINTFLAG.reg & USB_DEVICE_EPINTFLAG_RXSTP)
+    {
+      sam_ba_usb_CDC_Enumerate(pCdc);
+    }
+  }
+
+  return pCdc->currentConfiguration;
+}
+
+/*----------------------------------------------------------------------------
+ * \brief Stall the control endpoint
+ */
+void USB_SendStall(Usb *pUsb, bool direction_in)
+{
+  /* Check the direction */
+  if (direction_in)
+  {
+    /* Set STALL request on IN direction */
+    pUsb->DEVICE.DeviceEndpoint[0].EPSTATUSSET.bit.STALLRQ1 = 1;
+  }
+  else
+  {
+    /* Set STALL request on OUT direction */
+    pUsb->DEVICE.DeviceEndpoint[0].EPSTATUSSET.bit.STALLRQ0 = 1;
+  }
+}
+
+/*----------------------------------------------------------------------------
+ * \brief Send zero length packet through the control endpoint
+ */
+void USB_SendZlp(Usb *pUsb)
+{
+  /* Set the byte count as zero */
+  usb_endpoint_table[0].DeviceDescBank[1].PCKSIZE.bit.BYTE_COUNT = 0;
+  /* Clear the transfer complete flag  */
+  pUsb->DEVICE.DeviceEndpoint[0].EPINTFLAG.reg = USB_DEVICE_EPINTFLAG_TRCPT1;
+  /* Set the bank as ready */
+  pUsb->DEVICE.DeviceEndpoint[0].EPSTATUSSET.bit.BK1RDY = true;
+  /* Wait for transfer to complete */
+  while (!( pUsb->DEVICE.DeviceEndpoint[0].EPINTFLAG.bit.TRCPT1 ));
+}
+
+/*----------------------------------------------------------------------------
+ * \brief Set USB device address obtained from host
+ */
+void USB_SetAddress(Usb *pUsb, uint16_t wValue)
+{
+  pUsb->DEVICE.DADD.reg = USB_DEVICE_DADD_ADDEN | wValue;
+}
+
+/*----------------------------------------------------------------------------
+ * \brief Configure USB device
+ */
+void USB_Configure(Usb *pUsb)
+{
+  /* Configure BULK OUT endpoint for CDC Data interface*/
+  pUsb->DEVICE.DeviceEndpoint[USB_EP_OUT].EPCFG.reg = USB_DEVICE_EPCFG_EPTYPE0(3);
+  /* Set maximum packet size as 64 bytes */
+  usb_endpoint_table[USB_EP_OUT].DeviceDescBank[0].PCKSIZE.bit.SIZE = 3;
+  pUsb->DEVICE.DeviceEndpoint[USB_EP_OUT].EPSTATUSSET.reg = USB_DEVICE_EPSTATUSSET_BK0RDY;
+  /* Configure the data buffer */
+  usb_endpoint_table[USB_EP_OUT].DeviceDescBank[0].ADDR.reg = (uint32_t)&udd_ep_out_cache_buffer[1];
+
+  /* Configure BULK IN endpoint for CDC Data interface */
+  pUsb->DEVICE.DeviceEndpoint[USB_EP_IN].EPCFG.reg = USB_DEVICE_EPCFG_EPTYPE1(3);
+  /* Set maximum packet size as 64 bytes */
+  usb_endpoint_table[USB_EP_IN].DeviceDescBank[1].PCKSIZE.bit.SIZE = 3;
+  pUsb->DEVICE.DeviceEndpoint[USB_EP_IN].EPSTATUSCLR.reg = USB_DEVICE_EPSTATUSCLR_BK1RDY;
+  /* Configure the data buffer */
+  usb_endpoint_table[USB_EP_IN].DeviceDescBank[1].ADDR.reg = (uint32_t)&udd_ep_in_cache_buffer[1];
+
+  /* Configure INTERRUPT IN endpoint for CDC COMM interface*/
+  pUsb->DEVICE.DeviceEndpoint[USB_EP_COMM].EPCFG.reg = USB_DEVICE_EPCFG_EPTYPE1(4);
+  /* Set maximum packet size as 64 bytes */
+  usb_endpoint_table[USB_EP_COMM].DeviceDescBank[1].PCKSIZE.bit.SIZE = 0;
+  pUsb->DEVICE.DeviceEndpoint[USB_EP_COMM].EPSTATUSCLR.reg = USB_DEVICE_EPSTATUSCLR_BK1RDY;
+}
diff --git a/embedded/usb-adafruit-cdc/usb-adafruit-cdc/board_driver_usb.h b/embedded/usb-adafruit-cdc/usb-adafruit-cdc/board_driver_usb.h
new file mode 100644
index 0000000..2ee2022
--- /dev/null
+++ b/embedded/usb-adafruit-cdc/usb-adafruit-cdc/board_driver_usb.h
@@ -0,0 +1,45 @@
+/*
+  Copyright (c) 2015 Arduino LLC.  All right reserved.
+  Copyright (c) 2015 Atmel Corporation/Thibaut VIARD.  All right reserved.
+
+  This library is free software; you can redistribute it and/or
+  modify it under the terms of the GNU Lesser General Public
+  License as published by the Free Software Foundation; either
+  version 2.1 of the License, or (at your option) any later version.
+
+  This library is distributed in the hope that it will be useful,
+  but WITHOUT ANY WARRANTY; without even the implied warranty of
+  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
+  See the GNU Lesser General Public License for more details.
+
+  You should have received a copy of the GNU Lesser General Public
+  License along with this library; if not, write to the Free Software
+  Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA  02110-1301  USA
+*/
+
+#ifndef _DRIVER_USB_H_
+#define _DRIVER_USB_H_
+
+#include "sam_ba_cdc.h"
+
+extern UsbDeviceDescriptor usb_endpoint_table[MAX_EP];
+extern uint8_t udd_ep_out_cache_buffer[2][64]; //1 for CTRL, 1 for BULK
+extern uint8_t udd_ep_in_cache_buffer[2][64]; //1 for CTRL, 1 for BULK
+
+P_USB_CDC USB_Open(P_USB_CDC pCdc, Usb *pUsb);
+
+void USB_Init(void);
+
+uint32_t USB_Write(Usb *pUsb, const char *pData, uint32_t length, uint8_t ep_num);
+uint32_t USB_Read(Usb *pUsb, char *pData, uint32_t length);
+uint32_t USB_Read_blocking(Usb *pUsb, char *pData, uint32_t length);
+
+uint8_t USB_IsConfigured(P_USB_CDC pCdc);
+
+void USB_SendStall(Usb *pUsb, bool direction_in);
+void USB_SendZlp(Usb *pUsb);
+
+void USB_SetAddress(Usb *pUsb, uint16_t wValue);
+void USB_Configure(Usb *pUsb);
+
+#endif // _BOARD_DRIVER_USB_H_
diff --git a/embedded/usb-adafruit-cdc/usb-adafruit-cdc/board_init.c b/embedded/usb-adafruit-cdc/usb-adafruit-cdc/board_init.c
new file mode 100644
index 0000000..91c79c6
--- /dev/null
+++ b/embedded/usb-adafruit-cdc/usb-adafruit-cdc/board_init.c
@@ -0,0 +1,139 @@
+/*
+Copyright (c) 2015 Arduino LLC.  All right reserved.
+Copyright (c) 2015 Atmel Corporation/Thibaut VIARD.  All right reserved.
+
+This library is free software; you can redistribute it and/or
+modify it under the terms of the GNU Lesser General Public
+License as published by the Free Software Foundation; either
+version 2.1 of the License, or (at your option) any later version.
+
+This library is distributed in the hope that it will be useful,
+but WITHOUT ANY WARRANTY; without even the implied warranty of
+MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
+See the GNU Lesser General Public License for more details.
+
+You should have received a copy of the GNU Lesser General Public
+License along with this library; if not, write to the Free Software
+Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA  02110-1301  USA
+*/
+
+#include <sam.h>
+#include "board_definitions.h"
+
+/**
+* \brief system_init() configures the needed clocks and according Flash Read Wait States.
+* We need to:
+* 1) Enable XOSC32K clock (External on-board 32.768Hz oscillator), will be used as DFLL48M reference.
+* 2) Put XOSC32K as source of Generic Clock Generator 3
+* 3) Put Generic Clock Generator 3 as source for Generic Clock Multiplexer 0 (DFLL48M reference)
+* 4) Enable DFLL48M clock
+* 5) Switch Generic Clock Generator 0 to DFLL48M. CPU will run at 48MHz.
+*/
+
+void board_init(void)
+{
+	
+	/* Set 1 Flash Wait State for 48MHz */
+	NVMCTRL->CTRLA.reg |= NVMCTRL_CTRLA_RWS(0);
+
+	/* ----------------------------------------------------------------------------------------------
+	* 1) Enable XOSC32K clock (External on-board 32.768Hz oscillator)
+	*/
+	OSC32KCTRL->OSCULP32K.reg = OSC32KCTRL_OSCULP32K_EN32K;
+	/*
+	while( (OSC32KCTRL->STATUS.reg & OSC32KCTRL_STATUS_XOSC32KRDY) == 0 ){
+	// wait ready
+	}
+	*/
+	
+	OSC32KCTRL->RTCCTRL.bit.RTCSEL = OSC32KCTRL_RTCCTRL_RTCSEL_ULP1K;
+
+
+	/* Software reset the module to ensure it is re-initialized correctly */
+	/* Note: Due to synchronization, there is a delay from writing CTRL.SWRST until the reset is complete.
+	* CTRL.SWRST and STATUS.SYNCBUSY will both be cleared when the reset is complete
+	*/
+	GCLK->CTRLA.bit.SWRST = 1;
+	while ( GCLK->SYNCBUSY.reg & GCLK_SYNCBUSY_SWRST ){
+		/* wait for reset to complete */
+	}
+	
+	/* ----------------------------------------------------------------------------------------------
+	* 2) Put XOSC32K as source of Generic Clock Generator 3
+	*/
+	GCLK->GENCTRL[3].reg = GCLK_GENCTRL_SRC(GCLK_GENCTRL_SRC_OSCULP32K) | //generic clock gen 3
+	GCLK_GENCTRL_GENEN;
+
+	while ( GCLK->SYNCBUSY.reg & GCLK_SYNCBUSY_GENCTRL3 ){
+		/* Wait for synchronization */
+	}
+	
+	/* ----------------------------------------------------------------------------------------------
+	* 3) Put Generic Clock Generator 3 as source for Generic Clock Gen 0 (DFLL48M reference)
+	*/
+	GCLK->GENCTRL[0].reg = GCLK_GENCTRL_SRC(GCLK_GENCTRL_SRC_OSCULP32K) | GCLK_GENCTRL_GENEN;
+	
+	/* ----------------------------------------------------------------------------------------------
+	* 4) Enable DFLL48M clock
+	*/
+
+	/* DFLL Configuration in Open Loop mode */
+
+	OSCCTRL->DFLLCTRLA.reg = 0;
+	//GCLK->PCHCTRL[OSCCTRL_GCLK_ID_DFLL48].reg = (1 << GCLK_PCHCTRL_CHEN_Pos) | GCLK_PCHCTRL_GEN(GCLK_PCHCTRL_GEN_GCLK3_Val);
+
+	OSCCTRL->DFLLMUL.reg = OSCCTRL_DFLLMUL_CSTEP( 0x1 ) |
+	OSCCTRL_DFLLMUL_FSTEP( 0x1 ) |
+	OSCCTRL_DFLLMUL_MUL( 0 );
+
+	while ( OSCCTRL->DFLLSYNC.reg & OSCCTRL_DFLLSYNC_DFLLMUL )
+	{
+		/* Wait for synchronization */
+	}
+	
+	OSCCTRL->DFLLCTRLB.reg = 0;
+	while ( OSCCTRL->DFLLSYNC.reg & OSCCTRL_DFLLSYNC_DFLLCTRLB )
+	{
+		/* Wait for synchronization */
+	}
+	
+	OSCCTRL->DFLLCTRLA.reg |= OSCCTRL_DFLLCTRLA_ENABLE;
+	while ( OSCCTRL->DFLLSYNC.reg & OSCCTRL_DFLLSYNC_ENABLE )
+	{
+		/* Wait for synchronization */
+	}
+	
+	OSCCTRL->DFLLVAL.reg = OSCCTRL->DFLLVAL.reg;
+	while( OSCCTRL->DFLLSYNC.bit.DFLLVAL );
+	
+	OSCCTRL->DFLLCTRLB.reg = OSCCTRL_DFLLCTRLB_WAITLOCK |
+	OSCCTRL_DFLLCTRLB_CCDIS | OSCCTRL_DFLLCTRLB_USBCRM ;
+	
+	while ( !OSCCTRL->STATUS.bit.DFLLRDY )
+	{
+		/* Wait for synchronization */
+	}
+
+	/* ----------------------------------------------------------------------------------------------
+	* 5) Switch Generic Clock Generator 0 to DFLL48M. CPU will run at 48MHz.
+	*/
+	GCLK->GENCTRL[0].reg = GCLK_GENCTRL_SRC(GCLK_GENCTRL_SRC_DFLL) |
+	GCLK_GENCTRL_IDC |
+	GCLK_GENCTRL_OE |
+	GCLK_GENCTRL_GENEN;
+
+	while ( GCLK->SYNCBUSY.reg & GCLK_SYNCBUSY_GENCTRL0 )
+	{
+		/* Wait for synchronization */
+	}
+	
+	
+	/* Turn on the digital interface clock */
+	//MCLK->APBAMASK.reg |= MCLK_APBAMASK_GCLK;
+
+	/*
+	* Now that all system clocks are configured, we can set CLKDIV .
+	* These values are normally the ones present after Reset.
+	*/
+	MCLK->CPUDIV.reg = MCLK_CPUDIV_DIV_DIV1;
+}
diff --git a/embedded/usb-adafruit-cdc/usb-adafruit-cdc/main.c b/embedded/usb-adafruit-cdc/usb-adafruit-cdc/main.c
new file mode 100644
index 0000000..18ac1b9
--- /dev/null
+++ b/embedded/usb-adafruit-cdc/usb-adafruit-cdc/main.c
@@ -0,0 +1,67 @@
+/*
+ * usb-adafruit-cdc.c
+ *
+ * Created: 5/3/2018 6:39:05 PM
+ * Author : Jake
+ */ 
+
+#include <stdio.h>
+#include "sam.h"
+#include "sam_ba_usb.h"
+#include "sam_ba_monitor.h"
+
+static volatile bool main_b_cdc_enable = false;
+
+int main(void)
+{
+    /* Initialize the SAM system */
+    SystemInit();
+	
+	// clock setup to run main CPU at 120MHz, and DFLL48M setup from internal osc, should run USB
+	board_init();
+	// enable interrupts in the system
+	__enable_irq();
+	
+	// turning a light on to see if we hang
+	PORT->Group[1].DIRSET.reg = (uint32_t)(1 << 14);
+	PORT->Group[0].DIRSET.reg = (uint32_t)(1 << 21);
+	PORT->Group[0].OUTSET.reg = (uint32_t)(1 << 21);
+	
+	// pointer to the USB struct in sam_ba_usb.h
+	P_USB_CDC pCdc; 
+	
+	// turn the USB on, sam_ba_usb.h and .c
+	pCdc = usb_init();
+	
+	// a ticker to look for hangouts
+	SysTick_Config(8000000);
+
+    /* Replace with your application code */
+    while (1) 
+    {
+
+		// waits for config to config
+		if(pCdc->IsConfigured(pCdc) != 0){
+			main_b_cdc_enable = true;
+		}
+		
+		// if config is config, and port is opened
+		if(main_b_cdc_enable){
+			sam_ba_monitor_init(SAM_BA_INTERFACE_USBCDC);
+			
+			// loops on this
+			while(1){
+				sam_ba_monitor_run();
+			}
+		}
+		
+		// do_something
+		// monitor_run
+	}
+}
+
+void SysTick_Handler(void){
+	PORT->Group[1].OUTTGL.reg = (uint32_t)(1 << 14);
+	//PORT->Group[0].OUTTGL.reg = (uint32_t)(1 << 21);
+	// monitor_sys_tick
+}
diff --git a/embedded/usb-adafruit-cdc/usb-adafruit-cdc/sam_ba_cdc.c b/embedded/usb-adafruit-cdc/usb-adafruit-cdc/sam_ba_cdc.c
new file mode 100644
index 0000000..3773409
--- /dev/null
+++ b/embedded/usb-adafruit-cdc/usb-adafruit-cdc/sam_ba_cdc.c
@@ -0,0 +1,98 @@
+/*
+  Copyright (c) 2015 Arduino LLC.  All right reserved.
+  Copyright (c) 2015 Atmel Corporation/Thibaut VIARD.  All right reserved.
+
+  This library is free software; you can redistribute it and/or
+  modify it under the terms of the GNU Lesser General Public
+  License as published by the Free Software Foundation; either
+  version 2.1 of the License, or (at your option) any later version.
+
+  This library is distributed in the hope that it will be useful,
+  but WITHOUT ANY WARRANTY; without even the implied warranty of
+  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
+  See the GNU Lesser General Public License for more details.
+
+  You should have received a copy of the GNU Lesser General Public
+  License along with this library; if not, write to the Free Software
+  Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA  02110-1301  USA
+*/
+
+#include "sam_ba_cdc.h"
+#include "board_driver_usb.h"
+
+usb_cdc_line_coding_t line_coding=
+{
+  115200, // baudrate
+  0,      // 1 Stop Bit
+  0,      // None Parity
+  8     // 8 Data bits
+};
+
+#define pCdc (&sam_ba_cdc)
+
+int cdc_putc(/*P_USB_CDC pCdc,*/ int value)
+{
+  /* Send single byte on USB CDC */
+  USB_Write(pCdc->pUsb, (const char *)&value, 1, USB_EP_IN);
+
+  return 1;
+}
+
+int cdc_getc(/*P_USB_CDC pCdc*/void)
+{
+  uint8_t rx_char;
+
+  /* Read singly byte on USB CDC */
+  USB_Read(pCdc->pUsb, (char *)&rx_char, 1);
+
+  return (int)rx_char;
+}
+
+bool cdc_is_rx_ready(/*P_USB_CDC pCdc*/void)
+{
+  /* Check whether the device is configured */
+  if ( !USB_IsConfigured(pCdc) )
+    return 0;
+
+  /* Return transfer complete 0 flag status */
+  return (pCdc->pUsb->DEVICE.DeviceEndpoint[USB_EP_OUT].EPINTFLAG.bit.TRCPT0);
+}
+
+uint32_t cdc_write_buf(/*P_USB_CDC pCdc,*/ void const* data, uint32_t length)
+{
+  /* Send the specified number of bytes on USB CDC */
+  USB_Write(pCdc->pUsb, (const char *)data, length, USB_EP_IN);
+  return length;
+}
+
+uint32_t cdc_read_buf(/*P_USB_CDC pCdc,*/ void* data, uint32_t length)
+{
+  /* Check whether the device is configured */
+  if ( !USB_IsConfigured(pCdc) )
+    return 0;
+
+  /* Read from USB CDC */
+  return USB_Read(pCdc->pUsb, (char *)data, length);
+}
+
+uint32_t cdc_read_buf_xmd(/*P_USB_CDC pCdc,*/ void* data, uint32_t length)
+{
+  /* Check whether the device is configured */
+  if ( !USB_IsConfigured(pCdc) )
+    return 0;
+
+  /* Blocking read till specified number of bytes is received */
+  // XXX: USB_Read_blocking is not reliable
+  // return USB_Read_blocking(pCdc, (char *)data, length);
+
+  char *dst = (char *)data;
+  uint32_t remaining = length;
+  while (remaining)
+  {
+    uint32_t readed = USB_Read(pCdc->pUsb, (char *)dst, remaining);
+    remaining -= readed;
+    dst += readed;
+  }
+
+  return length;
+}
diff --git a/embedded/usb-adafruit-cdc/usb-adafruit-cdc/sam_ba_cdc.h b/embedded/usb-adafruit-cdc/usb-adafruit-cdc/sam_ba_cdc.h
new file mode 100644
index 0000000..49b7643
--- /dev/null
+++ b/embedded/usb-adafruit-cdc/usb-adafruit-cdc/sam_ba_cdc.h
@@ -0,0 +1,91 @@
+/*
+  Copyright (c) 2015 Arduino LLC.  All right reserved.
+  Copyright (c) 2015 Atmel Corporation/Thibaut VIARD.  All right reserved.
+
+  This library is free software; you can redistribute it and/or
+  modify it under the terms of the GNU Lesser General Public
+  License as published by the Free Software Foundation; either
+  version 2.1 of the License, or (at your option) any later version.
+
+  This library is distributed in the hope that it will be useful,
+  but WITHOUT ANY WARRANTY; without even the implied warranty of
+  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
+  See the GNU Lesser General Public License for more details.
+
+  You should have received a copy of the GNU Lesser General Public
+  License along with this library; if not, write to the Free Software
+  Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA  02110-1301  USA
+*/
+
+#ifndef _SAM_BA_USB_CDC_H_
+#define _SAM_BA_USB_CDC_H_
+
+#include <stdint.h>
+#include "sam_ba_usb.h"
+
+typedef struct
+{
+	uint32_t dwDTERate;
+	uint8_t bCharFormat;
+	uint8_t bParityType;
+	uint8_t bDataBits;
+} usb_cdc_line_coding_t;
+
+/* CDC Class Specific Request Code */
+#define GET_LINE_CODING               0x21A1
+#define SET_LINE_CODING               0x2021
+#define SET_CONTROL_LINE_STATE        0x2221
+
+extern usb_cdc_line_coding_t line_coding;
+
+
+/**
+ * \brief Sends a single byte through USB CDC
+ *
+ * \param Data to send
+ * \return number of data sent
+ */
+int cdc_putc(/*P_USB_CDC pCdc,*/ int value);
+
+/**
+ * \brief Reads a single byte through USB CDC
+ *
+ * \return Data read through USB
+ */
+int cdc_getc(/*P_USB_CDC pCdc*/);
+
+/**
+ * \brief Checks if a character has been received on USB CDC
+ *
+ * \return \c 1 if a byte is ready to be read.
+ */
+bool cdc_is_rx_ready(/*P_USB_CDC pCdc*/);
+
+/**
+ * \brief Sends buffer on USB CDC
+ *
+ * \param data pointer
+ * \param number of data to send
+ * \return number of data sent
+ */
+uint32_t cdc_write_buf(/*P_USB_CDC pCdc,*/ void const* data, uint32_t length);
+
+/**
+ * \brief Gets data on USB CDC
+ *
+ * \param data pointer
+ * \param number of data to read
+ * \return number of data read
+ */
+uint32_t cdc_read_buf(/*P_USB_CDC pCdc,*/ void* data, uint32_t length);
+
+/**
+ * \brief Gets specified number of bytes on USB CDC
+ *
+ * \param data pointer
+ * \param number of data to read
+ * \return number of data read
+ */
+uint32_t cdc_read_buf_xmd(/*P_USB_CDC pCdc,*/ void* data, uint32_t length);
+
+#endif // _SAM_BA_USB_CDC_H_
diff --git a/embedded/usb-adafruit-cdc/usb-adafruit-cdc/sam_ba_monitor.c b/embedded/usb-adafruit-cdc/usb-adafruit-cdc/sam_ba_monitor.c
new file mode 100644
index 0000000..61ed768
--- /dev/null
+++ b/embedded/usb-adafruit-cdc/usb-adafruit-cdc/sam_ba_monitor.c
@@ -0,0 +1,554 @@
+/*
+  Copyright (c) 2015 Arduino LLC.  All right reserved.
+  Copyright (c) 2015 Atmel Corporation/Thibaut VIARD.  All right reserved.
+
+  This library is free software; you can redistribute it and/or
+  modify it under the terms of the GNU Lesser General Public
+  License as published by the Free Software Foundation; either
+  version 2.1 of the License, or (at your option) any later version.
+
+  This library is distributed in the hope that it will be useful,
+  but WITHOUT ANY WARRANTY; without even the implied warranty of
+  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
+  See the GNU Lesser General Public License for more details.
+
+  You should have received a copy of the GNU Lesser General Public
+  License along with this library; if not, write to the Free Software
+  Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA  02110-1301  USA
+*/
+
+#include "sam.h"
+#include <string.h>
+#include "sam_ba_monitor.h"
+#include "sam_ba_serial.h"
+#include "board_driver_serial.h"
+#include "board_driver_usb.h"
+#include "sam_ba_usb.h"
+#include "sam_ba_cdc.h"
+//#include "board_driver_led.h"
+
+const char RomBOOT_Version[] = SAM_BA_VERSION;
+const char RomBOOT_ExtendedCapabilities[] = "[Arduino:XYZ]";
+
+/* Provides one common interface to handle both USART and USB-CDC */
+typedef struct
+{
+  /* send one byte of data */
+  int (*put_c)(int value);
+  /* Get one byte */
+  int (*get_c)(void);
+  /* Receive buffer not empty */
+  bool (*is_rx_ready)(void);
+  /* Send given data (polling) */
+  uint32_t (*putdata)(void const* data, uint32_t length);
+  /* Get data from comm. device */
+  uint32_t (*getdata)(void* data, uint32_t length);
+  /* Send given data (polling) using xmodem (if necessary) */
+  uint32_t (*putdata_xmd)(void const* data, uint32_t length);
+  /* Get data from comm. device using xmodem (if necessary) */
+  uint32_t (*getdata_xmd)(void* data, uint32_t length);
+} t_monitor_if;
+
+#if SAM_BA_INTERFACE == SAM_BA_UART_ONLY  ||  SAM_BA_INTERFACE == SAM_BA_BOTH_INTERFACES
+/* Initialize structures with function pointers from supported interfaces */
+const t_monitor_if uart_if =
+{
+  .put_c =       serial_putc,
+  .get_c =       serial_getc,
+  .is_rx_ready = serial_is_rx_ready,
+  .putdata =     serial_putdata,
+  .getdata =     serial_getdata,
+  .putdata_xmd = serial_putdata_xmd,
+  .getdata_xmd = serial_getdata_xmd
+};
+#endif
+
+#if SAM_BA_INTERFACE == SAM_BA_USBCDC_ONLY  ||  SAM_BA_INTERFACE == SAM_BA_BOTH_INTERFACES
+//Please note that USB doesn't use Xmodem protocol, since USB already includes flow control and data verification
+//Data are simply forwarded without further coding.
+const t_monitor_if usbcdc_if =
+{
+  .put_c =         cdc_putc,
+  .get_c =         cdc_getc,
+  .is_rx_ready =   cdc_is_rx_ready,
+  .putdata =       cdc_write_buf,
+  .getdata =       cdc_read_buf,
+  .putdata_xmd =   cdc_write_buf,
+  .getdata_xmd =   cdc_read_buf_xmd
+};
+#endif
+
+/* The pointer to the interface object use by the monitor */
+t_monitor_if * ptr_monitor_if;
+
+/* b_terminal_mode mode (ascii) or hex mode */
+volatile bool b_terminal_mode = false;
+volatile bool b_sam_ba_interface_usart = false;
+
+/* Pulse generation counters to keep track of the time remaining for each pulse type */
+#define TX_RX_LED_PULSE_PERIOD 100
+volatile uint16_t txLEDPulse = 0; // time remaining for Tx LED pulse
+volatile uint16_t rxLEDPulse = 0; // time remaining for Rx LED pulse
+
+void sam_ba_monitor_init(uint8_t com_interface)
+{
+#if SAM_BA_INTERFACE == SAM_BA_UART_ONLY  ||  SAM_BA_INTERFACE == SAM_BA_BOTH_INTERFACES
+  //Selects the requested interface for future actions
+  if (com_interface == SAM_BA_INTERFACE_USART)
+  {
+    ptr_monitor_if = (t_monitor_if*) &uart_if;
+    b_sam_ba_interface_usart = true;
+  }
+#endif
+#if SAM_BA_INTERFACE == SAM_BA_USBCDC_ONLY  ||  SAM_BA_INTERFACE == SAM_BA_BOTH_INTERFACES
+  if (com_interface == SAM_BA_INTERFACE_USBCDC)
+  {
+    ptr_monitor_if = (t_monitor_if*) &usbcdc_if;
+  }
+#endif
+}
+
+/*
+ * Central SAM-BA monitor putdata function using the board LEDs
+ */
+static uint32_t sam_ba_putdata(t_monitor_if* pInterface, void const* data, uint32_t length)
+{
+	uint32_t result ;
+
+	result=pInterface->putdata(data, length);
+
+	//LEDTX_on();
+	//txLEDPulse = TX_RX_LED_PULSE_PERIOD;
+
+	return result;
+}
+
+/*
+ * Central SAM-BA monitor getdata function using the board LEDs
+ */
+static uint32_t sam_ba_getdata(t_monitor_if* pInterface, void* data, uint32_t length)
+{
+	uint32_t result ;
+
+	result=pInterface->getdata(data, length);
+
+	if (result)
+	{
+		//LEDRX_on();
+		//rxLEDPulse = TX_RX_LED_PULSE_PERIOD;
+	}
+
+	return result;
+}
+
+/*
+ * Central SAM-BA monitor putdata function using the board LEDs
+ */
+static uint32_t sam_ba_putdata_xmd(t_monitor_if* pInterface, void const* data, uint32_t length)
+{
+	uint32_t result ;
+
+	result=pInterface->putdata_xmd(data, length);
+
+	//LEDTX_on();
+	//txLEDPulse = TX_RX_LED_PULSE_PERIOD;
+
+	return result;
+}
+
+/*
+ * Central SAM-BA monitor getdata function using the board LEDs
+ */
+static uint32_t sam_ba_getdata_xmd(t_monitor_if* pInterface, void* data, uint32_t length)
+{
+	uint32_t result ;
+
+	result=pInterface->getdata_xmd(data, length);
+
+	if (result)
+	{
+		//LEDRX_on();
+		//rxLEDPulse = TX_RX_LED_PULSE_PERIOD;
+	}
+
+	return result;
+}
+
+/**
+ * \brief This function allows data emission by USART
+ *
+ * \param *data  Data pointer
+ * \param length Length of the data
+ */
+void sam_ba_putdata_term(uint8_t* data, uint32_t length)
+{
+  uint8_t temp, buf[12], *data_ascii;
+  uint32_t i, int_value;
+
+  if (b_terminal_mode)
+  {
+    if (length == 4)
+      int_value = *(uint32_t *) data;
+    else if (length == 2)
+      int_value = *(uint16_t *) data;
+    else
+      int_value = *(uint8_t *) data;
+
+    data_ascii = buf + 2;
+    data_ascii += length * 2 - 1;
+
+    for (i = 0; i < length * 2; i++)
+    {
+      temp = (uint8_t) (int_value & 0xf);
+
+      if (temp <= 0x9)
+        *data_ascii = temp | 0x30;
+      else
+        *data_ascii = temp + 0x37;
+
+      int_value >>= 4;
+      data_ascii--;
+    }
+    buf[0] = '0';
+    buf[1] = 'x';
+    buf[length * 2 + 2] = '\n';
+    buf[length * 2 + 3] = '\r';
+    sam_ba_putdata(ptr_monitor_if, buf, length * 2 + 4);
+  }
+  else
+    sam_ba_putdata(ptr_monitor_if, data, length);
+  return;
+}
+
+volatile uint32_t sp;
+void call_applet(uint32_t address)
+{
+  uint32_t app_start_address;
+
+  __disable_irq();
+
+  sp = __get_MSP();
+
+  /* Rebase the Stack Pointer */
+  __set_MSP(*(uint32_t *) address);
+
+  /* Load the Reset Handler address of the application */
+  app_start_address = *(uint32_t *)(address + 4);
+
+  /* Jump to application Reset Handler in the application */
+  asm("bx %0"::"r"(app_start_address));
+}
+
+uint32_t current_number;
+uint32_t i, length;
+uint8_t command, *ptr_data, *ptr, data[SIZEBUFMAX];
+uint8_t j;
+uint32_t u32tmp;
+
+uint32_t PAGE_SIZE, PAGES, MAX_FLASH;
+
+// Prints a 32-bit integer in hex.
+static void put_uint32(uint32_t n)
+{
+  char buff[8];
+  int i;
+  for (i=0; i<8; i++)
+  {
+    int d = n & 0XF;
+    n = (n >> 4);
+
+    buff[7-i] = d > 9 ? 'A' + d - 10 : '0' + d;
+  }
+  sam_ba_putdata( ptr_monitor_if, buff, 8);
+}
+
+static void sam_ba_monitor_loop(void)
+{
+  length = sam_ba_getdata(ptr_monitor_if, data, SIZEBUFMAX);
+  ptr = data;
+
+  for (i = 0; i < length; i++, ptr++)
+  {
+    if (*ptr == 0xff) continue;
+
+    if (*ptr == '#')
+    {
+      if (b_terminal_mode)
+      {
+        sam_ba_putdata(ptr_monitor_if, "\n\r", 2);
+      }
+      if (command == 'S')
+      {
+        //Check if some data are remaining in the "data" buffer
+        if(length>i)
+        {
+          //Move current indexes to next avail data (currently ptr points to "#")
+          ptr++;
+          i++;
+
+          //We need to add first the remaining data of the current buffer already read from usb
+          //read a maximum of "current_number" bytes
+          if ((length-i) < current_number)
+          {
+            u32tmp=(length-i);
+          }
+          else
+          {
+            u32tmp=current_number;
+          }
+
+          memcpy(ptr_data, ptr, u32tmp);
+          i += u32tmp;
+          ptr += u32tmp;
+          j = u32tmp;
+        }
+        //update i with the data read from the buffer
+        i--;
+        ptr--;
+        //Do we expect more data ?
+        if(j<current_number)
+          sam_ba_getdata_xmd(ptr_monitor_if, ptr_data, current_number-j);
+
+        __asm("nop");
+      }
+      else if (command == 'R')
+      {
+        sam_ba_putdata_xmd(ptr_monitor_if, ptr_data, current_number);
+      }
+      else if (command == 'O')
+      {
+        *ptr_data = (char) current_number;
+      }
+      else if (command == 'H')
+      {
+        *((uint16_t *) ptr_data) = (uint16_t) current_number;
+      }
+      else if (command == 'W')
+      {
+        *((int *) ptr_data) = current_number;
+      }
+      else if (command == 'o')
+      {
+        sam_ba_putdata_term(ptr_data, 1);
+      }
+      else if (command == 'h')
+      {
+        current_number = *((uint16_t *) ptr_data);
+        sam_ba_putdata_term((uint8_t*) &current_number, 2);
+      }
+      else if (command == 'w')
+      {
+        current_number = *((uint32_t *) ptr_data);
+        sam_ba_putdata_term((uint8_t*) &current_number, 4);
+      }
+      else if (command == 'G')
+      {
+        call_applet(current_number);
+        /* Rebase the Stack Pointer */
+        __set_MSP(sp);
+        __enable_irq();
+        if (b_sam_ba_interface_usart) {
+          ptr_monitor_if->put_c(0x6);
+        }
+      }
+      else if (command == 'T')
+      {
+        b_terminal_mode = 1;
+        sam_ba_putdata(ptr_monitor_if, "\n\r", 2);
+      }
+      else if (command == 'N')
+      {
+        if (b_terminal_mode == 0)
+        {
+          sam_ba_putdata( ptr_monitor_if, "\n\r", 2);
+        }
+        b_terminal_mode = 0;
+      }
+      else if (command == 'V')
+      {
+        sam_ba_putdata( ptr_monitor_if, "v", 1);
+        sam_ba_putdata( ptr_monitor_if, (uint8_t *) RomBOOT_Version, strlen(RomBOOT_Version));
+        sam_ba_putdata( ptr_monitor_if, " ", 1);
+        sam_ba_putdata( ptr_monitor_if, (uint8_t *) RomBOOT_ExtendedCapabilities, strlen(RomBOOT_ExtendedCapabilities));
+        sam_ba_putdata( ptr_monitor_if, " ", 1);
+        ptr = (uint8_t*) &(__DATE__);
+        i = 0;
+        while (*ptr++ != '\0')
+          i++;
+        sam_ba_putdata( ptr_monitor_if, (uint8_t *) &(__DATE__), i);
+        sam_ba_putdata( ptr_monitor_if, " ", 1);
+        i = 0;
+        ptr = (uint8_t*) &(__TIME__);
+        while (*ptr++ != '\0')
+          i++;
+        sam_ba_putdata( ptr_monitor_if, (uint8_t *) &(__TIME__), i);
+        sam_ba_putdata( ptr_monitor_if, "\n\r", 2);
+      }
+      else if (command == 'X')
+      {
+        // Syntax: X[ADDR]#
+        // Erase the flash memory starting from ADDR to the end of flash.
+		
+		//block size 16 pages
+
+        uint32_t dst_addr = current_number; // starting address
+
+        while (dst_addr < MAX_FLASH)
+        {
+		  while (NVMCTRL->STATUS.bit.READY == 0);
+          // Execute "EB" Erase Block
+		  NVMCTRL->ADDR.reg = dst_addr;
+          NVMCTRL->CTRLB.reg = NVMCTRL_CTRLB_CMDEX_KEY | NVMCTRL_CTRLB_CMD_EB;
+		  while (NVMCTRL->STATUS.bit.READY == 0);
+		  
+          dst_addr += PAGE_SIZE * 16; // Skip a block
+        }
+
+        // Notify command completed
+        sam_ba_putdata( ptr_monitor_if, "X\n\r", 3);
+      }
+      else if (command == 'Y')
+      {
+        // This command writes the content of a buffer in SRAM into flash memory.
+
+        // Syntax: Y[ADDR],0#
+        // Set the starting address of the SRAM buffer.
+
+        // Syntax: Y[ROM_ADDR],[SIZE]#
+        // Write the first SIZE bytes from the SRAM buffer (previously set) into
+        // flash memory starting from address ROM_ADDR
+
+        static uint32_t *src_buff_addr = NULL;
+
+        if (current_number == 0)
+        {
+          // Set buffer address
+          src_buff_addr = (uint32_t*)ptr_data;
+        }
+        else
+        {
+          // Write to flash
+          uint32_t size = current_number/4;
+          uint32_t *src_addr = src_buff_addr;
+          uint32_t *dst_addr = (uint32_t*)ptr_data;
+
+          // Set automatic page write
+		  NVMCTRL->CTRLA.reg |= NVMCTRL_CTRLA_WMODE(NVMCTRL_CTRLA_WMODE_AP);
+
+          // Do writes in pages
+          while (size)
+          {
+            // Execute "PBC" Page Buffer Clear
+			NVMCTRL->CTRLB.reg = NVMCTRL_CTRLB_CMDEX_KEY | NVMCTRL_CTRLB_CMD_PBC;
+			while (NVMCTRL->STATUS.bit.READY == 0)
+              ;
+
+            // Fill page buffer
+            uint32_t i;
+            for (i=0; i<(PAGE_SIZE/4) && i<size; i++)
+            {
+              dst_addr[i] = src_addr[i];
+            }
+
+            // Execute "WP" Write Page
+			NVMCTRL->ADDR.reg = ((uint32_t)dst_addr);
+			NVMCTRL->CTRLB.reg = NVMCTRL_CTRLB_CMDEX_KEY | NVMCTRL_CTRLB_CMD_WP;
+			while (NVMCTRL->STATUS.bit.READY == 0)
+              ;
+
+            // Advance to next page
+            dst_addr += i;
+            src_addr += i;
+            size     -= i;
+          }
+        }
+
+        // Notify command completed
+        sam_ba_putdata( ptr_monitor_if, "Y\n\r", 3);
+      }
+      else if (command == 'Z')
+      {
+        // This command calculate CRC for a given area of memory.
+        // It's useful to quickly check if a transfer has been done
+        // successfully.
+
+        // Syntax: Z[START_ADDR],[SIZE]#
+        // Returns: Z[CRC]#
+
+        uint8_t *data = (uint8_t *)ptr_data;
+        uint32_t size = current_number;
+        uint16_t crc = 0;
+        uint32_t i = 0;
+        for (i=0; i<size; i++)
+          crc = serial_add_crc(*data++, crc);
+
+        // Send response
+        sam_ba_putdata( ptr_monitor_if, "Z", 1);
+        put_uint32(crc);
+        sam_ba_putdata( ptr_monitor_if, "#\n\r", 3);
+      }
+
+      command = 'z';
+      current_number = 0;
+
+      if (b_terminal_mode)
+      {
+        sam_ba_putdata( ptr_monitor_if, ">", 1);
+      }
+    }
+    else
+    {
+      if (('0' <= *ptr) && (*ptr <= '9'))
+      {
+        current_number = (current_number << 4) | (*ptr - '0');
+      }
+      else if (('A' <= *ptr) && (*ptr <= 'F'))
+      {
+        current_number = (current_number << 4) | (*ptr - 'A' + 0xa);
+      }
+      else if (('a' <= *ptr) && (*ptr <= 'f'))
+      {
+        current_number = (current_number << 4) | (*ptr - 'a' + 0xa);
+      }
+      else if (*ptr == ',')
+      {
+        ptr_data = (uint8_t *) current_number;
+        current_number = 0;
+      }
+      else
+      {
+        command = *ptr;
+        current_number = 0;
+      }
+    }
+  }
+}
+
+void sam_ba_monitor_sys_tick(void)
+{
+	/* Check whether the TX or RX LED one-shot period has elapsed.  if so, turn off the LED */
+	/*
+	if (txLEDPulse && !(--txLEDPulse))
+		LEDTX_off();
+	if (rxLEDPulse && !(--rxLEDPulse))
+		LEDRX_off();
+	*/
+}
+
+/**
+ * \brief This function starts the SAM-BA monitor.
+ */
+void sam_ba_monitor_run(void)
+{
+  uint32_t pageSizes[] = { 8, 16, 32, 64, 128, 256, 512, 1024 };
+  PAGE_SIZE = pageSizes[NVMCTRL->PARAM.bit.PSZ];
+  PAGES = NVMCTRL->PARAM.bit.NVMP;
+  MAX_FLASH = PAGE_SIZE * PAGES;
+
+  ptr_data = NULL;
+  command = 'z';
+  while (1)
+  {
+    sam_ba_monitor_loop();
+  }
+}
diff --git a/embedded/usb-adafruit-cdc/usb-adafruit-cdc/sam_ba_monitor.h b/embedded/usb-adafruit-cdc/usb-adafruit-cdc/sam_ba_monitor.h
new file mode 100644
index 0000000..6cfa4db
--- /dev/null
+++ b/embedded/usb-adafruit-cdc/usb-adafruit-cdc/sam_ba_monitor.h
@@ -0,0 +1,72 @@
+/*
+  Copyright (c) 2015 Arduino LLC.  All right reserved.
+  Copyright (c) 2015 Atmel Corporation/Thibaut VIARD.  All right reserved.
+
+  This library is free software; you can redistribute it and/or
+  modify it under the terms of the GNU Lesser General Public
+  License as published by the Free Software Foundation; either
+  version 2.1 of the License, or (at your option) any later version.
+
+  This library is distributed in the hope that it will be useful,
+  but WITHOUT ANY WARRANTY; without even the implied warranty of
+  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
+  See the GNU Lesser General Public License for more details.
+
+  You should have received a copy of the GNU Lesser General Public
+  License along with this library; if not, write to the Free Software
+  Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA  02110-1301  USA
+*/
+
+#ifndef _MONITOR_SAM_BA_H_
+#define _MONITOR_SAM_BA_H_
+
+#define SAM_BA_VERSION              "2.0"
+
+/* Enable the interfaces to save code size */
+#define SAM_BA_BOTH_INTERFACES      0
+#define SAM_BA_UART_ONLY            1
+#define SAM_BA_USBCDC_ONLY          2
+
+#ifndef SAM_BA_INTERFACE
+#define SAM_BA_INTERFACE    SAM_BA_BOTH_INTERFACES
+#endif
+
+/* Selects USB as the communication interface of the monitor */
+#define SAM_BA_INTERFACE_USBCDC     0
+/* Selects USART as the communication interface of the monitor */
+#define SAM_BA_INTERFACE_USART      1
+
+/* Selects USB as the communication interface of the monitor */
+#define SIZEBUFMAX                  64
+
+/**
+ * \brief Initialize the monitor
+ *
+ */
+void sam_ba_monitor_init(uint8_t com_interface);
+
+/**
+ * \brief System tick function of the SAM-BA Monitor
+ *
+ */
+void sam_ba_monitor_sys_tick(void);
+
+/**
+ * \brief Main function of the SAM-BA Monitor
+ *
+ */
+void sam_ba_monitor_run(void);
+
+/**
+ * \brief
+ *
+ */
+void sam_ba_putdata_term(uint8_t* data, uint32_t length);
+
+/**
+ * \brief
+ *
+ */
+void call_applet(uint32_t address);
+
+#endif // _MONITOR_SAM_BA_H_
diff --git a/embedded/usb-adafruit-cdc/usb-adafruit-cdc/sam_ba_serial.c b/embedded/usb-adafruit-cdc/usb-adafruit-cdc/sam_ba_serial.c
new file mode 100644
index 0000000..6b02b28
--- /dev/null
+++ b/embedded/usb-adafruit-cdc/usb-adafruit-cdc/sam_ba_serial.c
@@ -0,0 +1,529 @@
+/*
+  Copyright (c) 2015 Arduino LLC.  All right reserved.
+  Copyright (c) 2015 Atmel Corporation/Thibaut VIARD.  All right reserved.
+
+  This library is free software; you can redistribute it and/or
+  modify it under the terms of the GNU Lesser General Public
+  License as published by the Free Software Foundation; either
+  version 2.1 of the License, or (at your option) any later version.
+
+  This library is distributed in the hope that it will be useful,
+  but WITHOUT ANY WARRANTY; without even the implied warranty of
+  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
+  See the GNU Lesser General Public License for more details.
+
+  You should have received a copy of the GNU Lesser General Public
+  License along with this library; if not, write to the Free Software
+  Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA  02110-1301  USA
+*/
+
+#include <sam.h>
+#include "board_definitions.h"
+#include "sam_ba_serial.h"
+#include "board_driver_serial.h"
+
+/* Local reference to current Usart instance in use with this driver */
+//struct usart_module usart_sam_ba;
+
+/* Variable to let the main task select the appropriate communication interface */
+volatile uint8_t b_sharp_received;
+
+/* RX and TX Buffers + rw pointers for each buffer */
+volatile uint8_t buffer_rx_usart[USART_BUFFER_SIZE];
+
+volatile uint8_t idx_rx_read;
+volatile uint8_t idx_rx_write;
+
+volatile uint8_t buffer_tx_usart[USART_BUFFER_SIZE];
+
+volatile uint8_t idx_tx_read;
+volatile uint8_t idx_tx_write;
+
+/* Test for timeout in AT91F_GetChar */
+uint8_t error_timeout;
+uint16_t size_of_data;
+uint8_t mode_of_transfer;
+
+#define BOOT_USART_PAD(n) BOOT_USART_PAD##n
+
+#define GPIO_PIN(n) (((n)&0x1Fu) << 0)
+#define GPIO_PORT(n) ((n) >> 5)
+
+/**
+ * \brief Open the given USART
+ */
+void serial_open(void)
+{
+	uint32_t port;
+	uint32_t pin;
+	  
+	GCLK->PCHCTRL[BOOT_GCLK_ID_CORE].reg = GCLK_PCHCTRL_GEN_GCLK0_Val | (1 << GCLK_PCHCTRL_CHEN_Pos);
+	GCLK->PCHCTRL[BOOT_GCLK_ID_SLOW].reg = GCLK_PCHCTRL_GEN_GCLK3_Val | (1 << GCLK_PCHCTRL_CHEN_Pos);
+	
+	MCLK->BOOK_USART_MASK.reg |= BOOT_USART_BUS_CLOCK_INDEX ;
+	
+	/* Configure the port pins for SERCOM_USART */
+	if (BOOT_USART_PAD0 != PINMUX_UNUSED)
+  {
+		/* Mask 6th bit in pin number to check whether it is greater than 32 i.e., PORTB pin */
+		port = (BOOT_USART_PAD0 & 0x200000) >> 21;
+		pin = (BOOT_USART_PAD0 >> 16);
+		PORT->Group[port].PINCFG[(pin - (port*32))].bit.PMUXEN = 1;
+		PORT->Group[port].PMUX[(pin - (port*32))/2].reg &= ~(0xF << (4 * (pin & 0x01u)));
+		PORT->Group[port].PMUX[(pin - (port*32))/2].reg |= (BOOT_USART_PAD0 & 0xFF) << (4 * (pin & 0x01u));
+	}
+
+	if (BOOT_USART_PAD1 != PINMUX_UNUSED)
+  {
+		/* Mask 6th bit in pin number to check whether it is greater than 32 i.e., PORTB pin */
+		port = (BOOT_USART_PAD1 & 0x200000) >> 21;
+		pin = BOOT_USART_PAD1 >> 16;
+		PORT->Group[port].PINCFG[(pin - (port*32))].bit.PMUXEN = 1;
+		PORT->Group[port].PMUX[(pin - (port*32))/2].reg &= ~(0xF << (4 * (pin & 0x01u)));
+		PORT->Group[port].PMUX[(pin - (port*32))/2].reg |= (BOOT_USART_PAD1 & 0xFF) << (4 * (pin & 0x01u));
+	}
+
+	if (BOOT_USART_PAD2 != PINMUX_UNUSED)
+  {
+		/* Mask 6th bit in pin number to check whether it is greater than 32 i.e., PORTB pin */
+		port = (BOOT_USART_PAD2 & 0x200000) >> 21;
+		pin = BOOT_USART_PAD2 >> 16;
+		PORT->Group[port].PINCFG[(pin - (port*32))].bit.PMUXEN = 1;
+		PORT->Group[port].PMUX[(pin - (port*32))/2].reg &= ~(0xF << (4 * (pin & 0x01u)));
+		PORT->Group[port].PMUX[(pin - (port*32))/2].reg |= (BOOT_USART_PAD2 & 0xFF) << (4 * (pin & 0x01u));
+	}
+
+	if (BOOT_USART_PAD3 != PINMUX_UNUSED)
+  {
+		/* Mask 6th bit in pin number to check whether it is greater than 32 i.e., PORTB pin */
+		port = (BOOT_USART_PAD3 & 0x200000) >> 21;
+		pin = BOOT_USART_PAD3 >> 16;
+		PORT->Group[port].PINCFG[(pin - (port*32))].bit.PMUXEN = 1;
+		PORT->Group[port].PMUX[(pin - (port*32))/2].reg &= ~(0xF << (4 * (pin & 0x01u)));
+		PORT->Group[port].PMUX[(pin - (port*32))/2].reg |= (BOOT_USART_PAD3 & 0xFF) << (4 * (pin & 0x01u));
+	}
+
+	/* Baud rate 115200 - clock 48MHz -> BAUD value-63018 */
+	uart_basic_init(BOOT_USART_MODULE, 63018, BOOT_USART_PAD_SETTINGS);
+
+	//Initialize flag
+	b_sharp_received = false;
+	idx_rx_read = 0;
+	idx_rx_write = 0;
+	idx_tx_read = 0;
+	idx_tx_write = 0;
+
+	error_timeout = 0;
+}
+
+/**
+ * \brief Close communication line
+ */
+void serial_close(void)
+{
+	uart_disable(BOOT_USART_MODULE);
+}
+
+/**
+ * \brief Puts a byte on usart line
+ * The type int is used to support printf redirection from compiler LIB.
+ *
+ * \param value      Value to put
+ *
+ * \return \c 1 if function was successfully done, otherwise \c 0.
+ */
+int serial_putc(int value)
+{	
+	uart_write_byte(BOOT_USART_MODULE, (uint8_t)value);
+	return 1;
+}
+
+int serial_getc(void)
+{
+	uint16_t retval;
+	//Wait until input buffer is filled
+	while(!(serial_is_rx_ready()));
+	retval = (uint16_t)uart_read_byte(BOOT_USART_MODULE);
+	//usart_read_wait(&usart_sam_ba, &retval);
+	return (int)retval;
+
+}
+
+int serial_sharp_received(void)
+{
+	if (serial_is_rx_ready())
+  {
+		if (serial_getc() == SHARP_CHARACTER)
+			return (true);
+	}
+	return (false);
+}
+
+bool serial_is_rx_ready(void)
+{
+	return (BOOT_USART_MODULE->USART.INTFLAG.reg & SERCOM_USART_INTFLAG_RXC);
+}
+
+int serial_readc(void)
+{
+	int retval;
+	retval = buffer_rx_usart[idx_rx_read];
+	idx_rx_read = (idx_rx_read + 1) & (USART_BUFFER_SIZE - 1);
+	return (retval);
+}
+
+//Send given data (polling)
+uint32_t serial_putdata(void const* data, uint32_t length)
+{
+	uint32_t i;
+	uint8_t* ptrdata;
+	ptrdata = (uint8_t*) data;
+	for (i = 0; i < length; i++)
+  {
+		serial_putc(*ptrdata);
+		ptrdata++;
+	}
+	return (i);
+}
+
+//Get data from comm. device
+uint32_t serial_getdata(void* data, uint32_t length)
+{
+	uint8_t* ptrdata;
+	ptrdata = (uint8_t*) data;
+	*ptrdata = serial_getc();
+	return (1);
+}
+
+static const uint16_t crc16Table[256]=
+{
+	0x0000,0x1021,0x2042,0x3063,0x4084,0x50a5,0x60c6,0x70e7,
+	0x8108,0x9129,0xa14a,0xb16b,0xc18c,0xd1ad,0xe1ce,0xf1ef,
+	0x1231,0x0210,0x3273,0x2252,0x52b5,0x4294,0x72f7,0x62d6,
+	0x9339,0x8318,0xb37b,0xa35a,0xd3bd,0xc39c,0xf3ff,0xe3de,
+	0x2462,0x3443,0x0420,0x1401,0x64e6,0x74c7,0x44a4,0x5485,
+	0xa56a,0xb54b,0x8528,0x9509,0xe5ee,0xf5cf,0xc5ac,0xd58d,
+	0x3653,0x2672,0x1611,0x0630,0x76d7,0x66f6,0x5695,0x46b4,
+	0xb75b,0xa77a,0x9719,0x8738,0xf7df,0xe7fe,0xd79d,0xc7bc,
+	0x48c4,0x58e5,0x6886,0x78a7,0x0840,0x1861,0x2802,0x3823,
+	0xc9cc,0xd9ed,0xe98e,0xf9af,0x8948,0x9969,0xa90a,0xb92b,
+	0x5af5,0x4ad4,0x7ab7,0x6a96,0x1a71,0x0a50,0x3a33,0x2a12,
+	0xdbfd,0xcbdc,0xfbbf,0xeb9e,0x9b79,0x8b58,0xbb3b,0xab1a,
+	0x6ca6,0x7c87,0x4ce4,0x5cc5,0x2c22,0x3c03,0x0c60,0x1c41,
+	0xedae,0xfd8f,0xcdec,0xddcd,0xad2a,0xbd0b,0x8d68,0x9d49,
+	0x7e97,0x6eb6,0x5ed5,0x4ef4,0x3e13,0x2e32,0x1e51,0x0e70,
+	0xff9f,0xefbe,0xdfdd,0xcffc,0xbf1b,0xaf3a,0x9f59,0x8f78,
+	0x9188,0x81a9,0xb1ca,0xa1eb,0xd10c,0xc12d,0xf14e,0xe16f,
+	0x1080,0x00a1,0x30c2,0x20e3,0x5004,0x4025,0x7046,0x6067,
+	0x83b9,0x9398,0xa3fb,0xb3da,0xc33d,0xd31c,0xe37f,0xf35e,
+	0x02b1,0x1290,0x22f3,0x32d2,0x4235,0x5214,0x6277,0x7256,
+	0xb5ea,0xa5cb,0x95a8,0x8589,0xf56e,0xe54f,0xd52c,0xc50d,
+	0x34e2,0x24c3,0x14a0,0x0481,0x7466,0x6447,0x5424,0x4405,
+	0xa7db,0xb7fa,0x8799,0x97b8,0xe75f,0xf77e,0xc71d,0xd73c,
+	0x26d3,0x36f2,0x0691,0x16b0,0x6657,0x7676,0x4615,0x5634,
+	0xd94c,0xc96d,0xf90e,0xe92f,0x99c8,0x89e9,0xb98a,0xa9ab,
+	0x5844,0x4865,0x7806,0x6827,0x18c0,0x08e1,0x3882,0x28a3,
+	0xcb7d,0xdb5c,0xeb3f,0xfb1e,0x8bf9,0x9bd8,0xabbb,0xbb9a,
+	0x4a75,0x5a54,0x6a37,0x7a16,0x0af1,0x1ad0,0x2ab3,0x3a92,
+	0xfd2e,0xed0f,0xdd6c,0xcd4d,0xbdaa,0xad8b,0x9de8,0x8dc9,
+	0x7c26,0x6c07,0x5c64,0x4c45,0x3ca2,0x2c83,0x1ce0,0x0cc1,
+	0xef1f,0xff3e,0xcf5d,0xdf7c,0xaf9b,0xbfba,0x8fd9,0x9ff8,
+	0x6e17,0x7e36,0x4e55,0x5e74,0x2e93,0x3eb2,0x0ed1,0x1ef0
+};
+
+//*----------------------------------------------------------------------------
+//* \brief Compute the CRC
+//*----------------------------------------------------------------------------
+unsigned short serial_add_crc(char ptr, unsigned short crc)
+{
+	return (crc << 8) ^ crc16Table[((crc >> 8) ^ ptr) & 0xff];
+}
+
+//*----------------------------------------------------------------------------
+//* \brief
+//*----------------------------------------------------------------------------
+static uint16_t getbytes(uint8_t *ptr_data, uint16_t length)
+{
+	uint16_t crc = 0;
+	uint16_t cpt;
+	uint8_t c;
+
+	for (cpt = 0; cpt < length; ++cpt)
+  {
+		c = serial_getc();
+		if (error_timeout)
+			return 1;
+		crc = serial_add_crc(c, crc);
+		//crc = (crc << 8) ^ xcrc16tab[(crc>>8) ^ c];
+		if (size_of_data || mode_of_transfer)
+    {
+			*ptr_data++ = c;
+			if (length == PKTLEN_128)
+				size_of_data--;
+		}
+	}
+
+	return crc;
+}
+
+//*----------------------------------------------------------------------------
+//* \brief Used by Xup to send packets.
+//*----------------------------------------------------------------------------
+static int putPacket(uint8_t *tmppkt, uint8_t sno)
+{
+	uint32_t i;
+	uint16_t chksm;
+	uint8_t data;
+
+	chksm = 0;
+
+	serial_putc(SOH);
+
+	serial_putc(sno);
+	serial_putc((uint8_t) ~(sno));
+
+	for (i = 0; i < PKTLEN_128; i++)
+  {
+		if (size_of_data || mode_of_transfer)
+    {
+			data = *tmppkt++;
+			size_of_data--;
+		}
+    else
+			data = 0x00;
+
+		serial_putc(data);
+
+		//chksm = (chksm<<8) ^ xcrc16tab[(chksm>>8)^data];
+		chksm = serial_add_crc(data, chksm);
+	}
+
+	/* An "endian independent way to extract the CRC bytes. */
+	serial_putc((uint8_t) (chksm >> 8));
+	serial_putc((uint8_t) chksm);
+
+	return (serial_getc()); /* Wait for ack */
+}
+
+//*----------------------------------------------------------------------------
+//* \brief Called when a transfer from target to host is being made (considered
+//*        an upload).
+//*----------------------------------------------------------------------------
+//Send given data (polling) using xmodem (if necessary)
+uint32_t serial_putdata_xmd(void const* data, uint32_t length)
+{
+	uint8_t c, sno = 1;
+	uint8_t done;
+	uint8_t * ptr_data = (uint8_t *) data;
+	error_timeout = 0;
+	if (!length)
+		mode_of_transfer = 1;
+	else
+  {
+		size_of_data = length;
+		mode_of_transfer = 0;
+	}
+
+	if (length & (PKTLEN_128 - 1))
+  {
+		length += PKTLEN_128;
+		length &= ~(PKTLEN_128 - 1);
+	}
+
+	/* Startup synchronization... */
+	/* Wait to receive a NAK or 'C' from receiver. */
+	done = 0;
+	while (!done) {
+		c = (uint8_t) serial_getc();
+		if (error_timeout)
+    { // Test for timeout in serial_getc
+			error_timeout = 0;
+			c = (uint8_t) serial_getc();
+			if (error_timeout)
+      {
+				error_timeout = 0;
+				return (0);
+			}
+		}
+		switch (c)
+    {
+      case NAK:
+        done = 1;
+        // ("CSM");
+			break;
+      case 'C':
+        done = 1;
+        // ("CRC");
+			break;
+      case 'q': /* ELS addition, not part of XMODEM spec. */
+        return (0);
+      default:
+			break;
+		}
+	}
+
+	done = 0;
+	sno = 1;
+	while (!done)
+  {
+		c = (uint8_t) putPacket((uint8_t *) ptr_data, sno);
+		if (error_timeout)
+    { // Test for timeout in serial_getc
+			error_timeout = 0;
+			return (0);
+		}
+		switch (c)
+    {
+      case ACK:
+        ++sno;
+        length -= PKTLEN_128;
+        ptr_data += PKTLEN_128;
+        // ("A");
+			break;
+
+      case NAK:
+        // ("N");
+			break;
+
+      case CAN:
+      case EOT:
+      default:
+        done = 0;
+			break;
+		}
+
+		if (!length)
+    {
+			serial_putc(EOT);
+			serial_getc(); /* Flush the ACK */
+			break;
+		}
+		// ("!");
+	}
+
+	mode_of_transfer = 0;
+	// ("Xup_done.");
+	return (1);
+	//    return(0);
+}
+
+/*----------------------------------------------------------------------------
+ * \brief Used by serial_getdata_xmd to retrieve packets.
+ */
+static uint8_t getPacket(uint8_t *ptr_data, uint8_t sno)
+{
+	uint8_t seq[2];
+	uint16_t crc, xcrc;
+
+	getbytes(seq, 2);
+	xcrc = getbytes(ptr_data, PKTLEN_128);
+	if (error_timeout)
+		return (false);
+
+	/* An "endian independent way to combine the CRC bytes. */
+	crc = (uint16_t) serial_getc() << 8;
+	crc += (uint16_t) serial_getc();
+
+	if (error_timeout == 1)
+		return (false);
+
+	if ((crc != xcrc) || (seq[0] != sno) || (seq[1] != (uint8_t) (~sno)))
+  {
+		serial_putc(CAN);
+		return (false);
+	}
+
+	serial_putc(ACK);
+	return (true);
+}
+
+//*----------------------------------------------------------------------------
+//* \brief Called when a transfer from host to target is being made (considered
+//*        an download).
+//*----------------------------------------------------------------------------
+//Get data from comm. device using xmodem (if necessary)
+uint32_t serial_getdata_xmd(void* data, uint32_t length)
+{
+	uint32_t timeout;
+	char c;
+	uint8_t * ptr_data = (uint8_t *) data;
+	uint32_t b_run, nbr_of_timeout = 100;
+	uint8_t sno = 0x01;
+	uint32_t data_transfered = 0;
+
+	//Copied from legacy source code ... might need some tweaking
+	uint32_t loops_per_second = CPU_FREQUENCY/60;
+
+	error_timeout = 0;
+
+	if (length == 0)
+		mode_of_transfer = 1;
+	else
+  {
+		size_of_data = length;
+		mode_of_transfer = 0;
+	}
+
+	/* Startup synchronization... */
+	/* Continuously send NAK or 'C' until sender responds. */
+	// ("Xdown");
+	while (1)
+  {
+		serial_putc('C');
+		timeout = loops_per_second;
+		while (!(serial_is_rx_ready()) && timeout)
+			timeout--;
+		if (timeout)
+			break;
+
+		if (!(--nbr_of_timeout))
+			return (0);
+//            return -1;
+	}
+
+	b_run = true;
+	// ("Got response");
+	while (b_run != false)
+  {
+		c = (char) serial_getc();
+		if (error_timeout)
+    { // Test for timeout in serial_getc
+			error_timeout = 0;
+			return (0);
+//            return (-1);
+		}
+		switch (c)
+    {
+      case SOH: /* 128-byte incoming packet */
+        // ("O");
+        b_run = getPacket(ptr_data, sno);
+        if (error_timeout)
+        { // Test for timeout in serial_getc
+          error_timeout = 0;
+          return (0);
+  //                return (-1);
+        }
+        if (b_run == true)
+        {
+          ++sno;
+          ptr_data += PKTLEN_128;
+          data_transfered += PKTLEN_128;
+        }
+			break;
+      case EOT: // ("E");
+        serial_putc(ACK);
+        b_run = false;
+			break;
+      case CAN: // ("C");
+      case ESC: /* "X" User-invoked abort */
+      default:
+        b_run = false;
+			break;
+		}
+		// ("!");
+	}
+	mode_of_transfer = 0;
+	return (true);
+//    return(b_run);
+}
+
diff --git a/embedded/usb-adafruit-cdc/usb-adafruit-cdc/sam_ba_serial.h b/embedded/usb-adafruit-cdc/usb-adafruit-cdc/sam_ba_serial.h
new file mode 100644
index 0000000..cb69f45
--- /dev/null
+++ b/embedded/usb-adafruit-cdc/usb-adafruit-cdc/sam_ba_serial.h
@@ -0,0 +1,143 @@
+/*
+  Copyright (c) 2015 Arduino LLC.  All right reserved.
+  Copyright (c) 2015 Atmel Corporation/Thibaut VIARD.  All right reserved.
+
+  This library is free software; you can redistribute it and/or
+  modify it under the terms of the GNU Lesser General Public
+  License as published by the Free Software Foundation; either
+  version 2.1 of the License, or (at your option) any later version.
+
+  This library is distributed in the hope that it will be useful,
+  but WITHOUT ANY WARRANTY; without even the implied warranty of
+  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
+  See the GNU Lesser General Public License for more details.
+
+  You should have received a copy of the GNU Lesser General Public
+  License along with this library; if not, write to the Free Software
+  Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA  02110-1301  USA
+*/
+
+#ifndef _SAM_BA_SERIAL_H_
+#define _SAM_BA_SERIAL_H_
+
+#include <stdint.h>
+#include <stdbool.h>
+
+
+/* USART buffer size (must be a power of two) */
+#define USART_BUFFER_SIZE        (128)
+
+/* Define the default time-out value for USART. */
+#define USART_DEFAULT_TIMEOUT    (1000)
+
+/* Xmodem related defines */
+/* CRC16  polynomial */
+#define CRC16POLY                (0x1021)
+
+#define SHARP_CHARACTER          '#'
+
+/* X/Ymodem protocol: */
+#define SOH                      (0x01)
+//#define STX                    (0x02)
+#define EOT                      (0x04)
+#define ACK                      (0x06)
+#define NAK                      (0x15)
+#define CAN                      (0x18)
+#define ESC                      (0x1b)
+
+#define PKTLEN_128               (128)
+
+
+/**
+ * \brief Open the given USART
+ */
+void serial_open(void);
+
+/**
+ * \brief Stops the USART
+ */
+void serial_close(void);
+
+/**
+ * \brief Puts a byte on usart line
+ *
+ * \param value      Value to put
+ *
+ * \return \c 1 if function was successfully done, otherwise \c 0.
+ */
+int serial_putc(int value);
+
+/**
+ * \brief Waits and gets a value on usart line
+ *
+ * \return value read on usart line
+ */
+int serial_getc(void);
+
+/**
+ * \brief Returns true if the SAM-BA Uart received the sharp char
+ *
+ * \return Returns true if the SAM-BA Uart received the sharp char
+ */
+int serial_sharp_received(void);
+
+/**
+ * \brief This function checks if a character has been received on the usart line
+ *
+ * \return \c 1 if a byte is ready to be read.
+ */
+bool serial_is_rx_ready(void);
+
+/**
+ * \brief Gets a value on usart line
+ *
+ * \return value read on usart line
+ */
+int serial_readc(void);
+
+/**
+ * \brief Send buffer on usart line
+ *
+ * \param data pointer
+ * \param number of data to send
+ * \return number of data sent
+ */
+uint32_t serial_putdata(void const* data, uint32_t length); //Send given data (polling)
+
+/**
+ * \brief Gets data from usart line
+ *
+ * \param data pointer
+ * \param number of data to get
+ * \return value read on usart line
+ */
+uint32_t serial_getdata(void* data, uint32_t length); //Get data from comm. device
+
+/**
+ * \brief Send buffer on usart line using Xmodem protocol
+ *
+ * \param data pointer
+ * \param number of data to send
+ * \return number of data sent
+ */
+uint32_t serial_putdata_xmd(void const* data, uint32_t length); //Send given data (polling) using xmodem (if necessary)
+
+/**
+ * \brief Gets data from usart line using Xmodem protocol
+ *
+ * \param data pointer
+ * \param number of data to get
+ * \return value read on usart line
+ */
+uint32_t serial_getdata_xmd(void* data, uint32_t length); //Get data from comm. device using xmodem (if necessary)
+
+/**
+ * \brief Compute the CRC
+ *
+ * \param Char to add to CRC
+ * \param Previous CRC
+ * \return The new computed CRC
+ */
+unsigned short serial_add_crc(char c, unsigned short crc);
+
+#endif // _SAM_BA_SERIAL_H_
diff --git a/embedded/usb-adafruit-cdc/usb-adafruit-cdc/sam_ba_usb.c b/embedded/usb-adafruit-cdc/usb-adafruit-cdc/sam_ba_usb.c
new file mode 100644
index 0000000..068b81d
--- /dev/null
+++ b/embedded/usb-adafruit-cdc/usb-adafruit-cdc/sam_ba_usb.c
@@ -0,0 +1,436 @@
+/*
+  Copyright (c) 2015 Arduino LLC.  All right reserved.
+  Copyright (c) 2015 Atmel Corporation/Thibaut VIARD.  All right reserved.
+
+  This library is free software; you can redistribute it and/or
+  modify it under the terms of the GNU Lesser General Public
+  License as published by the Free Software Foundation; either
+  version 2.1 of the License, or (at your option) any later version.
+
+  This library is distributed in the hope that it will be useful,
+  but WITHOUT ANY WARRANTY; without even the implied warranty of
+  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
+  See the GNU Lesser General Public License for more details.
+
+  You should have received a copy of the GNU Lesser General Public
+  License along with this library; if not, write to the Free Software
+  Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA  02110-1301  USA
+*/
+
+#include <stdint.h>
+#include <string.h>
+#include "board_definitions.h"
+#include "sam_ba_usb.h"
+#include "board_driver_usb.h"
+#include "sam_ba_cdc.h"
+
+/* This data array will be copied into SRAM as its length is inferior to 64 bytes,
+ * and so can stay in flash.
+ */
+static __attribute__((__aligned__(4)))
+const char devDescriptor[] =
+{
+  /* Device descriptor */
+  0x12,   // bLength
+  0x01,   // bDescriptorType
+  0x00,   // bcdUSB L
+  0x02,   // bcdUSB H
+  0x02,   // bDeviceClass:    CDC class code
+  0x00,   // bDeviceSubclass: CDC class sub code
+  0x00,   // bDeviceProtocol: CDC Device protocol
+  0x40,   // bMaxPacketSize0
+  USB_VID_LOW,   // idVendor L
+  USB_VID_HIGH,   // idVendor H
+  USB_PID_LOW,   // idProduct L
+  USB_PID_HIGH,  // idProduct H
+  0x00,   // bcdDevice L, here matching SAM-BA version
+  0x02,   // bcdDevice H
+  STRING_INDEX_MANUFACTURER,   // iManufacturer
+  STRING_INDEX_PRODUCT,        // iProduct
+  0x00,   // SerialNumber, should be based on product unique ID
+  0x01    // bNumConfigs
+};
+
+/* This data array will be consumed directly by USB_Write() and must be in SRAM.
+ * We cannot send data from product internal flash.
+ */
+static __attribute__((__aligned__(4)))
+char cfgDescriptor[] =
+{
+  /* ============== CONFIGURATION 1 =========== */
+  /* Configuration 1 descriptor */
+  0x09,   // CbLength
+  0x02,   // CbDescriptorType
+  0x43,   // CwTotalLength 2 EP + Control
+  0x00,
+  0x02,   // CbNumInterfaces
+  0x01,   // CbConfigurationValue
+  0x00,   // CiConfiguration
+  0x80,   // CbmAttributes Bus powered without remote wakeup: 0x80, Self powered without remote wakeup: 0xc0
+  0x32,   // CMaxPower, report using 100mA, enough for a bootloader
+
+  /* Communication Class Interface Descriptor Requirement */
+  0x09, // bLength
+  0x04, // bDescriptorType
+  0x00, // bInterfaceNumber
+  0x00, // bAlternateSetting
+  0x01, // bNumEndpoints
+  0x02, // bInterfaceClass
+  0x02, // bInterfaceSubclass
+  0x00, // bInterfaceProtocol
+  0x00, // iInterface
+
+  /* Header Functional Descriptor */
+  0x05, // bFunction Length
+  0x24, // bDescriptor type: CS_INTERFACE
+  0x00, // bDescriptor subtype: Header Func Desc
+  0x10, // bcdCDC:1.1
+  0x01,
+
+  /* ACM Functional Descriptor */
+  0x04, // bFunctionLength
+  0x24, // bDescriptor Type: CS_INTERFACE
+  0x02, // bDescriptor Subtype: ACM Func Desc
+  0x00, // bmCapabilities
+
+  /* Union Functional Descriptor */
+  0x05, // bFunctionLength
+  0x24, // bDescriptorType: CS_INTERFACE
+  0x06, // bDescriptor Subtype: Union Func Desc
+  0x00, // bMasterInterface: Communication Class Interface
+  0x01, // bSlaveInterface0: Data Class Interface
+
+  /* Call Management Functional Descriptor */
+  0x05, // bFunctionLength
+  0x24, // bDescriptor Type: CS_INTERFACE
+  0x01, // bDescriptor Subtype: Call Management Func Desc
+  0x00, // bmCapabilities: D1 + D0
+  0x01, // bDataInterface: Data Class Interface 1
+
+  /* Endpoint 1 descriptor */
+  0x07,   // bLength
+  0x05,   // bDescriptorType
+  0x83,   // bEndpointAddress, Endpoint 03 - IN
+  0x03,   // bmAttributes      INT
+  0x08,   // wMaxPacketSize
+  0x00,
+  0xFF,   // bInterval
+
+  /* Data Class Interface Descriptor Requirement */
+  0x09, // bLength
+  0x04, // bDescriptorType
+  0x01, // bInterfaceNumber
+  0x00, // bAlternateSetting
+  0x02, // bNumEndpoints
+  0x0A, // bInterfaceClass
+  0x00, // bInterfaceSubclass
+  0x00, // bInterfaceProtocol
+  0x00, // iInterface
+
+  /* First alternate setting */
+  /* Endpoint 1 descriptor */
+  0x07,   // bLength
+  0x05,   // bDescriptorType
+  0x81,   // bEndpointAddress, Endpoint 01 - IN
+  0x02,   // bmAttributes      BULK
+  USB_EP_IN_SIZE,   // wMaxPacketSize
+  0x00,
+  0x00,   // bInterval
+
+  /* Endpoint 2 descriptor */
+  0x07,   // bLength
+  0x05,   // bDescriptorType
+  0x02,   // bEndpointAddress, Endpoint 02 - OUT
+  0x02,   // bmAttributes      BULK
+  USB_EP_OUT_SIZE,   // wMaxPacketSize
+  0x00,
+  0x00    // bInterval
+};
+
+#ifndef STRING_MANUFACTURER
+#  define STRING_MANUFACTURER "Arduino LLC"
+#endif
+
+#ifndef STRING_PRODUCT
+#  define STRING_PRODUCT "Arduino Zero"
+#endif
+
+USB_CDC sam_ba_cdc;
+
+/*----------------------------------------------------------------------------
+ * \brief This function is a callback invoked when a SETUP packet is received
+ */
+void sam_ba_usb_CDC_Enumerate(P_USB_CDC pCdc)
+{
+  Usb *pUsb = pCdc->pUsb;
+  static volatile uint8_t bmRequestType, bRequest, dir;
+  static volatile uint16_t wValue, wIndex, wLength, wStatus;
+
+  /* Clear the Received Setup flag */
+  pUsb->DEVICE.DeviceEndpoint[0].EPINTFLAG.reg = USB_DEVICE_EPINTFLAG_RXSTP;
+
+  /* Read the USB request parameters */
+  bmRequestType = udd_ep_out_cache_buffer[0][0];
+  bRequest      = udd_ep_out_cache_buffer[0][1];
+  wValue        = (udd_ep_out_cache_buffer[0][2] & 0xFF);
+  wValue       |= (udd_ep_out_cache_buffer[0][3] << 8);
+  wIndex        = (udd_ep_out_cache_buffer[0][4] & 0xFF);
+  wIndex       |= (udd_ep_out_cache_buffer[0][5] << 8);
+  wLength       = (udd_ep_out_cache_buffer[0][6] & 0xFF);
+  wLength      |= (udd_ep_out_cache_buffer[0][7] << 8);
+
+  /* Clear the Bank 0 ready flag on Control OUT */
+  pUsb->DEVICE.DeviceEndpoint[0].EPSTATUSCLR.reg = USB_DEVICE_EPSTATUSCLR_BK0RDY;
+
+  /* Handle supported standard device request Cf Table 9-3 in USB specification Rev 1.1 */
+  switch ((bRequest << 8) | bmRequestType)
+  {
+    case STD_GET_DESCRIPTOR:
+      if (wValue>>8 == STD_GET_DESCRIPTOR_DEVICE)
+      {
+        /* Return Device Descriptor */
+        USB_Write(pCdc->pUsb, devDescriptor, SAM_BA_MIN(sizeof(devDescriptor), wLength), USB_EP_CTRL);
+      }
+      else if (wValue>>8 == STD_GET_DESCRIPTOR_CONFIGURATION)
+      {
+        /* Return Configuration Descriptor */
+        USB_Write(pCdc->pUsb, cfgDescriptor, SAM_BA_MIN(sizeof(cfgDescriptor), wLength), USB_EP_CTRL);
+      }
+      else if (wValue>>8 == STD_GET_DESCRIPTOR_STRING)
+      {
+        switch ( wValue & 0xff )
+        {
+          case STRING_INDEX_LANGUAGES: {
+            uint16_t STRING_LANGUAGE[2] = { (STD_GET_DESCRIPTOR_STRING<<8) | 4, 0x0409 };
+
+            USB_Write(pCdc->pUsb, (const char*)STRING_LANGUAGE, SAM_BA_MIN(sizeof(STRING_LANGUAGE), wLength), USB_EP_CTRL);
+          }
+          break;
+
+          case STRING_INDEX_MANUFACTURER:
+            USB_SendString(pCdc->pUsb, STRING_MANUFACTURER, wLength );
+          break;
+
+          case STRING_INDEX_PRODUCT:
+            USB_SendString(pCdc->pUsb, STRING_PRODUCT, wLength );
+          break;
+          default:
+            /* Stall the request */
+            USB_SendStall(pUsb, true);
+          break;
+        }
+      }
+      else
+      {
+        /* Stall the request */
+        USB_SendStall(pUsb, true);
+      }
+    break;
+
+    case STD_SET_ADDRESS:
+      /* Send ZLP */
+      USB_SendZlp(pUsb);
+      /* Set device address to the newly received address from host */
+      USB_SetAddress(pCdc->pUsb, wValue);
+    break;
+
+    case STD_SET_CONFIGURATION:
+      /* Store configuration */
+      pCdc->currentConfiguration = (uint8_t)wValue;
+
+      /* Send ZLP */
+      USB_SendZlp(pUsb);
+
+      /* Configure the 3 needed endpoints */
+      USB_Configure(pUsb);
+    break;
+
+    case STD_GET_CONFIGURATION:
+      /* Return current configuration value */
+      USB_Write(pCdc->pUsb, (char *) &(pCdc->currentConfiguration), sizeof(pCdc->currentConfiguration), USB_EP_CTRL);
+    break;
+
+    case STD_GET_STATUS_ZERO:
+      wStatus = 0;
+      USB_Write(pCdc->pUsb, (char *) &wStatus, sizeof(wStatus), USB_EP_CTRL);
+    break;
+
+    case STD_GET_STATUS_INTERFACE:
+      wStatus = 0;
+      USB_Write(pCdc->pUsb, (char *) &wStatus, sizeof(wStatus), USB_EP_CTRL);
+    break;
+
+    case STD_GET_STATUS_ENDPOINT:
+      wStatus = 0;
+      dir = wIndex & 80;
+      wIndex &= 0x0F;
+      if (wIndex <= 3)
+      {
+        if (dir)
+        {
+          wStatus = (pUsb->DEVICE.DeviceEndpoint[wIndex].EPSTATUS.reg & USB_DEVICE_EPSTATUSSET_STALLRQ1) ? 1 : 0;
+        }
+        else
+        {
+          wStatus = (pUsb->DEVICE.DeviceEndpoint[wIndex].EPSTATUS.reg & USB_DEVICE_EPSTATUSSET_STALLRQ0) ? 1 : 0;
+        }
+        /* Return current status of endpoint */
+        USB_Write(pCdc->pUsb, (char *) &wStatus, sizeof(wStatus), USB_EP_CTRL);
+      }
+      else
+      {
+        /* Stall the request */
+        USB_SendStall(pUsb, true);
+      }
+    break;
+
+    case STD_SET_FEATURE_ZERO:
+      /* Stall the request */
+      USB_SendStall(pUsb, true);
+    break;
+
+    case STD_SET_FEATURE_INTERFACE:
+      /* Send ZLP */
+      USB_SendZlp(pUsb);
+    break;
+
+    case STD_SET_FEATURE_ENDPOINT:
+      dir = wIndex & 0x80;
+      wIndex &= 0x0F;
+      if ((wValue == 0) && wIndex && (wIndex <= 3))
+      {
+        /* Set STALL request for the endpoint */
+        if (dir)
+        {
+          pUsb->DEVICE.DeviceEndpoint[wIndex].EPSTATUSSET.reg = USB_DEVICE_EPSTATUSSET_STALLRQ1;
+        }
+        else
+        {
+          pUsb->DEVICE.DeviceEndpoint[wIndex].EPSTATUSSET.reg = USB_DEVICE_EPSTATUSSET_STALLRQ0;
+        }
+
+        /* Send ZLP */
+        USB_SendZlp(pUsb);
+      }
+      else
+      {
+        /* Stall the request */
+        USB_SendStall(pUsb, true);
+      }
+    break;
+
+    case STD_SET_INTERFACE:
+    case STD_CLEAR_FEATURE_ZERO:
+      /* Stall the request */
+      USB_SendStall(pUsb, true);
+    break;
+
+    case STD_CLEAR_FEATURE_INTERFACE:
+      /* Send ZLP */
+      USB_SendZlp(pUsb);
+    break;
+
+    case STD_CLEAR_FEATURE_ENDPOINT:
+      dir = wIndex & 0x80;
+      wIndex &= 0x0F;
+
+      if ((wValue == 0) && wIndex && (wIndex <= 3))
+      {
+        if (dir)
+        {
+          if (pUsb->DEVICE.DeviceEndpoint[wIndex].EPSTATUS.bit.STALLRQ1)
+          {
+            // Remove stall request
+            pUsb->DEVICE.DeviceEndpoint[wIndex].EPSTATUSCLR.reg = USB_DEVICE_EPSTATUSCLR_STALLRQ1;
+            if (pUsb->DEVICE.DeviceEndpoint[wIndex].EPINTFLAG.bit.STALL1)
+            {
+              pUsb->DEVICE.DeviceEndpoint[wIndex].EPINTFLAG.reg = USB_DEVICE_EPINTFLAG_STALL1;
+              // The Stall has occurred, then reset data toggle
+              pUsb->DEVICE.DeviceEndpoint[wIndex].EPSTATUSCLR.reg = USB_DEVICE_EPSTATUSSET_DTGLIN;
+            }
+          }
+        }
+        else
+        {
+          if (pUsb->DEVICE.DeviceEndpoint[wIndex].EPSTATUS.bit.STALLRQ0)
+          {
+            // Remove stall request
+            pUsb->DEVICE.DeviceEndpoint[wIndex].EPSTATUSCLR.reg = USB_DEVICE_EPSTATUSCLR_STALLRQ0;
+            if (pUsb->DEVICE.DeviceEndpoint[wIndex].EPINTFLAG.bit.STALL0)
+            {
+              pUsb->DEVICE.DeviceEndpoint[wIndex].EPINTFLAG.reg = USB_DEVICE_EPINTFLAG_STALL0;
+              // The Stall has occurred, then reset data toggle
+              pUsb->DEVICE.DeviceEndpoint[wIndex].EPSTATUSCLR.reg = USB_DEVICE_EPSTATUSSET_DTGLOUT;
+            }
+          }
+        }
+        /* Send ZLP */
+        USB_SendZlp(pUsb);
+      }
+      else
+      {
+        USB_SendStall(pUsb, true);
+      }
+    break;
+
+    // handle CDC class requests
+    case SET_LINE_CODING:
+      /* Send ZLP */
+      USB_SendZlp(pUsb);
+    break;
+
+    case GET_LINE_CODING:
+      /* Send current line coding */
+      USB_Write(pCdc->pUsb, (char *) &line_coding, SAM_BA_MIN(sizeof(usb_cdc_line_coding_t), wLength), USB_EP_CTRL);
+    break;
+
+    case SET_CONTROL_LINE_STATE:
+      /* Store the current connection */
+      pCdc->currentConnection = wValue;
+      /* Send ZLP */
+      USB_SendZlp(pUsb);
+    break;
+
+    default:
+      /* Stall the request */
+      USB_SendStall(pUsb, true);
+    break;
+  }
+}
+
+/*----------------------------------------------------------------------------
+ * \brief
+ */
+P_USB_CDC usb_init(void)
+{
+  sam_ba_cdc.pUsb = USB;
+
+  /* Initialize USB */
+  USB_Init();
+  /* Get the default CDC structure settings */
+  USB_Open(&sam_ba_cdc, sam_ba_cdc.pUsb);
+
+  return &sam_ba_cdc;
+}
+
+/*----------------------------------------------------------------------------
+ * \brief Send a USB descriptor string.
+ *
+ * The input string is plain ASCII but is sent out as UTF-16 with the correct 2-byte prefix.
+ */
+uint32_t USB_SendString(Usb *pUsb, const char* ascii_string, uint8_t maxLength)
+{
+  uint8_t string_descriptor[255]; // Max USB-allowed string length
+  uint16_t* unicode_string=(uint16_t*)(string_descriptor+2); // point on 3 bytes of descriptor
+  int resulting_length;
+
+  string_descriptor[0] = (strlen(ascii_string)<<1) + 2;
+  string_descriptor[1] = STD_GET_DESCRIPTOR_STRING;
+
+  for ( resulting_length = 1 ; *ascii_string && (resulting_length<maxLength>>1) ; resulting_length++ )
+  {
+    *unicode_string++ = (uint16_t)(*ascii_string++);
+  }
+
+  return USB_Write(pUsb, (const char*)string_descriptor, resulting_length<<1, USB_EP_CTRL);
+}
diff --git a/embedded/usb-adafruit-cdc/usb-adafruit-cdc/sam_ba_usb.h b/embedded/usb-adafruit-cdc/usb-adafruit-cdc/sam_ba_usb.h
new file mode 100644
index 0000000..457fdbc
--- /dev/null
+++ b/embedded/usb-adafruit-cdc/usb-adafruit-cdc/sam_ba_usb.h
@@ -0,0 +1,103 @@
+/*
+  Copyright (c) 2015 Arduino LLC.  All right reserved.
+  Copyright (c) 2015 Atmel Corporation/Thibaut VIARD.  All right reserved.
+
+  This library is free software; you can redistribute it and/or
+  modify it under the terms of the GNU Lesser General Public
+  License as published by the Free Software Foundation; either
+  version 2.1 of the License, or (at your option) any later version.
+
+  This library is distributed in the hope that it will be useful,
+  but WITHOUT ANY WARRANTY; without even the implied warranty of
+  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
+  See the GNU Lesser General Public License for more details.
+
+  You should have received a copy of the GNU Lesser General Public
+  License along with this library; if not, write to the Free Software
+  Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA  02110-1301  USA
+*/
+
+#ifndef CDC_ENUMERATE_H
+#define CDC_ENUMERATE_H
+
+#include <sam.h>
+#include <stdbool.h>
+
+#define USB_EP_CTRL             (0u)
+#define USB_EP_OUT              (2u)
+#define USB_EP_OUT_SIZE         (0x40u)
+#define USB_EP_IN               (1u)
+#define USB_EP_IN_SIZE          (0x40u)
+#define USB_EP_COMM             (3u)
+#define MAX_EP                  (4u)
+
+/* USB standard request code */
+#define STD_GET_STATUS_ZERO            (0x0080u)
+#define STD_GET_STATUS_INTERFACE       (0x0081u)
+#define STD_GET_STATUS_ENDPOINT        (0x0082u)
+
+#define STD_CLEAR_FEATURE_ZERO         (0x0100u)
+#define STD_CLEAR_FEATURE_INTERFACE    (0x0101u)
+#define STD_CLEAR_FEATURE_ENDPOINT     (0x0102u)
+
+#define STD_SET_FEATURE_ZERO           (0x0300u)
+#define STD_SET_FEATURE_INTERFACE      (0x0301u)
+#define STD_SET_FEATURE_ENDPOINT       (0x0302u)
+
+#define STD_SET_ADDRESS                (0x0500u)
+#define STD_GET_DESCRIPTOR             (0x0680u)
+#define STD_SET_DESCRIPTOR             (0x0700u)
+#define STD_GET_CONFIGURATION          (0x0880u)
+#define STD_SET_CONFIGURATION          (0x0900u)
+#define STD_GET_INTERFACE              (0x0A81u)
+#define STD_SET_INTERFACE              (0x0B01u)
+#define STD_SYNCH_FRAME                (0x0C82u)
+
+#define STD_GET_DESCRIPTOR_DEVICE                          (1u)
+#define STD_GET_DESCRIPTOR_CONFIGURATION                   (2u)
+#define STD_GET_DESCRIPTOR_STRING                          (3u)
+#define STD_GET_DESCRIPTOR_INTERFACE                       (4u)
+#define STD_GET_DESCRIPTOR_ENDPOINT                        (5u)
+#define STD_GET_DESCRIPTOR_DEVICE_QUALIFIER                (6u)
+#define STD_GET_DESCRIPTOR_OTHER_SPEED_CONFIGURATION       (7u)
+#define STD_GET_DESCRIPTOR_INTERFACE_POWER1                (8u)
+
+#define FEATURE_ENDPOINT_HALT          (0u)
+#define FEATURE_DEVICE_REMOTE_WAKEUP   (1u)
+#define FEATURE_TEST_MODE              (2u)
+
+#define STRING_INDEX_LANGUAGES         (0x00u)
+#define STRING_INDEX_MANUFACTURER      (0x01u)
+#define STRING_INDEX_PRODUCT           (0x02u)
+
+#define SAM_BA_MIN(a, b) (((a) < (b)) ? (a) : (b))
+
+
+typedef struct _USB_CDC
+{
+	// Private members
+	Usb *pUsb;
+	uint8_t currentConfiguration;
+	uint8_t currentConnection;
+	// Public Methods:
+	uint8_t (*IsConfigured)(struct _USB_CDC *pCdc);
+//	uint32_t (*Write) (Usb *pUsb, const char *pData, uint32_t length, uint8_t ep_num);
+//	uint32_t (*Read)  (Usb *pUsb, char *pData, uint32_t length);
+} USB_CDC, *P_USB_CDC;
+
+/**
+ * \brief Initializes the USB module
+ *
+ * \return Pointer to the USB CDC structure
+ */
+P_USB_CDC usb_init(void);
+
+void sam_ba_usb_CDC_Enumerate(P_USB_CDC pCdc);
+
+uint32_t USB_SendString(Usb *pUsb, const char* ascii_string, uint8_t maxLength);
+
+extern USB_CDC sam_ba_cdc;
+
+
+
+#endif // CDC_ENUMERATE_H
-- 
GitLab