summaryrefslogblamecommitdiff
path: root/nuttx/configs/arduino-due/include/board.h
blob: ef841926c7039fa86d7c5ae2d2c4e9c4f0513da5 (plain) (tree)


















































































































































































































































                                                                                          
/************************************************************************************
 * configs/arduino-due/include/board.h
 *
 *   Copyright (C) 2013 Gregory Nutt. All rights reserved.
 *   Author: Gregory Nutt <gnutt@nuttx.org>
 *
 * 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 __CONFIGS_ARDUINO_DUE_INCLUDE_BOARD_H
#define __CONFIGS_ARDUINO_DUE_INCLUDE_BOARD_H

/************************************************************************************
 * Included Files
 ************************************************************************************/

#include <nuttx/config.h>

#ifndef __ASSEMBLY__
#  include <stdint.h>
#  ifdef CONFIG_GPIO_IRQ
#    include <arch/irq.h>
#  endif
#endif

/************************************************************************************
 * Definitions
 ************************************************************************************/

/* Clocking *************************************************************************/
/* After power-on reset, the SAM3X device is running on a 4MHz internal RC.  These
 * definitions will configure clocking
 *
 *   MAINOSC:  Frequency = 12MHz (crysta)
 *   PLLA: PLL Divider = 1, Multiplier = 14 to generate PLLACK = 168MHz
 *   Master Clock (MCK): Source = PLLACK, Prescalar = 1 to generate MCK = 84MHz
 *   CPU clock: 84MHz
 */

/* Main oscillator register settings.
 *
 *   The start up time should be should be:
 *   Start Up Time = 8 * MOSCXTST / SLCK = 56 Slow Clock Cycles.
 */

#define BOARD_CKGR_MOR_MOSCXTST    (62 << PMC_CKGR_MOR_MOSCXTST_SHIFT) /* Start-up Time */

/* PLLA configuration.
 *
 *   Divider = 1
 *   Multipler = 14
 */

#define BOARD_CKGR_PLLAR_MUL       (13 << PMC_CKGR_PLLAR_MUL_SHIFT)
#define BOARD_CKGR_PLLAR_STMODE    PMC_CKGR_PLLAR_STMODE_FAST
#define BOARD_CKGR_PLLAR_COUNT     (63 << PMC_CKGR_PLLAR_COUNT_SHIFT)
#define BOARD_CKGR_PLLAR_DIV       PMC_CKGR_PLLAR_DIV_BYPASS

/* PMC master clock register settings.
 *
 *  Source = PLLA
 *  Divider = 2
 */

#define BOARD_PMC_MCKR_CSS         PMC_MCKR_CSS_PLLA
#define BOARD_PMC_MCKR_PRES        PMC_MCKR_PRES_DIV2

/* USB UTMI PLL start-up time */

#define BOARD_CKGR_UCKR_UPLLCOUNT  (3 << PMC_CKGR_UCKR_UPLLCOUNT_SHIFT)

/* Resulting frequencies */

#define BOARD_MAINOSC_FREQUENCY    (12000000)  /* MAINOSC: 12MHz crystal on-board */
#define BOARD_PLLA_FREQUENCY       (168000000) /* PLLACK:  14 * 12Mhz / 1 */
#define BOARD_MCK_FREQUENCY        (84000000)  /* MCK:     PLLACK / 2 */
#define BOARD_CPU_FREQUENCY        (84000000)  /* CPU:     MCK */

/* HSMCI clocking
 *
 * Multimedia Card Interface clock (MCCK or MCI_CK) is Master Clock (MCK)
 * divided by (2*(CLKDIV+1)).
 *
 *   MCI_SPEED = MCCK / (2*(CLKDIV+1))
 *   CLKDIV = MCCK / MCI_SPEED / 2 - 1
 *
 * Where CLKDIV has a range of 0-255.
 */

/* MCK = 84MHz, CLKDIV = 104, MCI_SPEED = 84MHz / 2 * (104+1) = 400 KHz */

#define HSMCI_INIT_CLKDIV          (104 << HSMCI_MR_CLKDIV_SHIFT)

/* MCK = 84MHz, CLKDIV = 2, MCI_SPEED = 84MHz / 2 * (2+1) = 14 MHz */

#define HSMCI_MMCXFR_CLKDIV        (1 << HSMCI_MR_CLKDIV_SHIFT)

/* MCK = 84MHz, CLKDIV = 1, MCI_SPEED = 84MHz / 2 * (1+1) = 21 MHz */

#define HSMCI_SDXFR_CLKDIV         (1 << HSMCI_MR_CLKDIV_SHIFT)
#define HSMCI_SDWIDEXFR_CLKDIV     HSMCI_SDXFR_CLKDIV

/* FLASH wait states
 *
 * FWS Max frequency
 *     1.62V 1.8V
 * --- ----- ------
 *  0  24MHz 27MHz
 *  1  40MHz 47MHz
 *  2  72MHz 84MHz
 *  3  84MHz 96MHz
 */

#define BOARD_FWS                  2

/* LED definitions ******************************************************************/
/*   There are two user-controllable LEDs on board the Arduino Due board:
 *
 *     LED              GPIO
 *     ---------------- -----
 *     TX  Yellow LED   PA21
 *     RX  Yellow LED   PC30
 *
 * Both are pulled high and can be illuminated by driving the corresponding
 * GPIO output to low.
 */

/* LED index values for use with sam_setled() */

#define BOARD_LED_RX      0
#define BOARD_LED_TX      1
#define BOARD_NLEDS       2

/* LED bits for use with sam_setleds() */

#define BOARD_LED_RX_BIT  (1 << BOARD_LED_RX)
#define BOARD_LED_TX_BIT  (1 << BOARD_LED_TX)

/* These LEDs are not used by the board port unless CONFIG_ARCH_LEDS is
 * defined.  In that case, the usage by the board port is defined in
 * include/board.h and src/sam_leds.c. The LEDs are used to encode OS-related
 * events as follows:
 *
 *   SYMBOL               Val   Meaning                     LED state
 *                                                      RX       TX
 *   -------------------  --- -----------------------  -------- --------- */
#define LED_STARTED       0  /* NuttX has been started  OFF      OFF      */
#define LED_HEAPALLOCATE  0  /* Heap has been allocated OFF      OFF      */
#define LED_IRQSENABLED   0  /* Interrupts enabled      OFF      OFF      */
#define LED_STACKCREATED  1  /* Idle stack created      ON       OFF      */
#define LED_INIRQ         2  /* In an interrupt           No change       */
#define LED_SIGNAL        2  /* In a signal handler       No change       */
#define LED_ASSERTION     2  /* An assertion failed       No change       */
#define LED_PANIC         3  /* The system has crashed  OFF      Blinking */
#undef  LED_IDLE             /* MCU is is sleep mode      Not used        */

/* Thus if RX is statically on, NuttX has successfully booted and is,
 * apparently, running normmally.  If TX is flashing at approximately
 * 2Hz, then a fatal error has been detected and the system has halted.
 */

/* Button definitions ***************************************************************/
/*   There are no buttons on the Arduino Due board. */


/************************************************************************************
 * Public Data
 ************************************************************************************/

#ifndef __ASSEMBLY__

#undef EXTERN
#if defined(__cplusplus)
#define EXTERN extern "C"
extern "C" {
#else
#define EXTERN extern
#endif

/************************************************************************************
 * Public Function Prototypes
 ************************************************************************************/
/************************************************************************************
 * Name: sam_boardinitialize
 *
 * Description:
 *   All SAM3X architectures must provide the following entry point.  This entry point
 *   is called early in the intitialization -- after all memory has been configured
 *   and mapped but before any devices have been initialized.
 *
 ************************************************************************************/

void sam_boardinitialize(void);

/************************************************************************************
 * Name:  sam_ledinit, sam_setled, and sam_setleds
 *
 * Description:
 *   If CONFIG_ARCH_LEDS is defined, then NuttX will control the on-board LEDs.  If
 *   CONFIG_ARCH_LEDS is not defined, then the following interfacesare available to
 *   control the LEDs from user applications.
 *
 ************************************************************************************/

#ifndef CONFIG_ARCH_LEDS
void sam_ledinit(void);
void sam_setled(int led, bool ledon);
void sam_setleds(uint8_t ledset);
#endif

#undef EXTERN
#if defined(__cplusplus)
}
#endif

#endif /* __ASSEMBLY__ */
#endif  /* __CONFIGS_ARDUINO_DUE_INCLUDE_BOARD_H */