summaryrefslogtreecommitdiff
path: root/nuttx/arch
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2015-03-26 07:56:26 -0600
committerGregory Nutt <gnutt@nuttx.org>2015-03-26 07:56:26 -0600
commitb65ebf74f89ba4b7387f891d8212555d3b7a7c9c (patch)
tree767eccd3e3da9c2460535621239127c28627a615 /nuttx/arch
parenteec3f57648eb32a66672e229c48665f3ec968793 (diff)
downloadpx4-nuttx-b65ebf74f89ba4b7387f891d8212555d3b7a7c9c.tar.gz
px4-nuttx-b65ebf74f89ba4b7387f891d8212555d3b7a7c9c.tar.bz2
px4-nuttx-b65ebf74f89ba4b7387f891d8212555d3b7a7c9c.zip
SAMV7 USB: Move clock initialization back to sam_clockconfig.c; add seperate UTMI register definition header file; fix a couple of typo bugs
Diffstat (limited to 'nuttx/arch')
-rw-r--r--nuttx/arch/arm/src/samv7/chip/sam_usbhs.h29
-rw-r--r--nuttx/arch/arm/src/samv7/chip/sam_utmi.h92
-rw-r--r--nuttx/arch/arm/src/samv7/sam_clockconfig.c80
-rw-r--r--nuttx/arch/arm/src/samv7/sam_usbdevhs.c108
4 files changed, 207 insertions, 102 deletions
diff --git a/nuttx/arch/arm/src/samv7/chip/sam_usbhs.h b/nuttx/arch/arm/src/samv7/chip/sam_usbhs.h
index 407cc507c..73edf6f7a 100644
--- a/nuttx/arch/arm/src/samv7/chip/sam_usbhs.h
+++ b/nuttx/arch/arm/src/samv7/chip/sam_usbhs.h
@@ -1,7 +1,7 @@
/************************************************************************************************************
* arch/arm/src/samv7/chip/sam_usbhs.h
*
- * Copyright (C) 2013 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2015 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* References:
@@ -126,10 +126,6 @@
#define SAM_USBHS_SCR_OFFSET 0x0808 /* General Status Clear Register */
#define SAM_USBHS_SFR_OFFSET 0x080c /* General Status Set Register */
/* 0x0810-0x082c: Reserved */
-/* UTMI Registers */
-
-#define SAM_UTMI_OHCIICR_OFFSET 0x0010 /* OHCI Interrupt Configuration Register */
-#define SAM_UTMI_CKTRIM_OFFSET 0x0030 /* UTMI Clock Trimming Register */
/* Register addresses ***************************************************************************************/
@@ -195,11 +191,6 @@
#define SAM_USBHS_SCR (SAM_USBHS_BASE+SAM_USBHS_SCR_OFFSET)
#define SAM_USBHS_SFR (SAM_USBHS_BASE+SAM_USBHS_SFR_OFFSET)
-/* UTMI Registers */
-
-#define SAM_UTMI_OHCIICR (SAM_UTMI_BASE+SAM_UTMI_OHCIICR_OFFSET)
-#define SAM_UTMI_CKTRIM (SAM_UTMI_BASE+SAM_UTMI_CKTRIM_OFFSET)
-
/* Register bit-field definitions ***************************************************************************/
/* USBHS Device Controller Register Bit Field Definitions */
@@ -304,7 +295,7 @@
/* Device Endpoint Configuration Register */
-#define USBHS_DEVEPTCFG_ALLOC (1 << 0) /* Bit 0: Endpoint Memory Allocate */
+#define USBHS_DEVEPTCFG_ALLOC (1 << 1) /* Bit 1: Endpoint Memory Allocate */
#define USBHS_DEVEPTCFG_EPBK_SHIFT (2) /* Bits 2-3: Endpoint Banks */
#define USBHS_DEVEPTCFG_EPBK_MASK (3 << USBHS_DEVEPTCFG_EPBK_SHIFT)
# define USBHS_DEVEPTCFG_EPBK(n) ((uint32_t)((n)-1) << USBHS_DEVEPTCFG_EPBK_SHIFT)
@@ -779,22 +770,6 @@
#define USBHS_SFR_RDERRIS (1 << 4) /* Bit 4: Remote Device Connection Error Interrupt Set */
-/* UTMI Registers */
-
-/* OHCI Interrupt Configuration Register */
-
-#define UTMI_OHCIICR_RES0 (1 << 0) /* Bit 0: USB PORT0 Reset */
-#define UTMI_OHCIICR_ARIE (1 << 4) /* Bit 4: OHCI Asynchronous Resume Interrupt Enable */
-#define UTMI_OHCIICR_APPSTART (0 << 5) /* Bit 5: Reserved, must be zero */
-#define UTMI_OHCIICR_UDPPUDIS (1 << 23) /* Bit 23: USB Device Pull-up Disable */
-
-/* UTMI Clock Trimming Register */
-
-#define UTMI_CKTRIM_FREQ_SHIFT (0) /* Bits 0-1: UTMI Reference Clock Frequency */
-#define UTMI_CKTRIM_FREQ_MASK (3 << UTMI_CKTRIM_FREQ_SHIFT)
-# define UTMI_CKTRIM_FREQ_XTAL12 (0 << UTMI_CKTRIM_FREQ_SHIFT) /* 12 MHz reference clock */
-# define UTMI_CKTRIM_FREQ_XTAL16 (1 << UTMI_CKTRIM_FREQ_SHIFT) /* 16 MHz reference clock */
-
/************************************************************************************************************
* Public Types
************************************************************************************************************/
diff --git a/nuttx/arch/arm/src/samv7/chip/sam_utmi.h b/nuttx/arch/arm/src/samv7/chip/sam_utmi.h
new file mode 100644
index 000000000..6d65d5480
--- /dev/null
+++ b/nuttx/arch/arm/src/samv7/chip/sam_utmi.h
@@ -0,0 +1,92 @@
+/************************************************************************************************************
+ * arch/arm/src/samv7/chip/sam_utmi.h
+ *
+ * Copyright (C) 2015 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * References:
+ * SAMV7D3 Series Data Sheet
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************************************************************/
+
+#ifndef __ARCH_ARM_SRC_SAMV7_CHIP_SAM_UTMI_H
+#define __ARCH_ARM_SRC_SAMV7_CHIP_SAM_UTMI_H
+
+/************************************************************************************************************
+ * Included Files
+ ************************************************************************************************************/
+
+#include <nuttx/config.h>
+#include <arch/samv7/chip.h>
+
+#include "chip/sam_memorymap.h"
+
+/************************************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************************************/
+/* Register offsets *****************************************************************************************/
+
+#define SAM_UTMI_OHCIICR_OFFSET 0x0010 /* OHCI Interrupt Configuration Register */
+#define SAM_UTMI_CKTRIM_OFFSET 0x0030 /* UTMI Clock Trimming Register */
+
+/* Register addresses ***************************************************************************************/
+
+#define SAM_UTMI_OHCIICR (SAM_UTMI_BASE+SAM_UTMI_OHCIICR_OFFSET)
+#define SAM_UTMI_CKTRIM (SAM_UTMI_BASE+SAM_UTMI_CKTRIM_OFFSET)
+
+/* Register bit-field definitions ***************************************************************************/
+
+/* OHCI Interrupt Configuration Register */
+
+#define UTMI_OHCIICR_RES0 (1 << 0) /* Bit 0: USB PORT0 Reset */
+#define UTMI_OHCIICR_ARIE (1 << 4) /* Bit 4: OHCI Asynchronous Resume Interrupt Enable */
+#define UTMI_OHCIICR_APPSTART (0 << 5) /* Bit 5: Reserved, must be zero */
+#define UTMI_OHCIICR_UDPPUDIS (1 << 23) /* Bit 23: USB Device Pull-up Disable */
+
+/* UTMI Clock Trimming Register */
+
+#define UTMI_CKTRIM_FREQ_SHIFT (0) /* Bits 0-1: UTMI Reference Clock Frequency */
+#define UTMI_CKTRIM_FREQ_MASK (3 << UTMI_CKTRIM_FREQ_SHIFT)
+# define UTMI_CKTRIM_FREQ_XTAL12 (0 << UTMI_CKTRIM_FREQ_SHIFT) /* 12 MHz reference clock */
+# define UTMI_CKTRIM_FREQ_XTAL16 (1 << UTMI_CKTRIM_FREQ_SHIFT) /* 16 MHz reference clock */
+
+/************************************************************************************************************
+ * Public Types
+ ************************************************************************************************************/
+
+/************************************************************************************************************
+ * Public Data
+ ************************************************************************************************************/
+
+/************************************************************************************************************
+ * Public Functions
+ ************************************************************************************************************/
+
+#endif /* __ARCH_ARM_SRC_SAMV7_CHIP_SAM_UTMI_H */
diff --git a/nuttx/arch/arm/src/samv7/sam_clockconfig.c b/nuttx/arch/arm/src/samv7/sam_clockconfig.c
index e5161a879..7d041e5ed 100644
--- a/nuttx/arch/arm/src/samv7/sam_clockconfig.c
+++ b/nuttx/arch/arm/src/samv7/sam_clockconfig.c
@@ -54,11 +54,17 @@
#include "chip/sam_wdt.h"
#include "chip/sam_supc.h"
#include "chip/sam_matrix.h"
+#include "chip/sam_utmi.h"
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
+/* Configuration ***********************************************************/
+/* Not yet supported */
+#undef CONFIG_SAMV7_USBDEVHS_LOWPOWER
+
+/* Board Settings **********************************************************/
/* PMC register settings based on the board configuration values defined
* in board.h
*/
@@ -223,6 +229,80 @@ static inline void sam_pmcsetup(void)
putreg32(BOARD_CKGR_PLLAR, SAM_PMC_CKGR_PLLAR);
sam_pmcwait(PMC_INT_LOCKA);
+#ifdef CONFIG_USBDEV
+ /* UTMI configuration: Enable port0, select 12/16 MHz MAINOSC crystal source */
+
+#if 0 /* REVISIT: Does this apply only to OHCI? */
+ putreg32(UTMI_OHCIICR_RES0, SAM_UTMI_OHCIICR);
+#endif
+
+#if BOARD_MAINOSC_FREQUENCY == 12000000
+ putreg32(UTMI_CKTRIM_FREQ_XTAL12, SAM_UTMI_CKTRIM);
+#elif BOARD_MAINOSC_FREQUENCY == 12000000
+ putreg32(UTMI_CKTRIM_FREQ_XTAL16, SAM_UTMI_CKTRIM);
+#else
+# error ERROR: Unrecognized MAINSOSC frequency
+#endif
+
+ /* Enable UTMI Clocking. The USBHS can work in two modes:
+ *
+ * - Normal mode where High speed, Full speed and Low speed are available.
+ * - Low-power mode where only Full speed and Low speed are available.
+ *
+ * Only the normal mode is supported by this logic.
+ */
+
+#ifdef CONFIG_SAMV7_USBDEVHS_LOWPOWER
+ /* UTMI Low-power mode, Full/Low Speed mode
+ *
+ * Enable the 48MHz FS Clock.
+ */
+
+ putreg32(PMC_USBCLK, SAM_PMC_SCER);
+
+#else
+ /* UTMI normal mode, High/Full/Low Speed
+ *
+ * Disable the 48MHz USB FS Clock. It is not used in this configuration
+ */
+
+ putreg32(PMC_USBCLK, SAM_PMC_SCDR);
+#endif
+
+ /* Select the UTMI PLL as the USB PLL clock input (480MHz) with divider
+ * to get to 48MHz. UPLL output frequency is determined only by the
+ * 12/16MHz crystal selection above.
+ */
+
+ regval = PMC_USB_USBS_UPLL;
+
+#ifdef CONFIG_SAMV7_USBDEVHS_LOWPOWER
+ if ((getreg32(SAM_PMC_MCKR) & PMC_MCKR_PLLADIV2) != 0)
+ {
+ /* Divider = 480 Mhz / 2 / 48 Mhz = 5 */
+
+ regval |= PMC_USB_USBDIV(4);
+ }
+ else
+ {
+ /* Divider = 480 Mhz / 1 / 48 Mhz = 10 */
+
+ regval |= PMC_USB_USBDIV(9);
+ }
+#endif
+
+ putreg32(regval, SAM_PMC_USB);
+
+ /* Enable the UTMI PLL with the maximum start-up time */
+
+ regval = PMC_CKGR_UCKR_UPLLEN | PMC_CKGR_UCKR_UPLLCOUNT_MAX;
+ putreg32(regval, SAM_PMC_CKGR_UCKR);
+
+ /* Wait for LOCKU */
+
+ sam_pmcwait(PMC_INT_LOCKU);
+#endif
+
/* Switch to the fast clock and wait for MCKRDY */
putreg32(BOARD_PMC_MCKR_FAST, SAM_PMC_MCKR);
diff --git a/nuttx/arch/arm/src/samv7/sam_usbdevhs.c b/nuttx/arch/arm/src/samv7/sam_usbdevhs.c
index cb4bdd4ad..c71e11d43 100644
--- a/nuttx/arch/arm/src/samv7/sam_usbdevhs.c
+++ b/nuttx/arch/arm/src/samv7/sam_usbdevhs.c
@@ -73,7 +73,6 @@
#include "cache.h"
#include "sam_periphclks.h"
-#include "chip/sam_pmc.h"
#include "chip/sam_usbhs.h"
#include "sam_usbdev.h"
@@ -118,7 +117,7 @@
#define EP0 (0)
#define SAM_EPSET_ALL (0xffff) /* All endpoints */
#define SAM_EPSET_NOTEP0 (0xfffe) /* All endpoints except EP0 */
-#define SAM_EPSET_DMA (0x00fe) /* All endpoints that support DMA transfers */
+#define SAM_EPSET_DMA (0x01fe) /* All endpoints that support DMA transfers */
#define SAM_EP_BIT(ep) (1 << (ep))
#define SAM_EP0_MAXPACKET (64) /* EP0 Max. packet size */
@@ -479,6 +478,8 @@ static inline bool
sam_ep_reserved(struct sam_usbdev_s *priv, int epno);
static int sam_ep_configure_internal(struct sam_ep_s *privep,
const struct usb_epdesc_s *desc);
+static inline int
+ sam_ep0_configure(struct sam_usbdev_s *priv);
/* Endpoint operations ******************************************************/
@@ -815,26 +816,26 @@ static void sam_dumpep(struct sam_usbdev_s *priv, int epno)
/* Global Registers */
lldbg("Global Register:\n");
- lldbg(" CTRL: %04x\n", sam_getreg(SAM_USBHS_DEVCTRL));
- lldbg(" IISR: %04x\n", sam_getreg(SAM_USBHS_DEVISR));
- lldbg(" IMR: %04x\n", sam_getreg(SAM_USBHS_DEVIMR));
- lldbg(" EPT: %04x\n", sam_getreg(SAM_USBHS_DEVEPT));
- lldbg(" FNUM: %04x\n", sam_getreg(SAM_USBHS_DEVFNUM));
+ lldbg(" CTRL: %08x\n", sam_getreg(SAM_USBHS_DEVCTRL));
+ lldbg(" IISR: %08x\n", sam_getreg(SAM_USBHS_DEVISR));
+ lldbg(" IMR: %08x\n", sam_getreg(SAM_USBHS_DEVIMR));
+ lldbg(" EPT: %08x\n", sam_getreg(SAM_USBHS_DEVEPT));
+ lldbg(" FNUM: %08x\n", sam_getreg(SAM_USBHS_DEVFNUM));
/* Endpoint registers */
lldbg("Endpoint %d Register:\n", epno);
- lldbg(" CFG: %04x\n", sam_getreg(SAM_USBHS_DEVEPTCFG(epno)));
- lldbg(" ISR: %04x\n", sam_getreg(SAM_USBHS_DEVEPTISR(epno)));
- lldbg(" IMR: %04x\n", sam_getreg(SAM_USBHS_DEVEPTIMR(epno)));
+ lldbg(" CFG: %08x\n", sam_getreg(SAM_USBHS_DEVEPTCFG(epno)));
+ lldbg(" ISR: %08x\n", sam_getreg(SAM_USBHS_DEVEPTISR(epno)));
+ lldbg(" IMR: %08x\n", sam_getreg(SAM_USBHS_DEVEPTIMR(epno)));
lldbg("DMA %d Register:\n", epno);
if ((SAM_EPSET_DMA & SAM_EP_BIT(epno)) != 0)
{
- lldbg(" NXTDSC: %04x\n", sam_getreg(SAM_USBHS_DEVDMANXTDSC(epno)));
- lldbg(" ADDRESS: %04x\n", sam_getreg(SAM_USBHS_DEVDMAADDR(epno)));
- lldbg(" CONTROL: %04x\n", sam_getreg(SAM_USBHS_DEVDMACTRL(epno)));
- lldbg(" STATUS: %04x\n", sam_getreg(SAM_USBHS_DEVDMASTA(epno)));
+ lldbg(" NXTDSC: %08x\n", sam_getreg(SAM_USBHS_DEVDMANXTDSC(epno)));
+ lldbg(" ADDRESS: %08x\n", sam_getreg(SAM_USBHS_DEVDMAADDR(epno)));
+ lldbg(" CONTROL: %08x\n", sam_getreg(SAM_USBHS_DEVDMACTRL(epno)));
+ lldbg(" STATUS: %08x\n", sam_getreg(SAM_USBHS_DEVDMASTA(epno)));
}
else
{
@@ -3306,7 +3307,7 @@ static int sam_ep_configure_internal(struct sam_ep_s *privep,
sam_putreg(USBHS_DEVEPTIDR_ALLINTS, SAM_USBHS_DEVEPTIDR(epno));
- /* Reset Endpoint FIFOs */
+ /* Clear toggle and stall indications */
sam_putreg(USBHS_DEVEPTISR_DTSEQ_MASK | USBHS_DEVEPTINT_STALLEDI,
SAM_USBHS_DEVEPTICR(epno));
@@ -3382,6 +3383,7 @@ static int sam_ep_configure_internal(struct sam_ep_s *privep,
* the FIFO maximum capacity and the maximum number of allowed banks.
*/
+ regaddr = SAM_USBHS_DEVEPTISR(epno);
if ((sam_getreg(regaddr) & USBHS_DEVEPTISR_CFGOK) == 0)
{
usbtrace(TRACE_DEVERROR(SAM_TRACEERR_NCFGOK), epno);
@@ -3445,6 +3447,19 @@ static int sam_ep_configure_internal(struct sam_ep_s *privep,
}
/****************************************************************************
+ * Name: sam_ep0_configure
+ *
+ * Description:
+ * Configure EP0 for normal operation.
+ *
+ ****************************************************************************/
+
+static inline int sam_ep0_configure(struct sam_usbdev_s *priv)
+{
+ return sam_ep_configure_internal(&priv->eplist[EP0], &g_ep0desc);
+}
+
+/****************************************************************************
* Endpoint operations
****************************************************************************/
/****************************************************************************
@@ -4232,7 +4247,7 @@ static void sam_reset(struct sam_usbdev_s *priv)
/* Reset and disable all endpoints other. Then re-configure EP0 */
sam_epset_reset(priv, SAM_EPSET_ALL);
- sam_ep_configure_internal(&priv->eplist[EP0], &g_ep0desc);
+ sam_ep0_configure(priv);
/* Reset endpoint data structures */
@@ -4306,6 +4321,8 @@ static void sam_hw_setup(struct sam_usbdev_s *priv)
* 2. Enable the USBHS (UIMOD = 1, USBE = 1, FRZCLK = 0).
* 3. Enable the UPLL 480 MHz.
* 4. Wait for the UPLL 480 MHz to be considered as locked by the PMC.
+ *
+ * Steps 1,3, and 4 were performed in sam_clockconfig.c.
*/
/* Enable the USBHS peripheral clock (PMC_PCER) */
@@ -4325,65 +4342,6 @@ static void sam_hw_setup(struct sam_usbdev_s *priv)
regval |= USBHS_CTRL_UIMOD_DEVICE;
sam_putreg(regval, SAM_USBHS_CTRL);
- /* UTMI configuration: Enable port0, select 12/16 MHz MAINOSC crystal source */
-
-#if 0 /* REVISIT: Does this apply only to OHCI? */
- sam_putreg(UTMI_OHCIICR_RES0, SAM_UTMI_OHCIICR);
-#endif
-
-#if BOARD_MAINOSC_FREQUENCY == 12000000
- sam_putreg(UTMI_CKTRIM_FREQ_XTAL12, SAM_UTMI_CKTRIM);
-#elif BOARD_MAINOSC_FREQUENCY == 12000000
- sam_putreg(UTMI_CKTRIM_FREQ_XTAL16, SAM_UTMI_CKTRIM);
-#else
-# error ERROR: Unrecognized MAINSOSC frequency
-#endif
-
-#ifdef CONFIG_SAMV7_USBDEVHS_LOWPOWER
- /* UTMI Full/Low Speed mode */
-
- sam_putreg(PMC_USBCLK, SAM_PMC_SCER);
-#else
- /* UTMI parallel mode, High/Full/Low Speed
- *
- * Disable 48MHz USB FS Clock. It is not used in this configuration
- */
-
- sam_putreg(PMC_USBCLK, SAM_PMC_SCDR);
-#endif
-
- /* Select the UTMI PLL as the USB PLL clock input (480MHz) with divider
- * to get to 48MHz.
- */
-
- regval = PMC_USB_USBS_UPLL;
-
-#ifdef CONFIG_SAMV7_USBDEVHS_LOWPOWER
- if ((sam_getreg(SAM_PMC_MCKR) & PMC_MCKR_PLLADIV2) != 0)
- {
- /* Divider = 480 Mhz / 2 / 48 Mhz = 5 */
-
- regval |= PMC_USB_USBDIV(4);
- }
- else
- {
- /* Divider = 480 Mhz / 1 / 48 Mhz = 10 */
-
- regval |= PMC_USB_USBDIV(9);
- }
-#endif
-
- sam_putreg(regval, SAM_PMC_USB);
-
- /* Enable the UTMI PLL with the maximum start-up time */
-
- regval = PMC_CKGR_UCKR_UPLLEN | PMC_CKGR_UCKR_UPLLCOUNT_MAX;
- sam_putreg(regval, SAM_PMC_CKGR_UCKR);
-
- /* Wait for LOCKU */
-
- while ((sam_getreg(SAM_PMC_SR) & PMC_INT_LOCKU) == 0);
-
/* Select High Speed */
regval = sam_getreg(SAM_USBHS_DEVCTRL);