diff --git a/boards.txt b/boards.txt
index 2433b3b949a405e843dd9443a856956f04238cca..81a4e4f246bf13457895a443ddb28f2fa45ea09a 100644
--- a/boards.txt
+++ b/boards.txt
@@ -1,6 +1,6 @@
 arduino_zero_edbg.name=Arduino Zero (Programming Port)
 arduino_zero_edbg.vid.0=0x03eb
-arduino_zero_edbg.pid.0=0x2111
+arduino_zero_edbg.pid.0=0x2157
 arduino_zero_edbg.upload.tool=openocd
 arduino_zero_edbg.upload.protocol=sam-ba
 arduino_zero_edbg.upload.maximum_size=262144
@@ -19,13 +19,15 @@ arduino_zero_edbg.build.openocdscript=openocd_scripts/arduino_zero.cfg
 arduino_zero_edbg.build.variant=arduino_zero
 arduino_zero_edbg.build.variant_system_lib=
 arduino_zero_edbg.build.vid=0x2341
-arduino_zero_edbg.build.pid=0x004d
+arduino_zero_edbg.build.pid=0x804d
 arduino_zero_edbg.bootloader.tool=openocd
 arduino_zero_edbg.bootloader.file=zero/samd21_sam_ba.bin
 
 arduino_zero_native.name=Arduino Zero (Native USB Port)
 arduino_zero_native.vid.0=0x2341
-arduino_zero_native.pid.0=0x004d
+arduino_zero_native.pid.0=0x804d
+arduino_zero_native.vid.1=0x2341
+arduino_zero_native.pid.1=0x004d
 arduino_zero_native.upload.tool=bossac
 arduino_zero_native.upload.protocol=sam-ba
 arduino_zero_native.upload.maximum_size=262144
@@ -44,4 +46,4 @@ arduino_zero_native.build.openocdscript=openocd_scripts/arduino_zero.cfg
 arduino_zero_native.build.variant=arduino_zero
 arduino_zero_native.build.variant_system_lib=
 arduino_zero_native.build.vid=0x2341
-arduino_zero_native.build.pid=0x004d
+arduino_zero_native.build.pid=0x804d
diff --git a/bootloaders/zero/drivers/cdc_enumerate.c b/bootloaders/zero/drivers/cdc_enumerate.c
index 5dda45ffb633d991179b387242511938e7ce4537..bd3873eb27f7ba40ff465f161ce3db7c613e6134 100644
--- a/bootloaders/zero/drivers/cdc_enumerate.c
+++ b/bootloaders/zero/drivers/cdc_enumerate.c
@@ -50,10 +50,10 @@ const char devDescriptor[] = {
 	0x00,   // bDeviceSubclass: CDC class sub code
 	0x00,   // bDeviceProtocol: CDC Device protocol
 	0x40,   // bMaxPacketSize0
-	0xEB,   // idVendorL
-	0x03,   //
-	0x24,   // idProductL
-	0x61,   //
+	0x41,   // idVendorL
+	0x23,   //
+	0x4D,   // idProductL
+	0x00,   //
 	0x10,   // bcdDeviceL
 	0x01,   //
 	0x00,   // iManufacturer    // 0x01
diff --git a/bootloaders/zero/main.c b/bootloaders/zero/main.c
index 3557eee6dc4788e3e5ba06861692bff4a2d326c4..4ad7abd54dd9f36bf394182f30697116abfdea0b 100644
--- a/bootloaders/zero/main.c
+++ b/bootloaders/zero/main.c
@@ -106,26 +106,22 @@ static void check_start_application(void)
 	}
 	else
 	{
-		switch (BOOT_DOUBLE_TAP_DATA) {
-		case 0:
-			/* First tap */
-			BOOT_DOUBLE_TAP_DATA = DOUBLE_TAP_MAGIC;
-
-			for (uint32_t i=0; i<125000; i++) /* 500ms */
-				/* force compiler to not optimize this... */
-				__asm__ __volatile__("");
-
-			/* Timeout happened, continue boot... */
-			BOOT_DOUBLE_TAP_DATA = 0;
-			break;
-		case DOUBLE_TAP_MAGIC:
+		if (BOOT_DOUBLE_TAP_DATA == DOUBLE_TAP_MAGIC) {
 			/* Second tap, stay in bootloader */
 			BOOT_DOUBLE_TAP_DATA = 0;
 			return;
-		default:
-			/* Fallback... reset counter and continue boot */
-			BOOT_DOUBLE_TAP_DATA = 0;
 		}
+
+		/* First tap */
+		BOOT_DOUBLE_TAP_DATA = DOUBLE_TAP_MAGIC;
+
+		/* Wait 0.5sec to see if the user tap reset again */
+		for (uint32_t i=0; i<125000; i++) /* 500ms */
+			/* force compiler to not optimize this... */
+			__asm__ __volatile__("");
+
+		/* Timeout happened, continue boot... */
+		BOOT_DOUBLE_TAP_DATA = 0;
 	}
 #endif
 
diff --git a/bootloaders/zero/samd21_sam_ba.bin b/bootloaders/zero/samd21_sam_ba.bin
index b1423180adc964f11901af6d6d042529325618f5..08f40f425437f8fc80c2462668f3d15bdf5453d5 100644
Binary files a/bootloaders/zero/samd21_sam_ba.bin and b/bootloaders/zero/samd21_sam_ba.bin differ
diff --git a/cores/arduino/SERCOM.h b/cores/arduino/SERCOM.h
index fb378d7d84d92898c69810bd87b8fbbf40e6900c..d64214522cea8814659dc951aaab9f9d8d68abd6 100644
--- a/cores/arduino/SERCOM.h
+++ b/cores/arduino/SERCOM.h
@@ -79,10 +79,9 @@ typedef enum
 
 typedef enum
 {
-	UART_TX_PAD_0 = 0x0ul,	//Only for UART
-	UART_TX_PAD_2 = 0x1ul,  //Only for UART
-	//UART_TX_PAD_1 = 0x0ul,	//DON'T USE
-	//UART_TX_PAD_3 = 0x1ul	//DON'T USE
+	UART_TX_PAD_0 = 0x0ul,	// Only for UART
+	UART_TX_PAD_2 = 0x1ul,  // Only for UART
+	UART_TX_RTS_CTS_PAD_0_2_3 = 0x2ul,  // Only for UART with TX on PAD0, RTS on PAD2 and CTS on PAD3
 } SercomUartTXPad;
 
 typedef enum
diff --git a/cores/arduino/Stream.cpp b/cores/arduino/Stream.cpp
index 14f972a8037e05f9187b9f56d1c0da0cda873672..b31942f293ea8ad911dfe83a93132ca4c6634d6f 100644
--- a/cores/arduino/Stream.cpp
+++ b/cores/arduino/Stream.cpp
@@ -254,59 +254,64 @@ String Stream::readStringUntil(char terminator)
 int Stream::findMulti( struct Stream::MultiTarget *targets, int tCount) {
   // any zero length target string automatically matches and would make
   // a mess of the rest of the algorithm.
-  for (struct MultiTarget *t = targets; t < targets+tCount; ++t)
+  for (struct MultiTarget *t = targets; t < targets+tCount; ++t) {
     if (t->len <= 0)
       return t - targets;
+  }
 
-  while(1) {
+  while (1) {
     int c = timedRead();
     if (c < 0)
       return -1;
 
     for (struct MultiTarget *t = targets; t < targets+tCount; ++t) {
       // the simple case is if we match, deal with that first.
-      if (c == t->str[t->index])
-	if (++t->index == t->len)
-	  return t - targets;
-	else
-	  continue;
+      if (c == t->str[t->index]) {
+        if (++t->index == t->len)
+          return t - targets;
+        else
+          continue;
+      }
 
       // if not we need to walk back and see if we could have matched further
       // down the stream (ie '1112' doesn't match the first position in '11112'
       // but it will match the second position so we can't just reset the current
       // index to 0 when we find a mismatch.
       if (t->index == 0)
-	continue;
+        continue;
 
       int origIndex = t->index;
       do {
-	--t->index;
-	// first check if current char works against the new current index
-	if (c != t->str[t->index])
-	  continue;
-
-	// if it's the only char then we're good, nothing more to check
-	if (t->index == 0) {
-	  t->index++;
-	  break;
-	}
-
-	// otherwise we need to check the rest of the found string
-	int diff = origIndex - t->index;
-	int i;
-	for (i = 0; i < t->index; ++i)
-	  if (t->str[i] != t->str[i + diff])
-	    break;
-	// if we successfully got through the previous loop then our current
-	// index is good.
-	if (i == t->index) {
-	  t->index++;
-	  break;
-	}
-	// otherwise we just try the next index
+        --t->index;
+        // first check if current char works against the new current index
+        if (c != t->str[t->index])
+          continue;
+
+        // if it's the only char then we're good, nothing more to check
+        if (t->index == 0) {
+          t->index++;
+          break;
+        }
+
+        // otherwise we need to check the rest of the found string
+        int diff = origIndex - t->index;
+        size_t i;
+        for (i = 0; i < t->index; ++i) {
+          if (t->str[i] != t->str[i + diff])
+            break;
+        }
+
+        // if we successfully got through the previous loop then our current
+        // index is good.
+        if (i == t->index) {
+          t->index++;
+          break;
+        }
+
+        // otherwise we just try the next index
       } while (t->index);
     }
   }
   // unreachable
   return -1;
-}
\ No newline at end of file
+}
diff --git a/cores/arduino/USB/USBCore.cpp b/cores/arduino/USB/USBCore.cpp
index 8164f25236fd5e19e85b0a5203b33e006f1e83d9..092adb256b6ab3cc96a6299a0d93f434cbc0f679 100644
--- a/cores/arduino/USB/USBCore.cpp
+++ b/cores/arduino/USB/USBCore.cpp
@@ -33,7 +33,7 @@
 //==================================================================
 
 #define USB_PID_DUE        0x003E
-#define USB_PID_ZERO       0x004D
+#define USB_PID_ZERO       0x804D
 
 // USB Device
 #define USB_VID            0x2341 // arduino LLC vid
diff --git a/cores/arduino/Uart.cpp b/cores/arduino/Uart.cpp
index 9e8a66d03bf559a98d40704074a3430f5ec3decf..2172ff5c794c08be675571ded11652314c03a18a 100644
--- a/cores/arduino/Uart.cpp
+++ b/cores/arduino/Uart.cpp
@@ -20,11 +20,13 @@
 #include "WVariant.h"
 #include "wiring_digital.h"
 
-Uart::Uart(SERCOM *_s, uint8_t _pinRX, uint8_t _pinTX)
+Uart::Uart(SERCOM *_s, uint8_t _pinRX, uint8_t _pinTX, SercomRXPad _padRX, SercomUartTXPad _padTX)
 {
   sercom = _s;
   uc_pinRX = _pinRX;
   uc_pinTX = _pinTX;
+  uc_padRX=_padRX ;
+  uc_padTX=_padTX;
 }
 
 void Uart::begin(unsigned long baudrate)
@@ -39,8 +41,7 @@ void Uart::begin(unsigned long baudrate, uint8_t config)
 
   sercom->initUART(UART_INT_CLOCK, SAMPLE_RATE_x16, baudrate);
   sercom->initFrame(extractCharSize(config), LSB_FIRST, extractParity(config), extractNbStopBit(config));
-  sercom->initPads(UART_TX_PAD_2, SERCOM_RX_PAD_3);
-
+  sercom->initPads(uc_padTX, uc_padRX);
 
   sercom->enableUART();
 }
@@ -140,13 +141,3 @@ SercomParityMode Uart::extractParity(uint8_t config)
       return SERCOM_ODD_PARITY;
   }
 }
-
-void SERCOM0_Handler()
-{
-  Serial1.IrqHandler();
-}
-
-void SERCOM5_Handler()
-{
-  Serial.IrqHandler();
-}
diff --git a/cores/arduino/Uart.h b/cores/arduino/Uart.h
index f2c439123543dcc178d820d0d17c361f6b8c5590..5245b6550378d579d262b387ca3bf070aef67e89 100644
--- a/cores/arduino/Uart.h
+++ b/cores/arduino/Uart.h
@@ -25,11 +25,10 @@
 
 #include <cstddef>
 
-
 class Uart : public HardwareSerial
 {
   public:
-    Uart(SERCOM *_s, uint8_t _pinRX, uint8_t _pinTX);
+    Uart(SERCOM *_s, uint8_t _pinRX, uint8_t _pinTX, SercomRXPad _padRX, SercomUartTXPad _padTX);
     void begin(unsigned long baudRate);
     void begin(unsigned long baudrate, uint8_t config);
     void end();
@@ -50,14 +49,12 @@ class Uart : public HardwareSerial
 
     uint8_t uc_pinRX;
     uint8_t uc_pinTX;
+    SercomRXPad uc_padRX;
+    SercomUartTXPad uc_padTX;
 
     SercomNumberStopBit extractNbStopBit(uint8_t config);
     SercomUartCharSize extractCharSize(uint8_t config);
     SercomParityMode extractParity(uint8_t config);
 };
 
-extern Uart Serial;
-extern Uart Serial1;
-
-
 #endif
diff --git a/cores/arduino/WVariant.h b/cores/arduino/WVariant.h
index e7301163b48732077087400245afae3a151859ec..b32b9707c17e3009e8586bec5e527e48c380c971 100644
--- a/cores/arduino/WVariant.h
+++ b/cores/arduino/WVariant.h
@@ -64,6 +64,12 @@ typedef enum _ETCChannel
   TCC2_CH1 = (2<<8)|(1),
   TC3_CH0  = (3<<8)|(0),
   TC3_CH1  = (3<<8)|(1),
+  TC5_CH0  = (5<<8)|(0),
+  TC5_CH1  = (5<<8)|(1),
+#if defined __SAMD21J18A__
+  TC7_CH0  = (7<<8)|(0),
+  TC7_CH1  = (7<<8)|(1)
+#endif // __SAMD21J18A__
 } ETCChannel ;
 
 extern const void* g_apTCInstances[TCC_INST_NUM+TC_INST_NUM] ;
@@ -90,6 +96,12 @@ typedef enum _EPWMChannel
   PWM2_CH1=TCC2_CH1,
   PWM3_CH0=TC3_CH0,
   PWM3_CH1=TC3_CH1,
+  PWM5_CH0=TC5_CH0,
+  PWM5_CH1=TC5_CH1,
+#if defined __SAMD21J18A__
+  PWM7_CH0=TC7_CH0,
+  PWM7_CH1=TC7_CH1
+#endif // __SAMD21J18A__
 } EPWMChannel ;
 
 typedef enum _EPortType
diff --git a/cores/arduino/startup.c b/cores/arduino/startup.c
index 011714469a17f2ad8c8967d91805b1a005a439f3..f5113227135957a9d532490279fdd385db2261ab 100644
--- a/cores/arduino/startup.c
+++ b/cores/arduino/startup.c
@@ -35,42 +35,22 @@ void Dummy_Handler(void);
 
 /* Cortex-M0+ core handlers */
 #if defined DEBUG
-void NMI_Handler( void )
-{
-  while ( 1 )
-  {
-  }
-}
-
 void HardFault_Handler( void )
 {
-  while ( 1 )
-  {
-  }
-}
-
-void SVC_Handler( void )
-{
-  while ( 1 )
-  {
-  }
-}
+  __BKPT( 3 ) ;
 
-void PendSV_Handler( void )
-{
   while ( 1 )
   {
   }
 }
-
-void SysTick_Handler         ( void ) __attribute__ ((weak, alias("Dummy_Handler")));
 #else
-void NMI_Handler             ( void ) __attribute__ ((weak, alias("Dummy_Handler")));
 void HardFault_Handler       ( void ) __attribute__ ((weak, alias("Dummy_Handler")));
+#endif //DEBUG
+
+void NMI_Handler             ( void ) __attribute__ ((weak, alias("Dummy_Handler")));
 void SVC_Handler             ( void ) __attribute__ ((weak, alias("Dummy_Handler")));
 void PendSV_Handler          ( void ) __attribute__ ((weak, alias("Dummy_Handler")));
 void SysTick_Handler         ( void ) __attribute__ ((weak, alias("Dummy_Handler")));
-#endif //DEBUG
 
 /* Peripherals handlers */
 void PM_Handler              ( void ) __attribute__ ((weak, alias("Dummy_Handler")));
@@ -343,6 +323,21 @@ void SystemInit( void )
   PM->APBCSEL.reg = PM_APBCSEL_APBCDIV_DIV1_Val ;
 
   SystemCoreClock=VARIANT_MCK ;
+
+  /* ----------------------------------------------------------------------------------------------
+   * 8) Load ADC factory calibration values
+   */
+
+  // ADC Bias Calibration
+  uint32_t bias = (*((uint32_t *) ADC_FUSES_BIASCAL_ADDR) & ADC_FUSES_BIASCAL_Msk) >> ADC_FUSES_BIASCAL_Pos;
+
+  // ADC Linearity bits 4:0
+  uint32_t linearity = (*((uint32_t *) ADC_FUSES_LINEARITY_0_ADDR) & ADC_FUSES_LINEARITY_0_Msk) >> ADC_FUSES_LINEARITY_0_Pos;
+
+  // ADC Linearity bits 7:5
+  linearity |= ((*((uint32_t *) ADC_FUSES_LINEARITY_1_ADDR) & ADC_FUSES_LINEARITY_1_Msk) >> ADC_FUSES_LINEARITY_1_Pos) << 5;
+
+  ADC->CALIB.reg = ADC_CALIB_BIAS_CAL(bias) | ADC_CALIB_LINEARITY_CAL(linearity);
 }
 
 /**
@@ -393,6 +388,10 @@ void Reset_Handler( void )
  */
 void Dummy_Handler( void )
 {
+#if defined DEBUG
+  __BKPT( 3 ) ;
+#endif // DEBUG
+
   while ( 1 )
   {
   }
diff --git a/cores/arduino/wiring_analog.c b/cores/arduino/wiring_analog.c
index ec911de61f88c78bc96bc6f0d0697874d10d610b..369356dd715ce227913d1c09ab6791b73fc9cf2e 100644
--- a/cores/arduino/wiring_analog.c
+++ b/cores/arduino/wiring_analog.c
@@ -1,5 +1,5 @@
 /*
-  Copyright (c) 2014 Arduino.  All right reserved.
+  Copyright (c) 2014 Arduino LLC.  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
@@ -57,7 +57,6 @@ static void syncTCC(Tcc* TCCx) {
 void analogReadResolution( int res )
 {
   _readResolution = res ;
-  syncADC();
   if (res > 10)
   {
     ADC->CTRLB.bit.RESSEL = ADC_CTRLB_RESSEL_12BIT_Val;
@@ -73,6 +72,7 @@ void analogReadResolution( int res )
     ADC->CTRLB.bit.RESSEL = ADC_CTRLB_RESSEL_8BIT_Val;
     _ADCResolution = 8;
   }
+  syncADC();
 }
 
 void analogWriteResolution( int res )
diff --git a/libraries/SPI/SPI.h b/libraries/SPI/SPI.h
index bedaf9e47e21cc9bb790d927a4af4e5240f0d424..4bce89c17bf2a58ec74dda0c3fb751a185cd5157 100644
--- a/libraries/SPI/SPI.h
+++ b/libraries/SPI/SPI.h
@@ -62,19 +62,15 @@ class SPISettings {
     switch (dataMode)
     {
       case SPI_MODE0:
-        this->dataMode = SERCOM_SPI_MODE_0;
-
+        this->dataMode = SERCOM_SPI_MODE_0; break;
       case SPI_MODE1:
-        this->dataMode = SERCOM_SPI_MODE_1;
-
+        this->dataMode = SERCOM_SPI_MODE_1; break;
       case SPI_MODE2:
-        this->dataMode = SERCOM_SPI_MODE_2;
-
+        this->dataMode = SERCOM_SPI_MODE_2; break;
       case SPI_MODE3:
-        this->dataMode = SERCOM_SPI_MODE_3;
-
+        this->dataMode = SERCOM_SPI_MODE_3; break;
       default:
-        this->dataMode = SERCOM_SPI_MODE_0;
+        this->dataMode = SERCOM_SPI_MODE_0; break;
     }
   }
 
diff --git a/platform.txt b/platform.txt
index 1a738494dbf0f81104eabfb0b028e38f541401b2..28df9f91cfeade0658ab15ec6605cac84dc843b6 100644
--- a/platform.txt
+++ b/platform.txt
@@ -1,3 +1,19 @@
+# Copyright (c) 2014-2015 Arduino LLC.  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
+
 # Arduino SAMD Core and platform.
 #
 # For more info:
@@ -123,5 +139,5 @@ tools.openocd.erase.pattern=
 
 tools.openocd.bootloader.params.verbose=-d2
 tools.openocd.bootloader.params.quiet=-d0
-tools.openocd.bootloader.pattern="{path}/{cmd}" {bootloader.verbose} -s "{path}/share/openocd/scripts/" -f "{runtime.platform.path}/variants/{build.variant}/{build.openocdscript}" -c "telnet_port disabled; program {{{runtime.platform.path}/bootloaders/{bootloader.file}}} verify reset; shutdown"
+tools.openocd.bootloader.pattern="{path}/{cmd}" {bootloader.verbose} -s "{path}/share/openocd/scripts/" -f "{runtime.platform.path}/variants/{build.variant}/{build.openocdscript}" -c "telnet_port disabled; init; at91samd bootloader 0; program {{{runtime.platform.path}/bootloaders/{bootloader.file}}} verify reset; shutdown"
 
diff --git a/programmers.txt b/programmers.txt
index 9ee3ce27fd7b92353cfe798234951ce0d2166427..96562f5c3728288855bbcf03507382b4a12eadc8 100644
--- a/programmers.txt
+++ b/programmers.txt
@@ -1,6 +1,38 @@
+# Copyright (c) 2014-2015 Arduino LLC.  All right reserved.
+# Copyright (c) 2015 Amel-Tech (a division of Amel Srl). 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
+
 edbg.name=Atmel EDBG
 edbg.communication=USB
 edbg.protocol=
 edbg.program.protocol=
 edbg.program.tool=openocd
 edbg.program.extra_params=
+#edbg.build.ldscript=linker_scripts/gcc/flash_without_bootloader.ld
+
+atmel_ice.name=Atmel-ICE
+atmel_ice.communication=USB
+atmel_ice.protocol=
+atmel_ice.program.protocol=
+atmel_ice.program.tool=openocd
+atmel_ice.program.extra_params=
+
+sam_ice.name=Atmel SAM-ICE
+sam_ice.communication=USB
+sam_ice.protocol=
+sam_ice.program.protocol=
+sam_ice.program.tool=openocd
+sam_ice.program.extra_params=
diff --git a/variants/arduino_zero/linker_scripts/gcc/flash_with_bootloader.ld b/variants/arduino_zero/linker_scripts/gcc/flash_with_bootloader.ld
index 083e5606a06ac3c5a573362d2bba805cd80fc9a5..4475f95115ac52ffd5c74da5a9f44b10c250c2d4 100644
--- a/variants/arduino_zero/linker_scripts/gcc/flash_with_bootloader.ld
+++ b/variants/arduino_zero/linker_scripts/gcc/flash_with_bootloader.ld
@@ -26,7 +26,7 @@
 MEMORY
 {
   FLASH (rx) : ORIGIN = 0x00000000+0x2000, LENGTH = 0x00040000-0x2000 /* First 8KB used by bootloader */
-  RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 0x00008000-0x0004         /* Last 4B used by bootloader   */
+  RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 0x00008000
 }
 
 /* Linker script to place sections and symbol values. Should be used together
diff --git a/variants/arduino_zero/variant.cpp b/variants/arduino_zero/variant.cpp
index 4e9d6896cfbb57c9a6a104802ac45548f7474b14..84df4033e690fa6a313c1c6a2d9a3e8f14070ca6 100644
--- a/variants/arduino_zero/variant.cpp
+++ b/variants/arduino_zero/variant.cpp
@@ -23,9 +23,9 @@
  * +------------+------------------+--------+-----------------+--------------------------------------------------------------------------------------------------------
  * | 0          | 0 -> RX          |  PA11  |                 | EIC/EXTINT[11] ADC/AIN[19]           PTC/X[3] *SERCOM0/PAD[3]  SERCOM2/PAD[3]  TCC0/WO[3]  TCC1/WO[1]
  * | 1          | 1 <- TX          |  PA10  |                 | EIC/EXTINT[10] ADC/AIN[18]           PTC/X[2] *SERCOM0/PAD[2]                  TCC0/WO[2]  TCC1/WO[0]
- * | 2          | 2                |  PA08  |                 | EIC/NMI        ADC/AIN[16]           PTC/X[0]  SERCOM0/PAD[0]  SERCOM2/PAD[0]  TCC0/WO[0]  TCC1/WO[2]
+ * | 2          | 2                |  PA14  |                 | EIC/EXTINT[14]                                 SERCOM2/PAD[2]  SERCOM4/PAD[2]  TC3/WO[0]   TCC0/WO[4]
  * | 3          | ~3               |  PA09  |                 | EIC/EXTINT[9]  ADC/AIN[17]           PTC/X[1]  SERCOM0/PAD[1]  SERCOM2/PAD[1] *TCC0/WO[1]  TCC1/WO[3]
- * | 4          | ~4               |  PA14  |                 | EIC/EXTINT[14]                                 SERCOM2/PAD[2]  SERCOM4/PAD[2]  TC3/WO[0]  *TCC0/WO[4]
+ * | 4          | ~4               |  PA08  |                 | EIC/NMI        ADC/AIN[16]           PTC/X[0]  SERCOM0/PAD[0]  SERCOM2/PAD[0] *TCC0/WO[0]  TCC1/WO[2]
  * | 5          | ~5               |  PA15  |                 | EIC/EXTINT[15]                                 SERCOM2/PAD[3]  SERCOM4/PAD[3] *TC3/WO[1]   TCC0/WO[5]
  * | 6          | ~6               |  PA20  |                 | EIC/EXTINT[4]                        PTC/X[8]  SERCOM5/PAD[2]  SERCOM3/PAD[2]             *TCC0/WO[6]
  * | 7          | 7                |  PA21  |                 | EIC/EXTINT[5]                        PTC/X[9]  SERCOM5/PAD[3]  SERCOM3/PAD[3]              TCC0/WO[7]
@@ -86,7 +86,7 @@
  * | 36         |                  |  PA18  | EDBG_SS         | EIC/EXTINT[2] *SERCOM1/PAD[2] SERCOM3/PAD[2] TC3/WO[0]  TCC0/WO[2]
  * | 37         |                  |  PA17  | EDBG_SCK        | EIC/EXTINT[1] *SERCOM1/PAD[1] SERCOM3/PAD[1] TCC2/WO[1] TCC0/WO[7]
  * +------------+------------------+--------+-----------------+--------------------------------------------------------------------------------------------------------
- * | 38         |                  |  PA13  | EDBG_GPIO0      | EIC/EXTINT[13] SERCOM2/PAD[1] SERCOM4/PAD[1] *TCC2/WO[1] TCC0/WO[7]
+ * | 38         | ATN              |  PA13  | EDBG_GPIO0      | EIC/EXTINT[13] SERCOM2/PAD[1] SERCOM4/PAD[1] *TCC2/WO[1] TCC0/WO[7]
  * | 39         |                  |  PA21  | EDBG_GPIO1      | Pin 7
  * | 40         |                  |  PA06  | EDBG_GPIO2      | Pin 8
  * | 41         |                  |  PA07  | EDBG_GPIO3      | Pin 9
@@ -119,9 +119,9 @@ const PinDescription g_APinDescription[]=
 
   // 2..12
   // Digital Low
-  { PORTA,  8, PIO_DIGITAL, (PIN_ATTR_DIGITAL), No_ADC_Channel, NOT_ON_PWM, NOT_ON_TIMER, EXTERNAL_INT_NMI },
+  { PORTA, 14, PIO_DIGITAL, (PIN_ATTR_DIGITAL), No_ADC_Channel, NOT_ON_PWM, NOT_ON_TIMER, EXTERNAL_INT_14 },
   { PORTA,  9, PIO_TIMER, (PIN_ATTR_DIGITAL|PIN_ATTR_PWM|PIN_ATTR_TIMER), No_ADC_Channel, PWM0_CH1, TCC0_CH1, EXTERNAL_INT_9 }, // TCC0/WO[1]
-  { PORTA, 14, PIO_TIMER_ALT, (PIN_ATTR_DIGITAL|PIN_ATTR_PWM|PIN_ATTR_TIMER), No_ADC_Channel, PWM0_CH4, TCC0_CH4, EXTERNAL_INT_14 }, // TCC0/WO[4]
+  { PORTA,  8, PIO_TIMER, (PIN_ATTR_DIGITAL|PIN_ATTR_PWM|PIN_ATTR_TIMER), No_ADC_Channel, PWM0_CH0, TCC0_CH0, EXTERNAL_INT_NMI },  // TCC0/WO[0]
   { PORTA, 15, PIO_TIMER, (PIN_ATTR_DIGITAL|PIN_ATTR_PWM|PIN_ATTR_TIMER), No_ADC_Channel, PWM3_CH1, TC3_CH1, EXTERNAL_INT_15 }, // TC3/WO[1]
   { PORTA, 20, PIO_TIMER_ALT, (PIN_ATTR_DIGITAL|PIN_ATTR_PWM|PIN_ATTR_TIMER), No_ADC_Channel, PWM0_CH6, TCC0_CH6, EXTERNAL_INT_4 }, // TCC0/WO[6]
   { PORTA, 21, PIO_DIGITAL, (PIN_ATTR_DIGITAL), No_ADC_Channel, NOT_ON_PWM, NOT_ON_TIMER, EXTERNAL_INT_5 },
@@ -207,5 +207,15 @@ SERCOM sercom3( SERCOM3 ) ;
 SERCOM sercom4( SERCOM4 ) ;
 SERCOM sercom5( SERCOM5 ) ;
 
-Uart Serial1( &sercom0, PIN_SERIAL1_RX, PIN_SERIAL1_TX ) ;
-Uart Serial( &sercom5, PIN_SERIAL_RX, PIN_SERIAL_TX ) ;
+Uart Serial1( &sercom0, PIN_SERIAL1_RX, PIN_SERIAL1_TX, PAD_SERIAL1_RX, PAD_SERIAL1_TX ) ;
+Uart Serial( &sercom5, PIN_SERIAL_RX, PIN_SERIAL_TX, PAD_SERIAL_RX, PAD_SERIAL_TX ) ;
+void SERCOM0_Handler()
+{
+  Serial1.IrqHandler();
+}
+
+void SERCOM5_Handler()
+{
+  Serial.IrqHandler();
+}
+
diff --git a/variants/arduino_zero/variant.h b/variants/arduino_zero/variant.h
index 00dec561e8b03103052189554d3298b8c5882a59..fe09b8995b43c7f98b9a134ebee9d0d7d48645ca 100644
--- a/variants/arduino_zero/variant.h
+++ b/variants/arduino_zero/variant.h
@@ -106,12 +106,16 @@ static const uint8_t A5  = PIN_A5 ;
  * Serial interfaces
  */
 // Serial (EDBG)
-#define PIN_SERIAL_RX (31ul)
-#define PIN_SERIAL_TX (30ul)
+#define PIN_SERIAL_RX       (31ul)
+#define PIN_SERIAL_TX       (30ul)
+#define PAD_SERIAL_TX       (UART_TX_PAD_2)
+#define PAD_SERIAL_RX       (SERCOM_RX_PAD_3)
 
 // Serial1
-#define PIN_SERIAL1_RX (0ul)
-#define PIN_SERIAL1_TX (1ul)
+#define PIN_SERIAL1_RX       (0ul)
+#define PIN_SERIAL1_TX       (1ul)
+#define PAD_SERIAL1_TX       (UART_TX_PAD_2)
+#define PAD_SERIAL1_RX       (SERCOM_RX_PAD_3)
 
 /*
  * SPI Interfaces