Add circular DMA support to STM32 and STM32 serial driver; Add initial configuration for the Mikroelektronika PIC32MX7 MMB board

git-svn-id: https://nuttx.svn.sourceforge.net/svnroot/nuttx/trunk@4640 7fd9a85b-ad96-42d3-883c-3090e2eb8679
This commit is contained in:
patacongo 2012-04-22 19:50:33 +00:00
parent cfbb78e266
commit ec81f66d5c
31 changed files with 5820 additions and 137 deletions

View File

@ -2673,4 +2673,10 @@
* drivers/serial/serial.c: Do not disable Rx interrupts on each byte.
Rather, only disable Rx interrupts when the Rx ring buffer may be empty.
* include/nuttx/usb/audio.h: USB Audio 1.0 definitions (in progress).
* arch/arm/src/stm32/stm32fxx_dma.c: STM32 F4 DMA now supports circular
buffer mode (contributed by Mike Smith)
* arch/arm/src/stm32/stm32_serial.c: The serial driver can now support
Rx DMA into a circular buffer (contributed by Mike Smith)
* configs/pic32mx7mmb: Beginning of a configuration for the Mikroelektronka
PIC32MX7 Multimedia Board (MMB).

View File

@ -1,7 +1,7 @@
/************************************************************************************
* arch/arm/src/stm32/chip/stm32_uart.h
*
* Copyright (C) 2009, 2011 Gregory Nutt. All rights reserved.
* Copyright (C) 2009, 2011-2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without

View File

@ -1,7 +1,7 @@
/****************************************************************************
* arch/arm/src/stm32/stm32_dma.c
*
* Copyright (C) 2009, 2011 Gregory Nutt. All rights reserved.
* Copyright (C) 2009, 2011-2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without

View File

@ -251,6 +251,19 @@ EXTERN void stm32_dmastart(DMA_HANDLE handle, dma_callback_t callback,
EXTERN void stm32_dmastop(DMA_HANDLE handle);
/****************************************************************************
* Name: stm32_dmaresidual
*
* Description:
* Returns the number of bytes remaining to be transferred
*
* Assumptions:
* - DMA handle allocated by stm32_dmachannel()
*
****************************************************************************/
EXTERN size_t stm32_dmaresidual(DMA_HANDLE handle);
/****************************************************************************
* Name: stm32_dmasample
*

View File

@ -56,89 +56,6 @@
/**************************************************************************
* Private Definitions
**************************************************************************/
/* Configuration **********************************************************/
/* Make sure that we have not enabled more U[S]ARTs than are support by
* the device.
*/
#if STM32_NUSART < 6
# undef CONFIG_STM32_USART6
#endif
#if STM32_NUSART < 5
# undef CONFIG_STM32_UART5
#endif
#if STM32_NUSART < 4
# undef CONFIG_STM32_UART4
#endif
#if STM32_NUSART < 3
# undef CONFIG_STM32_USART3
#endif
#if STM32_NUSART < 2
# undef CONFIG_STM32_USART2
#endif
#if STM32_NUSART < 1
# undef CONFIG_STM32_USART1
#endif
#if defined(CONFIG_STM32_USART1) || defined (CONFIG_STM32_USART2) || defined(CONFIG_STM32_USART3) || \
defined(CONFIG_STM32_UART4) || defined (CONFIG_STM32_UART5) || defined(CONFIG_STM32_USART6)
# define HAVE_UART
#endif
/* Is there a serial console? */
#if defined(CONFIG_USART1_SERIAL_CONSOLE) && defined(CONFIG_STM32_USART1)
# undef CONFIG_USART2_SERIAL_CONSOLE
# undef CONFIG_USART3_SERIAL_CONSOLE
# undef CONFIG_UART4_SERIAL_CONSOLE
# undef CONFIG_UART5_SERIAL_CONSOLE
# undef CONFIG_USART6_SERIAL_CONSOLE
# define HAVE_CONSOLE 1
#elif defined(CONFIG_USART2_SERIAL_CONSOLE) && defined(CONFIG_STM32_USART2)
# undef CONFIG_USART1_SERIAL_CONSOLE
# undef CONFIG_USART3_SERIAL_CONSOLE
# undef CONFIG_USART4_SERIAL_CONSOLE
# undef CONFIG_USART5_SERIAL_CONSOLE
# undef CONFIG_USART6_SERIAL_CONSOLE
# define HAVE_CONSOLE 1
#elif defined(CONFIG_USART3_SERIAL_CONSOLE) && defined(CONFIG_STM32_USART3)
# undef CONFIG_USART1_SERIAL_CONSOLE
# undef CONFIG_USART2_SERIAL_CONSOLE
# undef CONFIG_UART4_SERIAL_CONSOLE
# undef CONFIG_UART5_SERIAL_CONSOLE
# undef CONFIG_USART6_SERIAL_CONSOLE
# define HAVE_CONSOLE 1
#elif defined(CONFIG_UART4_SERIAL_CONSOLE) && defined(CONFIG_STM32_UART4)
# undef CONFIG_USART1_SERIAL_CONSOLE
# undef CONFIG_USART2_SERIAL_CONSOLE
# undef CONFIG_USART3_SERIAL_CONSOLE
# undef CONFIG_UART5_SERIAL_CONSOLE
# undef CONFIG_USART6_SERIAL_CONSOLE
# define HAVE_CONSOLE 1
#elif defined(CONFIG_UART5_SERIAL_CONSOLE) && defined(CONFIG_STM32_UART5)
# undef CONFIG_USART1_SERIAL_CONSOLE
# undef CONFIG_USART2_SERIAL_CONSOLE
# undef CONFIG_USART3_SERIAL_CONSOLE
# undef CONFIG_UART4_SERIAL_CONSOLE
# undef CONFIG_USART6_SERIAL_CONSOLE
# define HAVE_CONSOLE 1
#elif defined(CONFIG_USART6_SERIAL_CONSOLE) && defined(CONFIG_STM32_USART6)
# undef CONFIG_USART1_SERIAL_CONSOLE
# undef CONFIG_USART2_SERIAL_CONSOLE
# undef CONFIG_USART3_SERIAL_CONSOLE
# undef CONFIG_UART4_SERIAL_CONSOLE
# undef CONFIG_UART5_SERIAL_CONSOLE
# define HAVE_CONSOLE 1
#else
# undef CONFIG_USART1_SERIAL_CONSOLE
# undef CONFIG_USART2_SERIAL_CONSOLE
# undef CONFIG_USART3_SERIAL_CONSOLE
# undef CONFIG_UART4_SERIAL_CONSOLE
# undef CONFIG_UART5_SERIAL_CONSOLE
# undef CONFIG_USART6_SERIAL_CONSOLE
# undef HAVE_CONSOLE
#endif
/* Select USART parameters for the selected console */
#if defined(CONFIG_USART1_SERIAL_CONSOLE)

View File

@ -57,6 +57,7 @@
#include "chip.h"
#include "stm32_uart.h"
#include "stm32_dma.h"
#include "up_arch.h"
#include "up_internal.h"
#include "os_internal.h"
@ -65,36 +66,69 @@
* Definitions
****************************************************************************/
/* Some sanity checks *******************************************************/
/* Is there a USART enabled? */
/* DMA configuration */
#if defined(CONFIG_STM32_USART1) || defined(CONFIG_STM32_USART2) || \
defined(CONFIG_STM32_USART3) || defined(CONFIG_STM32_UART4) || \
defined(CONFIG_STM32_UART5) || defined(CONFIG_STM32_USART6)
# define HAVE_UART 1
#endif
/* Is there a serial console? */
#if defined(CONFIG_USART1_SERIAL_CONSOLE) && defined(CONFIG_STM32_USART1)
# define CONSOLE_UART 1
#elif defined(CONFIG_USART2_SERIAL_CONSOLE) && defined(CONFIG_STM32_USART2)
# define CONSOLE_UART 2
#elif defined(CONFIG_USART3_SERIAL_CONSOLE) && defined(CONFIG_STM32_USART3)
# define CONSOLE_UART 3
#elif defined(CONFIG_USART4_SERIAL_CONSOLE) && defined(CONFIG_STM32_UART4)
# define CONSOLE_UART 4
#elif defined(CONFIG_USART5_SERIAL_CONSOLE) && defined(CONFIG_STM32_UART5)
# define CONSOLE_UART 5
#elif defined(CONFIG_USART6_SERIAL_CONSOLE) && defined(CONFIG_STM32_USART6)
# define CONSOLE_UART 6
#else
# define CONSOLE_UART 0
#endif
/* If we are not using the serial driver for the console, then we still must
* provide some minimal implementation of up_putc.
/* If DMA is enabled on any USART, then very that other pre-requisites
* have also been selected.
*/
#if SERIAL_HAVE_DMA
/* Verify that DMA has been enabled an the DMA channel has been defined.
* NOTE: These assignments may only be true for the F4.
*/
# if defined(CONFIG_USART1_RXDMA) || defined(CONFIG_USART6_RXDMA)
# ifndef CONFIG_STM32_DMA2
# error STM32 USART1/6 receive DMA requires CONFIG_STM32_DMA2
# endif
# endif
# if defined(CONFIG_USART2_RXDMA) || defined(CONFIG_USART3_RXDMA) || \
defined(CONFIG_USART4_RXDMA) || defined(CONFIG_USART5_RXDMA)
# ifndef CONFIG_STM32_DMA1
# error STM32 USART2/3/4/5 receive DMA requires CONFIG_STM32_DMA1
# endif
# endif
/* For the F4, there are alternate DMA channels for USART1 and 6.
* Logic in the board.h file make the DMA channel selection by defining
* the following in the board.h file.
*/
# if defined(CONFIG_USART1_RXDMA) && !defined(DMAMAP_USART1_RX)
# error "USART1 DMA channel not defined (DMAMAP_USART1_RX)"
# endif
# if defined(CONFIG_USART2_RXDMA) && !defined(DMAMAP_USART2_RX)
# error "USART2 DMA channel not defined (DMAMAP_USART2_RX)"
# endif
# if defined(CONFIG_USART3_RXDMA) && !defined(DMAMAP_USART3_RX)
# error "USART3 DMA channel not defined (DMAMAP_USART3_RX)"
# endif
# if defined(CONFIG_USART4_RXDMA) && !defined(DMAMAP_UART4_RX)
# error "UART4 DMA channel not defined (DMAMAP_UART4_RX)"
# endif
# if defined(CONFIG_USART5_RXDMA) && !defined(DMAMAP_UART5_RX)
# error "UART5 DMA channel not defined (DMAMAP_UART5_RX)"
# endif
# if defined(CONFIG_USART6_RXDMA) && !defined(DMAMAP_USART6_RX)
# error "USART6 DMA channel not defined (DMAMAP_USART6_RX)"
# endif
/* The DMA buffer size when using RX DMA to emulate a FIFO.
*
* When streaming data, the generic serial layer will be called
* everytime the FIFO receives half this number of bytes.
*/
# define RXDMA_BUFFER_SIZE 32
#endif
#ifdef USE_SERIALDRIVER
#ifdef HAVE_UART
@ -120,7 +154,20 @@ struct up_dev_s
const uint32_t rts_gpio; /* U[S]ART RTS GPIO pin configuration */
const uint32_t cts_gpio; /* U[S]ART CTS GPIO pin configuration */
#ifdef SERIAL_HAVE_DMA
const unsigned int rxdma_channel; /* DMA channel assigned */
#endif
int (* const vector)(int irq, void *context); /* Interrupt handler */
/* RX DMA state */
#ifdef SERIAL_HAVE_DMA
DMA_HANDLE rxdma; /* currently-open receive DMA stream */
bool rxenable; /* DMA-based reception en/disable */
uint32_t rxdmanext; /* Next byte in the DMA buffer to be read */
char *const rxfifo; /* Receive DMA buffer */
#endif
};
/****************************************************************************
@ -133,13 +180,25 @@ static int up_attach(struct uart_dev_s *dev);
static void up_detach(struct uart_dev_s *dev);
static int up_interrupt_common(struct up_dev_s *dev);
static int up_ioctl(struct file *filep, int cmd, unsigned long arg);
#ifndef SERIAL_HAVE_ONLY_DMA
static int up_receive(struct uart_dev_s *dev, uint32_t *status);
static void up_rxint(struct uart_dev_s *dev, bool enable);
static bool up_rxavailable(struct uart_dev_s *dev);
#endif
static void up_send(struct uart_dev_s *dev, int ch);
static void up_txint(struct uart_dev_s *dev, bool enable);
static bool up_txready(struct uart_dev_s *dev);
#ifdef SERIAL_HAVE_DMA
static int up_dma_setup(struct uart_dev_s *dev);
static void up_dma_shutdown(struct uart_dev_s *dev);
static int up_dma_receive(struct uart_dev_s *dev, uint32_t *status);
static void up_dma_rxint(struct uart_dev_s *dev, bool enable);
static bool up_dma_rxavailable(struct uart_dev_s *dev);
static void up_dma_rxcallback(DMA_HANDLE handle, uint8_t status, void *arg);
#endif
#ifdef CONFIG_STM32_USART1
static int up_interrupt_usart1(int irq, void *context);
#endif
@ -163,6 +222,7 @@ static int up_interrupt_usart6(int irq, void *context);
* Private Variables
****************************************************************************/
#ifndef SERIAL_HAVE_ONLY_DMA
static const struct uart_ops_s g_uart_ops =
{
.setup = up_setup,
@ -178,32 +238,74 @@ static const struct uart_ops_s g_uart_ops =
.txready = up_txready,
.txempty = up_txready,
};
#endif
#ifdef SERIAL_HAVE_DMA
static const struct uart_ops_s g_uart_dma_ops =
{
.setup = up_dma_setup,
.shutdown = up_dma_shutdown,
.attach = up_attach,
.detach = up_detach,
.ioctl = up_ioctl,
.receive = up_dma_receive,
.rxint = up_dma_rxint,
.rxavailable = up_dma_rxavailable,
.send = up_send,
.txint = up_txint,
.txready = up_txready,
.txempty = up_txready,
};
#endif
/* I/O buffers */
#ifdef CONFIG_STM32_USART1
static char g_usart1rxbuffer[CONFIG_USART1_RXBUFSIZE];
static char g_usart1txbuffer[CONFIG_USART1_TXBUFSIZE];
# ifdef CONFIG_USART1_RXDMA
static char g_usart1rxfifo[RXDMA_BUFFER_SIZE];
# endif
#endif
#ifdef CONFIG_STM32_USART2
static char g_usart2rxbuffer[CONFIG_USART2_RXBUFSIZE];
static char g_usart2txbuffer[CONFIG_USART2_TXBUFSIZE];
# ifdef CONFIG_USART2_RXDMA
static char g_usart2rxfifo[RXDMA_BUFFER_SIZE];
# endif
#endif
#ifdef CONFIG_STM32_USART3
static char g_usart3rxbuffer[CONFIG_USART3_RXBUFSIZE];
static char g_usart3txbuffer[CONFIG_USART3_TXBUFSIZE];
# ifdef CONFIG_USART3_RXDMA
static char g_usart3rxfifo[RXDMA_BUFFER_SIZE];
# endif
#endif
#ifdef CONFIG_STM32_UART4
static char g_uart4rxbuffer[CONFIG_USART4_RXBUFSIZE];
static char g_uart4txbuffer[CONFIG_USART4_TXBUFSIZE];
# ifdef CONFIG_USART4_RXDMA
static char g_uart4rxfifo[RXDMA_BUFFER_SIZE];
# endif
#endif
#ifdef CONFIG_STM32_UART5
static char g_uart5rxbuffer[CONFIG_USART5_RXBUFSIZE];
static char g_uart5txbuffer[CONFIG_USART5_TXBUFSIZE];
# ifdef CONFIG_USART5_RXDMA
static char g_uart5rxfifo[RXDMA_BUFFER_SIZE];
# endif
#endif
#ifdef CONFIG_STM32_USART6
static char g_usart6rxbuffer[CONFIG_USART6_RXBUFSIZE];
static char g_usart6txbuffer[CONFIG_USART6_TXBUFSIZE];
# ifdef CONFIG_USART6_RXDMA
static char g_usart6rxfifo[RXDMA_BUFFER_SIZE];
# endif
#endif
/* This describes the state of the STM32 USART1 ports. */
@ -226,7 +328,11 @@ static struct up_dev_s g_usart1priv =
.size = CONFIG_USART1_TXBUFSIZE,
.buffer = g_usart1txbuffer,
},
#ifdef CONFIG_USART1_RXDMA
.ops = &g_uart_dma_ops,
#else
.ops = &g_uart_ops,
#endif
.priv = &g_usart1priv,
},
@ -244,6 +350,10 @@ static struct up_dev_s g_usart1priv =
#endif
#ifdef GPIO_USART1_RTS
.rts_gpio = GPIO_USART1_RTS,
#endif
#ifdef CONFIG_USART1_RXDMA
.rxdma_channel = DMAMAP_USART1_RX,
.rxfifo = g_usart1rxfifo,
#endif
.vector = up_interrupt_usart1,
};
@ -269,7 +379,11 @@ static struct up_dev_s g_usart2priv =
.size = CONFIG_USART2_TXBUFSIZE,
.buffer = g_usart2txbuffer,
},
#ifdef CONFIG_USART2_RXDMA
.ops = &g_uart_dma_ops,
#else
.ops = &g_uart_ops,
#endif
.priv = &g_usart2priv,
},
@ -287,6 +401,10 @@ static struct up_dev_s g_usart2priv =
#endif
#ifdef GPIO_USART2_RTS
.rts_gpio = GPIO_USART2_RTS,
#endif
#ifdef CONFIG_USART2_RXDMA
.rxdma_channel = DMAMAP_USART2_RX,
.rxfifo = g_usart2rxfifo,
#endif
.vector = up_interrupt_usart2,
};
@ -312,7 +430,11 @@ static struct up_dev_s g_usart3priv =
.size = CONFIG_USART3_TXBUFSIZE,
.buffer = g_usart3txbuffer,
},
#ifdef CONFIG_USART3_RXDMA
.ops = &g_uart_dma_ops,
#else
.ops = &g_uart_ops,
#endif
.priv = &g_usart3priv,
},
@ -330,6 +452,10 @@ static struct up_dev_s g_usart3priv =
#endif
#ifdef GPIO_USART3_RTS
.rts_gpio = GPIO_USART3_RTS,
#endif
#ifdef CONFIG_USART3_RXDMA
.rxdma_channel = DMAMAP_USART3_RX,
.rxfifo = g_usart3rxfifo,
#endif
.vector = up_interrupt_usart3,
};
@ -355,7 +481,11 @@ static struct up_dev_s g_uart4priv =
.size = CONFIG_USART4_TXBUFSIZE,
.buffer = g_uart4txbuffer,
},
#ifdef CONFIG_USART4_RXDMA
.ops = &g_uart_dma_ops,
#else
.ops = &g_uart_ops,
#endif
.priv = &g_uart4priv,
},
@ -373,6 +503,10 @@ static struct up_dev_s g_uart4priv =
#endif
#ifdef GPIO_USART4_RTS
.rts_gpio = GPIO_UART4_RTS,
#endif
#ifdef CONFIG_USART4_RXDMA
.rxdma_channel = DMAMAP_UART4_RX,
.rxfifo = g_uart4rxfifo,
#endif
.vector = up_interrupt_uart4,
};
@ -398,7 +532,11 @@ static struct up_dev_s g_uart5priv =
.size = CONFIG_USART5_TXBUFSIZE,
.buffer = g_uart5txbuffer,
},
#ifdef CONFIG_USART5_RXDMA
.ops = &g_uart_dma_ops,
#else
.ops = &g_uart_ops,
#endif
.priv = &g_uart5priv,
},
@ -416,6 +554,10 @@ static struct up_dev_s g_uart5priv =
#endif
#ifdef GPIO_USART5_RTS
.rts_gpio = GPIO_UART5_RTS,
#endif
#ifdef CONFIG_USART5_RXDMA
.rxdma_channel = DMAMAP_UART5_RX,
.rxfifo = g_uart5rxfifo,
#endif
.vector = up_interrupt_uart5,
};
@ -441,7 +583,11 @@ static struct up_dev_s g_usart6priv =
.size = CONFIG_USART6_TXBUFSIZE,
.buffer = g_usart6txbuffer,
},
#ifdef CONFIG_USART6_RXDMA
.ops = &g_uart_dma_ops,
#else
.ops = &g_uart_ops,
#endif
.priv = &g_usart6priv,
},
@ -459,6 +605,10 @@ static struct up_dev_s g_usart6priv =
#endif
#ifdef GPIO_USART6_RTS
.rts_gpio = GPIO_USART6_RTS,
#endif
#ifdef CONFIG_USART6_RXDMA
.rxdma_channel = DMAMAP_USART6_RX,
.rxfifo = g_usart6rxfifo,
#endif
.vector = up_interrupt_usart6,
};
@ -580,6 +730,26 @@ static inline void up_disableusartint(struct up_dev_s *priv, uint16_t *ie)
up_restoreusartint(priv, 0);
}
/****************************************************************************
* Name: up_dma_nextrx
*
* Description:
* Returns the index into the RX FIFO where the DMA will place the next
* byte that it receives.
*
****************************************************************************/
#ifdef SERIAL_HAVE_DMA
static int up_dma_nextrx(struct up_dev_s *priv)
{
size_t dmaresidual;
dmaresidual = stm32_dmaresidual(priv->rxdma);
return (RXDMA_BUFFER_SIZE - (int)dmaresidual);
}
#endif
/****************************************************************************
* Name: up_setup
*
@ -655,6 +825,7 @@ static int up_setup(struct uart_dev_s *dev)
{
regval |= USART_CR1_PCE;
}
up_serialout(priv, STM32_USART_CR1_OFFSET, regval);
/* Configure CR3 */
@ -709,6 +880,71 @@ static int up_setup(struct uart_dev_s *dev)
return OK;
}
/****************************************************************************
* Name: up_dma_setup
*
* Description:
* Configure the USART baud, bits, parity, etc. This method is called the
* first time that the serial port is opened.
*
****************************************************************************/
#ifdef SERIAL_HAVE_DMA
static int up_dma_setup(struct uart_dev_s *dev)
{
struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
int result;
uint32_t regval;
/* Do the basic UART setup first */
result = up_setup(dev);
if (result != OK)
{
return result;
}
/* Acquire the DMA channel. This should always succeed. */
priv->rxdma = stm32_dmachannel(priv->rxdma_channel);
/* Configure for circular DMA reception into the RX fifo */
stm32_dmasetup(priv->rxdma,
priv->usartbase + STM32_USART_DR_OFFSET,
(uint32_t)priv->rxfifo,
RXDMA_BUFFER_SIZE,
DMA_SCR_DIR_P2M |
DMA_SCR_CIRC |
DMA_SCR_MINC |
DMA_SCR_PSIZE_8BITS |
DMA_SCR_MSIZE_8BITS |
DMA_SCR_PBURST_SINGLE |
DMA_SCR_MBURST_SINGLE);
/* Reset our DMA shadow pointer to match the address just
* programmed above.
*/
priv->rxdmanext = 0;
/* Enable receive DMA for the UART */
regval = up_serialin(priv, STM32_USART_CR3_OFFSET);
regval |= USART_CR3_DMAR;
up_serialout(priv, STM32_USART_CR3_OFFSET, regval);
/* Start the DMA channel, and arrange for callbacks at the half and
* full points in the FIFO. This ensures that we have half a FIFO
* worth of time to claim bytes before they are overwritten.
*/
stm32_dmastart(priv->rxdma, up_dma_rxcallback, (void *)priv, true);
return OK;
}
#endif
/****************************************************************************
* Name: up_shutdown
*
@ -734,6 +970,35 @@ static void up_shutdown(struct uart_dev_s *dev)
up_serialout(priv, STM32_USART_CR1_OFFSET, regval);
}
/****************************************************************************
* Name: up_dma_shutdown
*
* Description:
* Disable the USART. This method is called when the serial
* port is closed
*
****************************************************************************/
#ifdef SERIAL_HAVE_DMA
static void up_dma_shutdown(struct uart_dev_s *dev)
{
struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
/* Perform the normal UART shutdown */
up_shutdown(dev);
/* Stop the DMA channel */
stm32_dmastop(priv->rxdma);
/* Release the DMA channel */
stm32_dmafree(priv->rxdma);
priv->rxdma = NULL;
}
#endif
/****************************************************************************
* Name: up_attach
*
@ -951,6 +1216,7 @@ static int up_ioctl(struct file *filep, int cmd, unsigned long arg)
*
****************************************************************************/
#ifndef SERIAL_HAVE_ONLY_DMA
static int up_receive(struct uart_dev_s *dev, uint32_t *status)
{
struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
@ -969,6 +1235,7 @@ static int up_receive(struct uart_dev_s *dev, uint32_t *status)
return dr & 0xff;
}
#endif
/****************************************************************************
* Name: up_rxint
@ -978,6 +1245,7 @@ static int up_receive(struct uart_dev_s *dev, uint32_t *status)
*
****************************************************************************/
#ifndef SERIAL_HAVE_ONLY_DMA
static void up_rxint(struct uart_dev_s *dev, bool enable)
{
struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
@ -1025,6 +1293,7 @@ static void up_rxint(struct uart_dev_s *dev, bool enable)
up_restoreusartint(priv, ie);
irqrestore(flags);
}
#endif
/****************************************************************************
* Name: up_rxavailable
@ -1034,11 +1303,90 @@ static void up_rxint(struct uart_dev_s *dev, bool enable)
*
****************************************************************************/
#ifndef SERIAL_HAVE_ONLY_DMA
static bool up_rxavailable(struct uart_dev_s *dev)
{
struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
return ((up_serialin(priv, STM32_USART_SR_OFFSET) & USART_SR_RXNE) != 0);
}
#endif
/****************************************************************************
* Name: up_dma_receive
*
* Description:
* Called (usually) from the interrupt level to receive one
* character from the USART. Error bits associated with the
* receipt are provided in the return 'status'.
*
****************************************************************************/
#ifdef SERIAL_HAVE_DMA
static int up_dma_receive(struct uart_dev_s *dev, uint32_t *status)
{
struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
int c = 0;
if (up_dma_nextrx(priv) != priv->rxdmanext)
{
c = priv->rxfifo[priv->rxdmanext];
priv->rxdmanext++;
if (priv->rxdmanext == RXDMA_BUFFER_SIZE)
{
priv->rxdmanext = 0;
}
}
return c;
}
#endif
/****************************************************************************
* Name: up_dma_rxint
*
* Description:
* Call to enable or disable RX interrupts
*
****************************************************************************/
#ifdef SERIAL_HAVE_DMA
static void up_dma_rxint(struct uart_dev_s *dev, bool enable)
{
struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
/* En/disable DMA reception.
*
* Note that it is not safe to check for available bytes and immediately
* pass them to uart_recvchars as that could potentially recurse back
* to us again. Instead, bytes must wait until the next up_dma_poll or
* DMA event.
*/
priv->rxenable = enable;
}
#endif
/****************************************************************************
* Name: up_dma_rxavailable
*
* Description:
* Return true if the receive register is not empty
*
****************************************************************************/
#ifdef SERIAL_HAVE_DMA
static bool up_dma_rxavailable(struct uart_dev_s *dev)
{
struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
/* Compare our receive pointer to the current DMA pointer, if they
* do not match, then there are bytes to be received.
*/
return (up_dma_nextrx(priv) != priv->rxdmanext);
}
#endif
/****************************************************************************
* Name: up_send
@ -1163,6 +1511,28 @@ static int up_interrupt_usart6(int irq, void *context)
return up_interrupt_common(&g_usart6priv);
}
#endif
/****************************************************************************
* Name: up_dma_rxcallback
*
* Description:
* This function checks the current DMA state and calls the generic
* serial stack when bytes appear to be available.
*
****************************************************************************/
#ifdef SERIAL_HAVE_DMA
static void up_dma_rxcallback(DMA_HANDLE handle, uint8_t status, void *arg)
{
struct up_dev_s *priv = (struct up_dev_s*)arg;
if (priv->rxenable && up_dma_rxavailable(&priv->dev))
{
uart_recvchars(&priv->dev);
}
}
#endif
#endif /* HAVE UART */
/****************************************************************************
@ -1246,6 +1616,70 @@ void up_serialinit(void)
#endif /* HAVE UART */
}
/****************************************************************************
* Name: stm32_serial_dma_poll
*
* Description:
* Checks receive DMA buffers for received bytes that have not accumulated
* to the point where the DMA half/full interrupt has triggered.
*
* This function should be called from a timer or other periodic context.
*
****************************************************************************/
#ifdef SERIAL_HAVE_DMA
void stm32_serial_dma_poll(void)
{
irqstate_t flags;
flags = irqsave();
#ifdef CONFIG_USART1_RXDMA
if (g_usart1priv.rxdma != NULL)
{
up_dma_rxcallback(g_usart1priv.rxdma, 0, &g_usart1priv);
}
#endif
#ifdef CONFIG_USART2_RXDMA
if (g_usart2priv.rxdma != NULL)
{
up_dma_rxcallback(g_usart2priv.rxdma, 0, &g_usart2priv);
}
#endif
#ifdef CONFIG_USART3_RXDMA
if (g_usart3priv.rxdma != NULL)
{
up_dma_rxcallback(g_usart3priv.rxdma, 0, &g_usart3priv);
}
#endif
#ifdef CONFIG_USART4_RXDMA
if (g_uart4priv.rxdma != NULL)
{
up_dma_rxcallback(g_uart4priv.rxdma, 0, &g_uart4priv);
}
#endif
#ifdef CONFIG_USART5_RXDMA
if (g_uart5priv.rxdma != NULL)
{
up_dma_rxcallback(g_uart5priv.rxdma, 0, &g_uart5priv);
}
#endif
#ifdef CONFIG_USART6_RXDMA
if (g_usart6priv.rxdma != NULL)
{
up_dma_rxcallback(g_usart6priv.rxdma, 0, &g_usart6priv);
}
#endif
irqrestore(flags);
}
#endif
/****************************************************************************
* Name: up_putc
*

View File

@ -532,6 +532,9 @@ static inline void spi_dmarxwakeup(FAR struct stm32_spidev_s *priv)
static void spi_dmarxcallback(DMA_HANDLE handle, uint8_t isr, void *arg)
{
FAR struct stm32_spidev_s *priv = (FAR struct stm32_spidev_s *)arg;
/* Wake-up the SPI driver */
priv->rxresult = isr | 0x080; /* OR'ed with 0x80 to assure non-zero */
spi_dmarxwakeup(priv);
}
@ -549,6 +552,9 @@ static void spi_dmarxcallback(DMA_HANDLE handle, uint8_t isr, void *arg)
static void spi_dmatxcallback(DMA_HANDLE handle, uint8_t isr, void *arg)
{
FAR struct stm32_spidev_s *priv = (FAR struct stm32_spidev_s *)arg;
/* Wake-up the SPI driver */
priv->txresult = isr | 0x080; /* OR'ed with 0x80 to assure non-zero */
spi_dmatxwakeup(priv);
}

View File

@ -1,7 +1,7 @@
/************************************************************************************
* arch/arm/src/stm32/stm32_uart.h
*
* Copyright (C) 2009 Gregory Nutt. All rights reserved.
* Copyright (C) 2009, 2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@ -48,6 +48,163 @@
/************************************************************************************
* Pre-processor Definitions
************************************************************************************/
/* Make sure that we have not enabled more U[S]ARTs than are support by
* the device.
*/
#if STM32_NUSART < 6
# undef CONFIG_STM32_USART6
#endif
#if STM32_NUSART < 5
# undef CONFIG_STM32_UART5
#endif
#if STM32_NUSART < 4
# undef CONFIG_STM32_UART4
#endif
#if STM32_NUSART < 3
# undef CONFIG_STM32_USART3
#endif
#if STM32_NUSART < 2
# undef CONFIG_STM32_USART2
#endif
#if STM32_NUSART < 1
# undef CONFIG_STM32_USART1
#endif
/* Is there a USART enabled? */
#if defined(CONFIG_STM32_USART1) || defined(CONFIG_STM32_USART2) || \
defined(CONFIG_STM32_USART3) || defined(CONFIG_STM32_UART4) || \
defined(CONFIG_STM32_UART5) || defined(CONFIG_STM32_USART6)
# define HAVE_UART 1
#endif
/* Is there a serial console? */
#if defined(CONFIG_USART1_SERIAL_CONSOLE) && defined(CONFIG_STM32_USART1)
# undef CONFIG_USART2_SERIAL_CONSOLE
# undef CONFIG_USART3_SERIAL_CONSOLE
# undef CONFIG_UART4_SERIAL_CONSOLE
# undef CONFIG_UART5_SERIAL_CONSOLE
# undef CONFIG_USART6_SERIAL_CONSOLE
# define CONSOLE_UART 1
# define HAVE_CONSOLE 1
#elif defined(CONFIG_USART2_SERIAL_CONSOLE) && defined(CONFIG_STM32_USART2)
# undef CONFIG_USART1_SERIAL_CONSOLE
# undef CONFIG_USART3_SERIAL_CONSOLE
# undef CONFIG_USART4_SERIAL_CONSOLE
# undef CONFIG_USART5_SERIAL_CONSOLE
# undef CONFIG_USART6_SERIAL_CONSOLE
# define CONSOLE_UART 2
# define HAVE_CONSOLE 1
#elif defined(CONFIG_USART3_SERIAL_CONSOLE) && defined(CONFIG_STM32_USART3)
# undef CONFIG_USART1_SERIAL_CONSOLE
# undef CONFIG_USART2_SERIAL_CONSOLE
# undef CONFIG_UART4_SERIAL_CONSOLE
# undef CONFIG_UART5_SERIAL_CONSOLE
# undef CONFIG_USART6_SERIAL_CONSOLE
# define CONSOLE_UART 3
# define HAVE_CONSOLE 1
#elif defined(CONFIG_USART4_SERIAL_CONSOLE) && defined(CONFIG_STM32_UART4)
# undef CONFIG_USART1_SERIAL_CONSOLE
# undef CONFIG_USART2_SERIAL_CONSOLE
# undef CONFIG_USART3_SERIAL_CONSOLE
# undef CONFIG_UART5_SERIAL_CONSOLE
# undef CONFIG_USART6_SERIAL_CONSOLE
# define CONSOLE_UART 4
# define HAVE_CONSOLE 1
#elif defined(CONFIG_USART5_SERIAL_CONSOLE) && defined(CONFIG_STM32_UART5)
# undef CONFIG_USART1_SERIAL_CONSOLE
# undef CONFIG_USART2_SERIAL_CONSOLE
# undef CONFIG_USART3_SERIAL_CONSOLE
# undef CONFIG_UART4_SERIAL_CONSOLE
# undef CONFIG_USART6_SERIAL_CONSOLE
# define CONSOLE_UART 5
# define HAVE_CONSOLE 1
#elif defined(CONFIG_USART6_SERIAL_CONSOLE) && defined(CONFIG_STM32_USART6)
# undef CONFIG_USART1_SERIAL_CONSOLE
# undef CONFIG_USART2_SERIAL_CONSOLE
# undef CONFIG_USART3_SERIAL_CONSOLE
# undef CONFIG_UART4_SERIAL_CONSOLE
# undef CONFIG_UART5_SERIAL_CONSOLE
# define CONSOLE_UART 6
# define HAVE_CONSOLE 1
#else
# undef CONFIG_USART1_SERIAL_CONSOLE
# undef CONFIG_USART2_SERIAL_CONSOLE
# undef CONFIG_USART3_SERIAL_CONSOLE
# undef CONFIG_UART4_SERIAL_CONSOLE
# undef CONFIG_UART5_SERIAL_CONSOLE
# undef CONFIG_USART6_SERIAL_CONSOLE
# define CONSOLE_UART 0
# undef HAVE_CONSOLE
#endif
/* DMA support is only provided if CONFIG_ARCH_DMA is in the NuttX configuration.
* Furthermore, DMA support is currently only implemented for the F4 (but could be
* extended to the F1 and F2 with a little effort in the DMA code.
*/
#if !defined(HAVE_UART) || !defined(CONFIG_ARCH_DMA) || !defined(CONFIG_STM32_STM32F40XX)
# undef CONFIG_USART1_RXDMA
# undef CONFIG_USART2_RXDMA
# undef CONFIG_USART3_RXDMA
# undef CONFIG_USART4_RXDMA
# undef CONFIG_USART5_RXDMA
# undef CONFIG_USART6_RXDMA
#endif
/* Disable the DMA configuration on all unused USARTs */
#ifndef CONFIG_STM32_USART1
# undef CONFIG_USART1_RXDMA
#endif
#ifndef CONFIG_STM32_USART2
# undef CONFIG_USART2_RXDMA
#endif
#ifndef CONFIG_STM32_USART3
# undef CONFIG_USART3_RXDMA
#endif
#ifndef CONFIG_STM32_USART4
# undef CONFIG_USART4_RXDMA
#endif
#ifndef CONFIG_STM32_USART5
# undef CONFIG_USART5_RXDMA
#endif
#ifndef CONFIG_STM32_USART6
# undef CONFIG_USART6_RXDMA
#endif
/* Is DMA available on any (enabled) USART? */
#undef SERIAL_HAVE_DMA
#if defined(CONFIG_USART1_RXDMA) || defined(CONFIG_USART2_RXDMA) || \
defined(CONFIG_USART3_RXDMA) || defined(CONFIG_USART4_RXDMA) || \
defined(CONFIG_USART5_RXDMA) || defined(CONFIG_USART6_RXDMA)
# define SERIAL_HAVE_DMA 1
#endif
/* Is DMA used on all (enabled) USARTs */
#define SERIAL_HAVE_ONLY_DMA 1
#if defined(CONFIG_STM32_USART1) && !defined(CONFIG_USART1_RXDMA)
# undef SERIAL_HAVE_ONLY_DMA
#elif defined(CONFIG_STM32_USART2) && !defined(CONFIG_USART2_RXDMA)
# undef SERIAL_HAVE_ONLY_DMA
#elif defined(CONFIG_STM32_USART3) && !defined(CONFIG_USART3_RXDMA)
# undef SERIAL_HAVE_ONLY_DMA
#elif defined(CONFIG_STM32_UART4) && !defined(CONFIG_USART4_RXDMA)
# undef SERIAL_HAVE_ONLY_DMA
#elif defined(CONFIG_STM32_UART5) && !defined(CONFIG_USART5_RXDMA)
# undef SERIAL_HAVE_ONLY_DMA
#elif defined(CONFIG_STM32_USART6) && !defined(CONFIG_USART6_RXDMA)
# undef SERIAL_HAVE_ONLY_DMA
#endif
/************************************************************************************
* Public Types
@ -57,8 +214,41 @@
* Public Data
************************************************************************************/
#ifndef __ASSEMBLY__
#undef EXTERN
#if defined(__cplusplus)
#define EXTERN extern "C"
extern "C" {
#else
#define EXTERN extern
#endif
/************************************************************************************
* Public Functions
************************************************************************************/
/****************************************************************************
* Name: stm32_serial_dma_poll
*
* Description:
* Must be called periodically if any STM32 UART is configured for DMA.
* The DMA callback is triggered for each fifo size/2 bytes, but this can
* result in some bytes being transferred but not collected if the incoming
* data is not a whole multiple of half the FIFO size.
*
* May be safely called from either interrupt or thread context.
*
****************************************************************************/
#ifdef SERIAL_HAVE_DMA
EXTERN void stm32_serial_dma_poll(void);
#endif
#undef EXTERN
#if defined(__cplusplus)
}
#endif
#endif /* __ASSEMBLY__ */
#endif /* __ARCH_ARM_STC_STM32_STM32_UART_H */

View File

@ -94,6 +94,7 @@ struct stm32_dma_s
uint8_t irq; /* DMA stream IRQ number */
uint8_t shift; /* ISR/IFCR bit shift value */
uint8_t channel; /* DMA channel number (0-7) */
bool nonstop; /* Stream is configured in a non-stopping mode. */
sem_t sem; /* Used to wait for DMA channel to become available */
uint32_t base; /* DMA register channel base address */
dma_callback_t callback; /* Callback invoked when the DMA completes */
@ -429,9 +430,20 @@ static int stm32_dmainterrupt(int irq, void *context)
status = (dmabase_getreg(dmast, regoffset) >> dmast->shift) & DMA_STREAM_MASK;
/* Disable the DMA stream */
/* Clear fetched stream interrupts by setting bits in the upper or lower IFCR
* register
*/
stm32_dmastreamdisable(dmast);
if (stream < 4)
{
regoffset = STM32_DMA_LIFCR_OFFSET;
}
else
{
regoffset = STM32_DMA_HIFCR_OFFSET;
}
dmabase_putreg(dmast, regoffset, (status << dmast->shift));
/* Invoke the callback */
@ -636,11 +648,15 @@ void stm32_dmasetup(DMA_HANDLE handle, uint32_t paddr, uint32_t maddr,
/* "Set the memory address in the DMA_SM0ARx ... register. The data will be
* written to or read from this memory after the peripheral event."
*
* Note that only single-buffer mode is currently supported so SM1ARx
* is not used."
* Note that in double-buffered mode it is explicitly assumed that the second
* buffer immediately follows the first.
*/
dmast_putreg(dmast, STM32_DMA_SM0AR_OFFSET, maddr);
if (scr & DMA_SCR_DBM)
{
dmast_putreg(dmast, STM32_DMA_SM1AR_OFFSET, maddr + ntransfers);
}
/* "Configure the total number of data items to be transferred in the
* DMA_SNDTRx register. After each peripheral event, this value will be
@ -677,28 +693,42 @@ void stm32_dmasetup(DMA_HANDLE handle, uint32_t paddr, uint32_t maddr,
* generated when the stream is enabled, then the stream will be automatically
* disabled."
*
* The FIFO is disabled in circular mode when transferring data from a
* peripheral to memory, as in this case it is usually desirable to know that
* every byte from the peripheral is transferred immediately to memory. It is
* not practical to flush the DMA FIFO, as this requires disabling the channel
* which triggers the transfer-complete interrupt.
*
* NOTE: The FEIFx error interrupt is not enabled because the FEIFx seems to
* be reported spuriously causing good transfers to be marked as failures.
*/
regval = dmast_getreg(dmast, STM32_DMA_SFCR_OFFSET);
regval &= ~(DMA_SFCR_FTH_MASK | DMA_SFCR_FS_MASK | DMA_SFCR_FEIE);
if (!((scr & (DMA_SCR_CIRC | DMA_SCR_DIR_MASK)) == (DMA_SCR_CIRC | DMA_SCR_DIR_P2M)))
{
regval |= (DMA_SFCR_FTH_FULL | DMA_SFCR_DMDIS);
}
dmast_putreg(dmast, STM32_DMA_SFCR_OFFSET, regval);
/* "Configure data transfer direction, circular mode, peripheral & memory
* incremented mode, peripheral & memory data size, and interrupt after
* half and/or full transfer in the DMA_CCRx register."
*
* Note: The CT bit is always reset.
*/
regval = dmast_getreg(dmast, STM32_DMA_SCR_OFFSET);
regval &= ~(DMA_SCR_PFCTRL|DMA_SCR_DIR_MASK|DMA_SCR_PINC|DMA_SCR_MINC|
DMA_SCR_PSIZE_MASK|DMA_SCR_MSIZE_MASK|DMA_SCR_PINCOS|
DMA_SCR_CIRC|DMA_SCR_DBM|DMA_SCR_CT|
DMA_SCR_PBURST_MASK|DMA_SCR_MBURST_MASK);
scr &= (DMA_SCR_PFCTRL|DMA_SCR_DIR_MASK|DMA_SCR_PINC|DMA_SCR_MINC|
DMA_SCR_PSIZE_MASK|DMA_SCR_MSIZE_MASK|DMA_SCR_PINCOS|
DMA_SCR_DBM|DMA_SCR_CIRC|
DMA_SCR_PBURST_MASK|DMA_SCR_MBURST_MASK);
regval |= scr;
dmast->nonstop = (scr & (DMA_SCR_DBM|DMA_SCR_CIRC)) != 0;
dmast_putreg(dmast, STM32_DMA_SCR_OFFSET, regval);
}
@ -734,6 +764,8 @@ void stm32_dmastart(DMA_HANDLE handle, dma_callback_t callback, void *arg, bool
scr = dmast_getreg(dmast, STM32_DMA_SCR_OFFSET);
scr |= DMA_SCR_EN;
if (!dmast->nonstop)
{
/* Once half of the bytes are transferred, the half-transfer flag (HTIF) is
* set and an interrupt is generated if the Half-Transfer Interrupt Enable
* bit (HTIE) is set. At the end of the transfer, the Transfer Complete Flag
@ -742,6 +774,18 @@ void stm32_dmastart(DMA_HANDLE handle, dma_callback_t callback, void *arg, bool
*/
scr |= (half ? (DMA_SCR_HTIE|DMA_SCR_TEIE) : (DMA_SCR_TCIE|DMA_SCR_TEIE));
}
else
{
/* In nonstop mode, when the transfer completes it immediately resets
* and starts again. The transfer-complete interrupt is thus always
* enabled, and the half-complete interrupt can be used in circular
* mode to determine when the buffer is half-full, or in double-buffered
* mode to determine when one of the two buffers is full.
*/
scr |= (half ? DMA_SCR_HTIE : 0) | DMA_SCR_TCIE | DMA_SCR_TEIE;
}
dmast_putreg(dmast, STM32_DMA_SCR_OFFSET, scr);
}
@ -764,6 +808,38 @@ void stm32_dmastop(DMA_HANDLE handle)
stm32_dmastreamdisable(dmast);
}
/****************************************************************************
* Name: stm32_dmaresidual
*
* Description:
* Read the DMA bytes-remaining register.
*
* Assumptions:
* - DMA handle allocated by stm32_dmachannel()
*
****************************************************************************/
size_t stm32_dmaresidual(DMA_HANDLE handle)
{
struct stm32_dma_s *dmast = (struct stm32_dma_s *)handle;
uint32_t residual;
/* Fetch the count of bytes remaining to be transferred.
*
* If the FIFO is enabled, this count may be inaccurate. ST don't
* appear to document whether this counts the peripheral or the memory
* side of the channel, and they don't make the memory pointer
* available either.
*
* For reception in circular mode the FIFO is disabled in order that
* this value can be useful.
*/
residual = dmast_getreg(dmast, STM32_DMA_SNDTR_OFFSET);
return (size_t)residual;
}
/****************************************************************************
* Name: stm32_dmasample
*

View File

@ -660,7 +660,7 @@ config PIC32MX_UART2PRIO
---help---
UART 2. Range 4-31, Default 16.
config PIC32MX_CN
config PIC32MX_CNPRIO
int "CN"
default 16
depends on PIC32MX_CN

View File

@ -266,9 +266,16 @@ config ARCH_BOARD_PIC32_STARTERKIT
bool "Microchip PIC32 Ethernet Starter Kit (DM320004)"
depends on ARCH_CHIP_PIC32MX795F512L
---help---
This README file discusses the port of NuttX to the Microchip PIC32 Ethernet
Starter Kit (DM320004) with the Multimedia Expansion Board (MEB, DM320005).
Advanced USB Storage. See www.microchip.com for further information.
This is the port of NuttX to the Microchip PIC32 Ethernet Starter Kit
(DM320004) with the Multimedia Expansion Board (MEB, DM320005).
See www.microchip.com for further information.
config ARCH_BOARD_PIC32_PIC32MXMMB
bool "Mikroelektronika PIC32MX7 MMB"
depends on ARCH_CHIP_PIC32MX795F512L
---help---
This is the port NuttX to the Mikroelektronika PIC32MX7 Multimedia Board
(MMB). See http://www.mikroe.com/ for further information.
config ARCH_BOARD_PJRC_87C52
bool "PJRC 87C52 development system"
@ -524,6 +531,7 @@ source "configs/olimex-lpc2378/Kconfig"
source "configs/olimex-strp711/Kconfig"
source "configs/pcblogic-pic32mx/Kconfig"
source "configs/pic32-starterkit/Kconfig"
source "configs/pic32mx7mmb/Kconfig"
source "configs/pjrc-8051/Kconfig"
source "configs/qemu-i486/Kconfig"
source "configs/rgmp/Kconfig"

View File

@ -1486,9 +1486,18 @@ configs/pcblogic-pic32mx
configs/pic32-starterkit
This README file discusses the port of NuttX to the Microchip PIC32 Ethernet
This directory contains the port of NuttX to the Microchip PIC32 Ethernet
Starter Kit (DM320004) with the Multimedia Expansion Board (MEB, DM320005).
Advanced USB Storage. See www.microchip.com for further information.
See www.microchip.com for further information.
configs/pic32mx7mmb
This directory will (eventually) contain the port of NuttX to the
Mikroelektronika PIC32MX7 Multimedia Board (MMB). See
http://www.mikroe.com/ for further information.
On initial check-in, this directory is just a clone of the PIC32 starter
kit port with the appropriate naming changes. More to come.
configs/pjrc-8051
8051 Microcontroller. This port uses the PJRC 87C52 development system

View File

@ -0,0 +1,4 @@
#
# For a description of the syntax of this configuration file,
# see misc/tools/kconfig-language.txt.
#

View File

@ -0,0 +1,826 @@
configs/pic32mx7mmb README
===============================
This README file discusses the port of NuttX to the Mikroelektronika PIC32MX7
Multimedia Board (MMB)
Contents
========
PIC32MX795F512L Pin Out
Toolchains
Creating Compatible NuttX HEX files
Serial Console
LEDs
PIC32MX Configuration Options
Configurations
PIC32MX795F512L Pin Out
=======================
[This current pin-out is for the PIC32 Starter Kit and still needs to be
updated for the Mikroelektronika PIC32MX7 MMB]
LEFT SIDE, TOP-TO-BOTTOM (if pin 1 is in upper left)
--- ---------------------------------- -------------------------- -----------------------------------------------
PIN CONFIGURATIONS SIGNAL NAME ON-BOARD CONNECTIONS
(Family Data Sheet Table 1-1) (Starter Kit User Guide)
--- ---------------------------------- -------------------------- -----------------------------------------------
1 RG15/AERXERR ERXERR Ethernet RX_ER/MDIX_IN
2 VDD P32_VDD ---
3 PMD5/RE5 PMPD5/RE5 J2 pin 13
4 PMD6/RE6 PMPD6/RE6 J2 pin 9
5 PMD7/RE7 PMPD7/RE7 J2 pin 7
6 RC1/T2CK T2CLK/RC1 J2 pin 35 (timer)
7 RC2/AC2TX/T3CK T3CLK/RC2 J2 pin 37 (timer)
8 RC3/AC2RX/T4CK T4CLK/RC3 J2 pin 39 (timer)
9 RC4/SDI1/T5CK SDI1/T4CLK/RC4 J2 pin 41 (timer)
J2 pin 93 (SPI1)
10 PMA5/CN8/ECOL/RG6/SCK2/U3RTS/U6TX PMPA5/SCM2C/CN8/RG6 J2 pin 45 (SPI2)
J2 pin 117 (PMP address)
11 PMA4/CN9/ECRS/RG7/SDA4/SDI2/U3RX PMPA4/SCM2A/CN9/RG7 J2 pin 47 (SPI2)
J2 pin 119 (PMP address)
12 PMA3/AECRSDV/AERXDV/CN10/ECRSDV/ ECRS_DV Ethernet CRS/CRS_DV/LED_CFG
ERXDV/RG8/SCL4/SDO2/U3TX
13 MCLR PIC32_MCLR (pulled up)
PIC32MX440F512H debug processor
J2 pin 130 (ICSP)
14 PMA2/AEREFCLK/AERXCLK/CN11/ EREF_CLK 50MHz clock, Ethernet X1
EREFCLK/ERXCLK/RG9/SS2/U3CTS/
U6RX
15 VSS (grounded) ---
16 VDD P32_VDD ---
17 RA0/TMS TMS/RA0 J2 pin 126 (JTAG/GPIO)
18 AERXD0/INT1/RE8 ERXD0(2) Ethernet RXD_0/PHYAD1
19 AERXD1/INT2/RE9 ERXD1(2) Ethernet RXD_1/PHYAD2
20 AN5/C1IN+/CN7/RB5/VBUSON VBUSON/C1IN+/AN5/CN7/RB5 USB host power supply, TPS20x1B ~EN,
Low enables power to host port (J4)
USB OTG power supply, MCP1253_MSOP ~SHDN
Enables power to device/OTG port (J5)
J2 pin 63 (comparator 1)
J2 pin 62 (A/D)
21 AN4/C1IN-/CN6/RB4 USBOEN/C1IN-/AN4/CN6/RB4 J2 pin 65 (comparator 1)
J2 pin 64 (A/D)
22 AN3/C2IN+/CN5/RB3 C2IN+/AN3/CN5/RB3 TPS20x1B ~OC, sense host port power
MCP1253_MSOP PGOOD, sense device/OTG port power
J2 pin 67 (comparator 2)
J2 pin 66 (A/D)
23 AN2/C2IN-/CN4/RB2 C2IN-/AN2/CN4/RB2 J2 pin 69 (comparator 2)
J2 pin 101
J2 pin 68 (A/D)
24 AN1/CN3/PGEC1/RB1 PGC1/AN1/CN3/RB1 J2 pin 70 (A/D)
25 AN0/CN2/PGED1/RB0 PGD1/AN0/CN2/RB0 J2 pin 72 (A/D)
BOTTOM SIDE, LEFT-TO-RIGHT (if pin 1 is in upper left)
--- ---------------------------------- -------------------------- -----------------------------------------------
PIN CONFIGURATIONS SIGNAL NAME ON-BOARD CONNECTIONS
(Family Data Sheet Table 1-1) (Starter Kit User Guide)
--- ---------------------------------- -------------------------- -----------------------------------------------
26 AN6/OCFA/PGEC2/RB6 PIC32_PGC2 PIC32MX440F512H debug processor
J2 pin 128 (ICSP)
27 AN7/PGED2/RB7 PIC32_PGD2/DBG_SD0 PIC32MX440F512H debug processor
J2 pin 132 (ICSP)
28 PMA7/AERXD2/CVREF-/RA9 PMPA7/VREF-/RA9 J2 pin 113 (PMP address)
J2 pin 114 (A/D ref)
29 PMA6/AERXD3/CVREF+/RA10/VREF+ PMPA6/VREF+/RA10 J2 pin 115 (PMP address)
J2 pin 116 (A/D ref)
30 AVDD P32_VDD ---
31 AVSS (grounded) ---
32 AN8/C1OUT/RB8 C1OUT/AN8/RB8 J2 pin 71
33 AN9/C2OUT/RB9 C2OUT/AN9/RB9 J2 pin 73
34 PMA13/AN10/RB10/CVREFOUT PMPA13/CVREF/AN10 J2 pin 101 (PMP address)
J2 pin 102 (Comparator ref)
35 PMA12/AETXERR/AN11/ERXERR/RB11 PMPA12/AN11/RB11 J2 pin 103 (PMP address)
36 VSS (grounded) ---
37 VDD P32_VDD ---
38 RA1/TCK TCK/RA1 PIC32MX440F512H debug processor
J2 pin 124 (JTAG/GPIO)
39 AC1TX/RF13/SCK4/U2RTS/U5TX SCM3D/BCLK2/RF13 J2 pin 106 (UART2)
40 AC1RX/RF12/SS4/U2CTS/U5RX SCM3C/RF12 J2 pin 108 (UART2)
41 PMA11/AECRS/AN12/ERXD0/RB12 PMPA11/AN12/RB12 J2 pin 105 (PMP address)
42 PMA10/AECOL/AN13/ERXD1/RB13 PMPA10/AN13/RB13 J2 pin 107 (PMP address)
43 PMA1/AETXD3/AN14/ERXD2/PMALH/RB14 PMPA1/AN14/RB14 J2 pin 127 (PMP address)
44 PMA0/AETXD2/AN15/CN12/ERXD3/OCFB/ PMPA0/AN15/OCFB/CN12 J2 pin 129 (PMP address)
PMALL/RB15 J2 pin 36
45 VSS (grounded) ---
46 VDD P32_VDD ---
47 AETXD0/CN20/RD14/SS3/U1CTS/U4RX EXTD0(2) Ethernet TXD_0
48 AETXD1/CN21/RD15/SCK3/U1RTS/U4TX EXTD1(2) Ethernet TXD_1
49 PMA9/CN17/RF4/SDA5/SDI4/U2RX PMPA9/SCM3A/CN17/RF4 J2 pin 109 (PMP address)
J2 pin 110 (UART2)
50 PMA8/CN18/RF5/SCL5/SDO4/U2TX PMPA8/SCM3B/CN18/RF5 J2 pin 111 (PMP address)
J2 pin 112 (UART2)
RIGHT SIDE, TOP-TO-BOTTOM (if pin 1 is in upper left)
--- ---------------------------------- -------------------------- -----------------------------------------------
PIN CONFIGURATIONS SIGNAL NAME ON-BOARD CONNECTIONS
(Family Data Sheet Table 1-1) (Starter Kit User Guide)
--- ---------------------------------- -------------------------- -----------------------------------------------
75 VSS (grounded)
74 CN0/RC14/SOSCO/T1CK SOSC0/T1CK/CN0/RC14 32kHz Oscillator, J2 pin (timer)
J2 pin 32 (secondary OSC)
73 CN1/RC13/SOSCI SOSC1/CN1/RC13 32kHz Oscillator
J2 pin 32 (secondary OSC)
72 OC1/INT0/RD0/SDO1 SDO1/INT0/OC1/RD0 User LED D4 (high illuminates)
J2 pin 87 (EXT_INT)
J2 pin 95 (SPI1)
J2 pin 46 (OC/PWM)
71 PMA14/AEMDC/EMDC/IC4/PMCS1/RD11 EMDC Ethernet MDC
70 PMA15/IC3/PMCS2/RD10/SCK1 SCK1/IC3/PMPCS2/RD10 J2 pin 29 (PMP control)
J2 pin 91 (SPI1)
J2 pin 52 (input capture)
69 IC2/RD9/SS1 SS1/IC2/RD9 J2 pin 54 (input capture)
68 AEMDIO/EMDIO/IC1/RD8/RTCC EMDIO Ethernet MDIO
67 AETXEN/INT4/RA15/SDA1 ETXEN(2) Ethernet TX_EN
66 AETXCLK/INT3/RA14/SCL1 INT3/SCL1/RA14 Ethernet PWR_DOWN/INT
65 VSS (grounded) ---
64 CLKO/OSC2/RC15 8MHz crystal
63 CLKI/OSC1/RC12 8MHz crystal
62 VDD P32_VDD ---
61 RA5/TDO TDO/RA5 PIC32MX440F512H debug processor
J2 pin 118 (JTAG/GPIO)
60 RA4/TDI TDI/RA4 PIC32MX440F512H debug processor
59 RA3/SDA2 SDA2/RA3 J2 pin 74 (I2C2)
58 RA2/SCL2 SCL2/RA2 J2 pin 76 (I2C2)
57 D+/RG2 D+/RG2 Host port (J4), Device OTG port (J5)
56 D-/RG3 D-/RG3 Host port (J4), Device OTG port (J5)
55 VUSB P32_VDD ---
54 VBUS P32_VBUS ---
53 RF8/SCL3/SDO3/U1TX SCM1B/RF8 J2 pin 90 (UART1)
52 RF2/SDA3/SDI3/U1RX SCM1A/RF2 J2 pin 88 (UART1)
51 RF3/USBID USBID/RF3 Device OTG port (J5)
TOP SIDE, LEFT-TO-RIGHT (if pin 1 is in upper left)
--- ---------------------------------- -------------------------- -----------------------------------------------
PIN CONFIGURATIONS SIGNAL NAME ON-BOARD CONNECTIONS
(Family Data Sheet Table 1-1) (Starter Kit User Guide)
--- ---------------------------------- -------------------------- -----------------------------------------------
100 PMD4/RE4 PMPD4/RE4 J2 pin 15 (PMP data)
99 PMD3/RE3 PMPD3/RE3 J2 pin 17 (PMP data)
98 PMD2/RE2 PMPD2/RE2 J2 pin 19 (PMP data)
97 RG13/TRD0 TRD0/RG13 J2 pin 8 (Trace/GPIO)
96 RG12/TRD1 TRD1/RG12 J2 pin 5
95 RG14/TRD2 TRD2/RG14 J2 pin 3
94 PMD1/RE1 PMPD1/RE1 J2 pin 21 (PMP data)
93 PMD0/RE0 PMPD0/RE0 J2 pin 23 (PMP data)
92 RA7/TRD3 TRD3/RA7 J2 pin 6 (Trace/GPIO)
91 RA6/TRCLK TRCLK/RA6 J2 pin 4 (Trace/GPIO)
90 PMD8/C2RX/RG0 PMPD8/RG0 J2 pin 10 (PMP data)
89 PMD9/C2TX/ETXERR/RG1 PMPD9/RG1 J2 pin 14 (PMP data)
88 PMD10/C1TX/ETXD0/RF1 PMPD10/RF1 J2 pin 16 (PMP data)
87 PMD11/C1RX/ETXD1/RF0 PMPD11/RF0 J2 pin 18 (PMP data)
86 VDD P32_VDD ---
85 VCAP/VCORE (capacitor to ground) ---
84 PMD15/CN16/ETXCLK/RD7 PMPD15/CN16/RD7 Switch SW2 (low when closed)
J2 pin 26 (PMP data)
83 PMD14/CN15/ETXEN/RD6 PMPD14/CN15/RD6 Switch SW1 (low when closed)
J2 pin 24 (PMP data)
82 CN14/PMRD/RD5 PMPRD/CN14/RD5 J2 pin 25
81 CN13/OC5/PMWR/RD4 PMPWR/OC5/C13/RD4 J2 pin 28 (PMP control)
J2 pin 38
80 PMD13/CN19/ETXD3/RD13 CN19/PMPD13/RD13 Switch SW3 (low when closed)
J2 pin 22 (PMP data)
79 PMD12/ETXD2/IC5/RD12 IC5/PMPD12/RD12 J2 pin 20 (PMP data)
J2 pin 48
78 OC4/RD3 OC4/RD3 J2 pin 40 (OC/PWM)
77 OC3/RD2 OC3/RD2 User LED D5 (high illuminates)
J2 pin 42 (OC/PWM)
76 OC2/RD1 OC1/RD1 User LED D6 (high illuminates)
J2 pin 44 (OC/PWM)
Toolchains
==========
I am using the free, LITE version of the PIC32MX toolchain available
for download from the microchip.com web site. I am using the Windows
version. The MicroChip toolchain is the only toolchaing currently
supported in these configurations, but it should be a simple matter to
adapt to other toolchains by modifying the Make.defs file include in
each configuration.
Toolchain Options:
CONFIG_PIC32MX_MICROCHIPW - MicroChip full toolchain for Windows
CONFIG_PIC32MX_MICROCHIPL - MicroChip full toolchain for Linux
CONFIG_PIC32MX_MICROCHIPW_LITE - MicroChip LITE toolchain for Windows
CONFIG_PIC32MX_MICROCHIPL_LITE - MicroChip LITE toolchain for Linux
Windows Native Toolchains
NOTE: There are several limitations to using a Windows based toolchain in a
Cygwin environment. The three biggest are:
1. The Windows toolchain cannot follow Cygwin paths. Path conversions are
performed automatically in the Cygwin makefiles using the 'cygpath' utility
but you might easily find some new path problems. If so, check out 'cygpath -w'
2. Windows toolchains cannot follow Cygwin symbolic links. Many symbolic links
are used in Nuttx (e.g., include/arch). The make system works around these
problems for the Windows tools by copying directories instead of linking them.
But this can also cause some confusion for you: For example, you may edit
a file in a "linked" directory and find that your changes had no effect.
That is because you are building the copy of the file in the "fake" symbolic
directory. If you use a Windows toolchain, you should get in the habit of
making like this:
make clean_context all
An alias in your .bashrc file might make that less painful.
3. Dependencies are not made when using Windows versions of the GCC. This is
because the dependencies are generated using Windows pathes which do not
work with the Cygwin make.
Support has been added for making dependencies with the windows-native toolchains.
That support can be enabled by modifying your Make.defs file as follows:
- MKDEP = $(TOPDIR)/tools/mknulldeps.sh
+ MKDEP = $(TOPDIR)/tools/mkdeps.sh --winpaths "$(TOPDIR)"
If you have problems with the dependency build (for example, if you are not
building on C:), then you may need to modify tools/mkdeps.sh
Powering the Board
==================
[To be provided]
Creating Compatible NuttX HEX files
===================================
Intel Hex Format Files:
-----------------------
When NuttX is built it will produce two files in the top-level NuttX
directory:
1) nuttx - This is an ELF file, and
2) nuttx.hex - This is an Intel Hex format file. This is controlled by
the setting CONFIG_INTELHEX_BINARY in the .config file.
The PICkit tool wants an Intel Hex format file to burn into FLASH. However,
there is a problem with the generated nutt.hex: The tool expects the nuttx.hex
file to contain physical addresses. But the nuttx.hex file generated from the
top-level make will have address in the KSEG0 and KSEG1 regions.
tools/mkpichex:
---------------
There is a simple tool in the configs/pic32mx7mmb/tools directory
that can be used to solve both issues with the nuttx.hex file. But,
first, you must build the the tools:
cd configs/pic32mx7mmb/tools
make
Now you will have an excecutable file call mkpichex (or mkpichex.exe on
Cygwin). This program will take the nutt.hex file as an input, it will
convert all of the KSEG0 and KSEG1 addresses to physical address, and
it will write the modified file, replacing the original nuttx.hex.
To use this file, you need to do the following things:
. ./setenv.sh # Source setenv.sh. Among other this, this script
# will add configs/pic32mx7mmb/tools to your
# PATH variable
make # Build nuttx and nuttx.hex
mkpichex $PWD # Convert addresses in nuttx.hex. $PWD is the path
# to the top-level build directory. It is the only
# required input to mkpichex.
Serial Console
==============
[To be provided]
LEDs
====
[This needs to be updated. This test currently addresses the PIC32 starter kit]
The PIC32MX Ethernet Starter kit has 3 user LEDs labeled LED1-3 on the
board graphics (but referred to as LED4-6 in the schematic):
PIN User's Guide Board Stencil Notes
--- ------------- -------------- -------------------------
RD0 "User LED D4" "LED1 (RD0") High illuminates (RED)
RD2 "User LED D5" "LED3 (RD2)" High illuminates (YELLOW)
RD1 "User LED D6" "LED2 (RD1)" High illuminates (GREEN)
We will use the labels on the board to identify LEDs. If CONFIG_ARCH_LEDS
is defined, then NuttX will control these LEDs as follows:
ON OFF
------------------------- ---- ---- ---- ---- ---- ----
LED1 LED2 LED3 LED1 LED2 LED3
------------------------- ---- ---- ---- ---- ---- ----
LED_STARTED 0 OFF OFF OFF --- --- ---
LED_HEAPALLOCATE 1 ON OFF N/C --- --- ---
LED_IRQSENABLED 2 OFF ON N/C --- --- ---
LED_STACKCREATED 3 ON ON N/C --- --- ---
LED_INIRQ 4 N/C N/C ON N/C N/C OFF
LED_SIGNAL 4 N/C N/C ON N/C N/C OFF
LED_ASSERTION 4 N/C N/C ON N/C N/C OFF
LED_PANIC 5 ON N/C N/C OFF N/C N/C
There are 5 additional LEDs available on the MEB. These are not
used by NuttX.
RD1 LED1
RD2 LED2
RD3 LED3
RC1 LED4
RC2 LED5
PIC32MX Configuration Options
=============================
General Architecture Settings:
CONFIG_ARCH - Identifies the arch/ subdirectory. This should
be set to:
CONFIG_ARCH=mips
CONFIG_ARCH_family - For use in C code:
CONFIG_ARCH_MIPS=y
CONFIG_ARCH_architecture - For use in C code:
CONFIG_ARCH_MIPS32=y
CONFIG_ARCH_CHIP - Identifies the arch/*/chip subdirectory
CONFIG_ARCH_CHIP=pic32mx
CONFIG_ARCH_CHIP_name - For use in C code to identify the exact
chip:
CONFIG_ARCH_CHIP_PIC32MX795F512L=y
CONFIG_ARCH_BOARD - Identifies the configs subdirectory and
hence, the board that supports the particular chip or SoC.
CONFIG_ARCH_BOARD=pic32mx7mmb
CONFIG_ARCH_BOARD_name - For use in C code
CONFIG_ARCH_BOARD_PIC32MX7MMB=y
CONFIG_ARCH_LOOPSPERMSEC - Must be calibrated for correct operation
of delay loops
CONFIG_ENDIAN_BIG - define if big endian (default is little
endian)
CONFIG_DRAM_SIZE - Describes the installed DRAM (CPU SRAM in this case):
CONFIG_DRAM_SIZE=(32*1024) (32Kb)
There is an additional 32Kb of SRAM in AHB SRAM banks 0 and 1.
CONFIG_DRAM_START - The start address of installed DRAM
CONFIG_DRAM_START=0x10000000
CONFIG_DRAM_END - Last address+1 of installed RAM
CONFIG_DRAM_END=(CONFIG_DRAM_START+CONFIG_DRAM_SIZE)
CONFIG_ARCH_IRQPRIO - The PIC32MXx supports interrupt prioritization
CONFIG_ARCH_IRQPRIO=y
CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to boards that
have LEDs
CONFIG_ARCH_INTERRUPTSTACK - This architecture supports an interrupt
stack. If defined, this symbol is the size of the interrupt
stack in bytes. If not defined, the user task stacks will be
used during interrupt handling.
CONFIG_ARCH_STACKDUMP - Do stack dumps after assertions
CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to board architecture.
CONFIG_ARCH_CALIBRATION - Enables some build in instrumentation that
cause a 100 second delay during boot-up. This 100 second delay
serves no purpose other than it allows you to calibratre
CONFIG_ARCH_LOOPSPERMSEC. You simply use a stop watch to measure
the 100 second delay then adjust CONFIG_ARCH_LOOPSPERMSEC until
the delay actually is 100 seconds.
PIC32MX Configuration
CONFIG_PIC32MX_MVEC - Select muli- vs. single-vectored interrupts
Individual subsystems can be enabled:
CONFIG_PIC32MX_WDT - Watchdog timer
CONFIG_PIC32MX_T2 - Timer 2 (Timer 1 is the system time and always enabled)
CONFIG_PIC32MX_T3 - Timer 3
CONFIG_PIC32MX_T4 - Timer 4
CONFIG_PIC32MX_T5 - Timer 5
CONFIG_PIC32MX_IC1 - Input Capture 1
CONFIG_PIC32MX_IC2 - Input Capture 2
CONFIG_PIC32MX_IC3 - Input Capture 3
CONFIG_PIC32MX_IC4 - Input Capture 4
CONFIG_PIC32MX_IC5 - Input Capture 5
CONFIG_PIC32MX_OC1 - Output Compare 1
CONFIG_PIC32MX_OC2 - Output Compare 2
CONFIG_PIC32MX_OC3 - Output Compare 3
CONFIG_PIC32MX_OC4 - Output Compare 4
CONFIG_PIC32MX_OC5 - Output Compare 5
CONFIG_PIC32MX_I2C1 - I2C 1
CONFIG_PIC32MX_I2C2 - I2C 2
CONFIG_PIC32MX_I2C3 - I2C 3
CONFIG_PIC32MX_I2C4 - I2C 4
CONFIG_PIC32MX_I2C5 - I2C 5
CONFIG_PIC32MX_SPI1 - SPI 1
CONFIG_PIC32MX_SPI2 - SPI 2
CONFIG_PIC32MX_SPI3 - SPI 3
CONFIG_PIC32MX_SPI4 - SPI 4
CONFIG_PIC32MX_UART1 - UART 1
CONFIG_PIC32MX_UART2 - UART 2
CONFIG_PIC32MX_UART3 - UART 3
CONFIG_PIC32MX_UART4 - UART 4
CONFIG_PIC32MX_UART5 - UART 5
CONFIG_PIC32MX_UART6 - UART 6
CONFIG_PIC32MX_ADC - ADC 1
CONFIG_PIC32MX_PMP - Parallel Master Port
CONFIG_PIC32MX_CM1 - Comparator 1
CONFIG_PIC32MX_CM2 - Comparator 2
CONFIG_PIC32MX_RTCC - Real-Time Clock and Calendar
CONFIG_PIC32MX_DMA - DMA
CONFIG_PIC32MX_FLASH - FLASH
CONFIG_PIC32MX_USBDEV - USB device
CONFIG_PIC32MX_USBHOST - USB host
CONFIG_PIC32MX_CAN1 - Controller area network 1
CONFIG_PIC32MX_CAN2 - Controller area network 2
CONFIG_PIC32MX_ETHERNET - Ethernet
PIC32MX Configuration Settings
DEVCFG0:
CONFIG_PIC32MX_DEBUGGER - Background Debugger Enable. Default 3 (disabled). The
value 2 enables.
CONFIG_PIC32MX_ICESEL - In-Circuit Emulator/Debugger Communication Channel Select
Default 1 (PG2)
CONFIG_PIC32MX_PROGFLASHWP - Program FLASH write protect. Default 0xff (disabled)
CONFIG_PIC32MX_BOOTFLASHWP - Default 1 (disabled)
CONFIG_PIC32MX_CODEWP - Default 1 (disabled)
DEVCFG1: (All settings determined by selections in board.h)
DEVCFG2: (All settings determined by selections in board.h)
DEVCFG3:
CONFIG_PIC32MX_USBIDO - USB USBID Selection. Default 1 if USB enabled
(USBID pin is controlled by the USB module), but 0 (GPIO) otherwise.
CONFIG_PIC32MX_VBUSIO - USB VBUSON Selection (Default 1 if USB enabled
(VBUSON pin is controlled by the USB module, but 0 (GPIO) otherwise.
CONFIG_PIC32MX_WDENABLE - Enabled watchdog on power up. Default 0 (watchdog
can be enabled later by software).
The priority of interrupts may be specified. The value ranage of
priority is 4-31. The default (16) will be used if these any of these
are undefined.
CONFIG_PIC32MX_CTPRIO - Core Timer Interrupt
CONFIG_PIC32MX_CS0PRIO - Core Software Interrupt 0
CONFIG_PIC32MX_CS1PRIO - Core Software Interrupt 1
CONFIG_PIC32MX_INT0PRIO - External Interrupt 0
CONFIG_PIC32MX_INT1PRIO - External Interrupt 1
CONFIG_PIC32MX_INT2PRIO - External Interrupt 2
CONFIG_PIC32MX_INT3PRIO - External Interrupt 3
CONFIG_PIC32MX_INT4PRIO - External Interrupt 4
CONFIG_PIC32MX_FSCMPRIO - Fail-Safe Clock Monitor
CONFIG_PIC32MX_T1PRIO - Timer 1 (System timer) priority
CONFIG_PIC32MX_T2PRIO - Timer 2 priority
CONFIG_PIC32MX_T3PRIO - Timer 3 priority
CONFIG_PIC32MX_T4PRIO - Timer 4 priority
CONFIG_PIC32MX_T5PRIO - Timer 5 priority
CONFIG_PIC32MX_IC1PRIO - Input Capture 1
CONFIG_PIC32MX_IC2PRIO - Input Capture 2
CONFIG_PIC32MX_IC3PRIO - Input Capture 3
CONFIG_PIC32MX_IC4PRIO - Input Capture 4
CONFIG_PIC32MX_IC5PRIO - Input Capture 5
CONFIG_PIC32MX_OC1PRIO - Output Compare 1
CONFIG_PIC32MX_OC2PRIO - Output Compare 2
CONFIG_PIC32MX_OC3PRIO - Output Compare 3
CONFIG_PIC32MX_OC4PRIO - Output Compare 4
CONFIG_PIC32MX_OC5PRIO - Output Compare 5
CONFIG_PIC32MX_I2C1PRIO - I2C 1
CONFIG_PIC32MX_I2C2PRIO - I2C 2
CONFIG_PIC32MX_I2C3PRIO - I2C 3
CONFIG_PIC32MX_I2C4PRIO - I2C 4
CONFIG_PIC32MX_I2C5PRIO - I2C 5
CONFIG_PIC32MX_SPI2PRIO - SPI 2
CONFIG_PIC32MX_UART1PRIO - UART 1
CONFIG_PIC32MX_UART2PRIO - UART 2
CONFIG_PIC32MX_CN - Input Change Interrupt
CONFIG_PIC32MX_ADCPRIO - ADC1 Convert Done
CONFIG_PIC32MX_PMPPRIO - Parallel Master Port
CONFIG_PIC32MX_CM1PRIO - Comparator 1
CONFIG_PIC32MX_CM2PRIO - Comparator 2
CONFIG_PIC32MX_FSCMPRIO - Fail-Safe Clock Monitor
CONFIG_PIC32MX_RTCCPRIO - Real-Time Clock and Calendar
CONFIG_PIC32MX_DMA0PRIO - DMA Channel 0
CONFIG_PIC32MX_DMA1PRIO - DMA Channel 1
CONFIG_PIC32MX_DMA2PRIO - DMA Channel 2
CONFIG_PIC32MX_DMA3PRIO - DMA Channel 3
CONFIG_PIC32MX_DMA4PRIO - DMA Channel 4
CONFIG_PIC32MX_DMA5PRIO - DMA Channel 5
CONFIG_PIC32MX_DMA6PRIO - DMA Channel 6
CONFIG_PIC32MX_DMA7PRIO - DMA Channel 7
CONFIG_PIC32MX_FCEPRIO - Flash Control Event
CONFIG_PIC32MX_USBPRIO - USB
PIC32MXx specific device driver settings. NOTE: For the Ethernet
starter kit, there is no RS-232 connector (even with the MEB). See
discussion above ("") for information about how you can configure
an external MAX2232 board to get a serial console.
CONFIG_UARTn_SERIAL_CONSOLE - selects the UARTn for the
console and ttys0 (default is the UART0).
CONFIG_UARTn_RXBUFSIZE - Characters are buffered as received.
This specific the size of the receive buffer
CONFIG_UARTn_TXBUFSIZE - Characters are buffered before
being sent. This specific the size of the transmit buffer
CONFIG_UARTn_BAUD - The configure BAUD of the UART. Must be
CONFIG_UARTn_BITS - The number of bits. Must be either 7 or 8.
CONFIG_UARTn_PARTIY - 0=no parity, 1=odd parity, 2=even parity
CONFIG_UARTn_2STOP - Two stop bits
PIC32MX specific PHY/Ethernet device driver settings
CONFIG_PHY_KS8721 - Selects the Micrel KS8721 PHY
CONFIG_PHY_DP83848C - Selects the National Semiconduction DP83848C PHY
CONFIG_PHY_LAN8720 - Selects the SMSC LAN8720 PHY
CONFIG_PHY_AUTONEG - Enable auto-negotion
CONFIG_PHY_SPEED100 - Select 100Mbit vs. 10Mbit speed.
CONFIG_PHY_FDUPLEX - Select full (vs. half) duplex
CONFIG_NET_NTXDESC - Configured number of Tx descriptors. Default: 2
CONFIG_NET_NRXDESC - Configured number of Rx descriptors. Default: 4
CONFIG_NET_PRIORITY - Ethernet interrupt priority. The is default is
the higest priority.
CONFIG_NET_WOL - Enable Wake-up on Lan (not fully implemented).
CONFIG_NET_DUMPPACKET - Dump all received and transmitted packets.
Also needs CONFIG_DEBUG.
CONFIG_NET_REGDEBUG - Enabled low level register debug. Also needs
CONFIG_DEBUG.
CONFIG_NET_HASH - Enable receipt of near-perfect match frames.
CONFIG_NET_MULTICAST - Enable receipt of multicast (and unicast) frames.
Automatically set if CONFIG_NET_IGMP is selected.
Related DEVCFG3 Configuration Settings:
CONFIG_PIC32MX_FETHIO: Ethernet I/O Pin Selection bit:
1 = Default Ethernet I/O Pins
0 = Alternate Ethernet I/O Pins
CONFIG_PIC32MX_FMIIEN: Ethernet MII Enable bit
1 = MII enabled
0 = RMII enabled
PIC32MXx USB Device Configuration
PIC32MXx USB Host Configuration (the PIC32MX does not support USB Host)
Configurations
==============
Each PIC32MX configuration is maintained in a sudirectory and can be
selected as follow:
cd tools
./configure.sh pic32mx7mmb/<subdir>
cd -
. ./setenv.sh
Where <subdir> is one of the following:
ostest:
=======
Description.
------------
This configuration directory, performs a simple OS test using
apps/examples/ostest.
Serial Output.
--------------
The OS test produces all of its test output on the serial console.
This configuration has UART1 enabled as a serial console. I have
been unable to get this UART work on the MEB. But on the Expansion
I/O board, this maps to RX = J11 pin 41 and TX = J11 pin 43
nsh:
====
Description.
------------
This is the NuttShell (NSH) using the NSH startup logic at
apps/examples/nsh.
Serial Output.
--------------
The OS test produces all of its test output on the serial console.
This configuration has UART1 enabled as a serial console. I have
been unable to get this UART work on the MEB. But on the Expansion
I/O board, this maps to RX = J11 pin 41 and TX = J11 pin 43
USB Configuations.
-----------------
Several USB device configurations can be enabled and included
as NSH built-in built in functions.
To use USB device, connect the starter kit to the host using a cable
with a Type-B micro-plug to the starter kits micro-A/B port J5, located
on the bottom side of the starter kit. The other end of the cable
must have a Type-A plug. Connect it to a USB host. Jumper JP2 should be
removed.
All USB device configurations require the following basic setup in
your NuttX configuration file to enable USB device support:
CONFIG_USBDEV=y : Enable basic USB device support
CONFIG_PIC32MX_USBDEV=y : Enable PIC32 USB device support
examples/usbterm - This option can be enabled by uncommenting
the following line in the appconfig file:
CONFIGURED_APPS += examples/usbterm
And by enabling one of the USB serial devices:
CONFIG_PL2303=y : Enable the Prolifics PL2303 emulation
CONFIG_CDCACM=y : or the CDC/ACM serial driver (not both)
examples/cdcacm - The examples/cdcacm program can be included as an
function by uncommenting the following line in the appconfig file:
CONFIGURED_APPS += examples/cdcacm
and defining the following in your .config file:
CONFIG_CDCACM=y : Enable the CDCACM device
examples/usbstorage - There are some hooks in the appconfig file
to enable the USB mass storage device. However, this device cannot
work until support for the SD card is also incorporated.
Networking Configuations.
-------------------------
Several Networking configurations can be enabled and included
as NSH built-in built in functions. The following additional
configuration settings are required:
CONFIG_NET=y : Enable networking support
CONFIG_PIC32MX_ETHERNET=y : Enable the PIC32 Ethernet driver
CONFIG_NSH_TELNET=y : Enable the Telnet NSH console (optional)
NOTES:
1. This logic will assume that a network is connected. During its
initialization, it will try to negotiate the link speed. If you have
no network connected when you reset the board, there will be a long
delay (maybe 30 seconds?) before anything happens. That is the timeout
before the networking finally gives up and decides that no network is
available.
2. This example can support an FTP client. In order to build in FTP client
support simply uncomment the following lines in the appconfig file (before
configuring) or in the apps/.config file (after configuring):
#CONFIGURED_APPS += netutils/ftpc
#CONFIGURED_APPS += examples/ftpc
3. This example can support an FTP server. In order to build in FTP server
support simply uncomment the following lines in the appconfig file (before
configuring) or in the apps/.config file (after configuring):
#CONFIGURED_APPS += netutils/ftpd
#CONFIGURED_APPS += examples/ftpd
And enable poll() support in the NuttX configuration file:
CONFIG_DISABLE_POLL=n
nsh2:
=====
This is an alternative NSH configuration. Without the Expansion I/O board,
there is no way to connect a serial console. This NSH alternative supports
only a Telnet console. The nsh2 differs from the nsh configuration in the
following ways:
1. Networking is enabled:
CONFIG_NET=y : Enable networking support
CONFIG_PIC32MX_ETHERNET=y : Enable the PIC32 Ethernet driver
CONFIG_NSH_CONSOLE=n : Disable NSH serial console
CONFIG_NSH_TELNET=y : Enable the Telnet NSH console
See apps/nshlib/README.txt for other NSH networking-related configuration
settings.
2. UART1 is disabled
CONFIG_PIC32MX_UART1=n : UART1 is disabled (as well as other UARTs)
CONFIG_UART1_SERIAL_CONSOLE=n : There is no serial console
3. The RAM log is enabled"
CONFIG_SYSLOG=y : Enables the System Logging feature.
CONFIG_RAMLOG=y : Enable the RAM-based logging feature.
CONFIG_RAMLOG_CONSOLE=n : (there is no default console device)
CONFIG_RAMLOG_SYSLOG=y : This enables the RAM-based logger as the
system logger.
Logging is currently set up to use 16Kb of memory:
CONFIG_RAMLOG_CONSOLE_BUFSIZE=16384
There are a few other configuration differences as necessary to support
this different device configuration. Just the do the 'diff' if you are
curious.
NOTES:
See the notes for the nsh configuration. Most also apply to the nsh2
configuration.
Using a RAM disk and the USB MSC device with nsh and nsh2
---------------------------------------------------------
Here is an experimental change to either examples/nsh or examples/nsh2
that will create a RAM disk and attempt to export that RAM disk as a
USB mass storage device.
1. Changes to nuttx/.config
a) Enable support for the PIC32 USB device
-CONFIG_PIC32MX_USBDEV=n
+CONFIG_PIC32MX_USBDEV=y
b) Enable NuttX USB device support
-CONFIG_USBDEV=n
+CONFIG_USBDEV=y
c) Enable the USB MSC class driver
-CONFIG_USBMSC=n
+CONFIG_USBMSC=y
d) Use a RAM disk (instead of an SD card) as the USB MSC logical unit:
-CONFIG_EXAMPLES_USBMSC_DEVPATH1="/dev/mmcsd0"
+CONFIG_EXAMPLES_USBMSC_DEVPATH1="/dev/ram0"
2. Changes to nuttx/.config.
a) Enable building of the examples/usbstorage:
-# CONFIGURED_APPS += examples/usbstorage
+ CONFIGURED_APPS += examples/usbstorage
3. When NSH first comes up, you must manually create the RAM disk
before exporting it:
a) Create a 64Kb RAM disk at /dev/ram0:
nsh> mkrd -s 512 128
b) Put a FAT file system on the RAM disk:
nsh> mkfatfs /dev/ram0
b) Now the 'msconn' command will connect to the host and
export /dev/ram0 as the USB logical unit:
nsh> msconn
NOTE: This modification should be considered experimental. IN the
little testing I have done with it, it appears functional. But the
logic has not been stressed and there could still be lurking issues.
Update. The following was added to the top-level TODO list:
Title: PIC32 USB DRIVER DOES NOT WORK WITH MASS STORAGE CLASS
Description: The PIC32 USB driver either crashes or hangs when used with
the mass storage class when trying to write files to the target
storage device. This usually works with debug on, but does not
work with debug OFF (implying some race condition?)
Here are some details of what I see in debugging:
1. The USB MSC device completes processing of a read request
and returns the read request to the driver.
2. Before the MSC device can even begin the wait for the next
driver, many packets come in at interrupt level. The MSC
device goes to sleep (on pthread_cond_wait) with all of the
read buffers ready (16 in my test case).
3. The pthread_cond_wait() does not wake up. This implies
a problem with pthread_con_wait(?). But in other cases,
the MSC device does wake up, but then immediately crashes
because its stack is bad.
4. If I force the pthread_cond_wait to wake up (by using
pthread_cond_timedwait instead), then the thread wakes
up and crashes with a bad stack.
So far, I have no clue why this is failing.
Status: Open
Priority: High

View File

@ -0,0 +1,221 @@
/****************************************************************************
* configs/pic32mx7mmb/include/board.h
* include/arch/board/board.h
*
* Copyright (C) 2012 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_MIKROELEKTRONIKA_PIC32MX7MMB_INCLUDE_BOARD_H
#define __CONFIGS_MIKROELEKTRONIKA_PIC32MX7MMB_INCLUDE_BOARD_H
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#ifndef __ASSEMBLY__
# include <stdbool.h>
#endif
/****************************************************************************
* Pre-Processor Definitions
****************************************************************************/
/* Configuration ************************************************************/
/* Clocking *****************************************************************/
/* Crystal frequencies */
#define BOARD_POSC_FREQ 8000000 /* Primary OSC XTAL frequency (8MHz) */
#define BOARD_SOSC_FREQ 32768 /* Secondary OSC XTAL frequency (32.768KHz) */
/* PLL configuration and resulting CPU clock.
* CPU_CLOCK = ((POSC_FREQ / IDIV) * MULT) / ODIV
*/
#define BOARD_PLL_IDIV 2 /* PLL input divider */
#define BOARD_PLL_MULT 20 /* PLL multiplier */
#define BOARD_PLL_ODIV 1 /* PLL output divider */
#define BOARD_CPU_CLOCK 80000000 /* CPU clock (80MHz = 8MHz * 20 / 2) */
/* USB PLL configuration.
* USB_CLOCK = ((POSC_XTAL / IDIV) * 24) / 2
*/
#define BOARD_UPLL_IDIV 2 /* USB PLL divider (revisit) */
#define BOARD_USB_CLOCK 48000000 /* USB clock (8MHz / 2) * 24 / 2) */
/* Peripheral clock is divided down from CPU clock.
* PBCLOCK = CPU_CLOCK / PBDIV
*/
#define BOARD_PBDIV 2 /* Peripheral clock divisor (PBDIV) */
#define BOARD_PBCLOCK 40000000 /* Peripheral clock (PBCLK = 80MHz/2) */
/* Watchdog pre-scaler (re-visit) */
#define BOARD_WD_ENABLE 0 /* Watchdog is disabled */
#define BOARD_WD_PRESCALER 8 /* Watchdog pre-scaler */
/* Ethernet MII clocking.
*
* The clock divider used to create the MII Management Clock (MDC). The MIIM
* module uses the SYSCLK as an input clock. According to the IEEE 802.3
* Specification this should be no faster than 2.5 MHz. However, some PHYs
* support clock rates up to 12.5 MHz.
*/
#define BOARD_EMAC_MIIM_DIV 32 /* Ideal: 80MHz/32 = 2.5MHz */
/* LED definitions **********************************************************/
/* LED Configuration ********************************************************/
/* The Mikroelektronika PIC32MX7 MMB has 3 user LEDs labeled LED1-3 on the
* board graphics (but referred to as LED4-6 in the schematic):
*
* PIN User's Guide Board Stencil Notes
* --- ------------- -------------- -------------------------
* RD0 "User LED D4" "LED1 (RD0") High illuminates (RED)
* RD2 "User LED D5" "LED3 (RD2)" High illuminates (YELLOW)
* RD1 "User LED D6" "LED2 (RD1)" High illuminates (GREEN)
*
* We will use the labels on the board to identify LEDs
*
* There are 5 additional LEDs available on the MEB (but not used by NuttX):
*
* RD1 LED1
* RD2 LED2
* RD3 LED3
* RC1 LED4
* RC2 LED5
*/
/* LED index values for use with pic32mx_setled() */
#define PIC32MX_PIC32MX7MMB_LED1 0
#define PIC32MX_PIC32MX7MMB_LED2 1
#define PIC32MX_PIC32MX7MMB_LED3 2
#define PIC32MX_PIC32MX7MMB_NLEDS 3
/* LED bits for use with pic32mx_setleds() */
#define PIC32MX_PIC32MX7MMB_LED1_BIT (1 << PIC32MX_PIC32MX7MMB_LED1)
#define PIC32MX_PIC32MX7MMB_LED2_BIT (1 << PIC32MX_PIC32MX7MMB_LED2)
#define PIC32MX_PIC32MX7MMB_LED3_BIT (1 << PIC32MX_PIC32MX7MMB_LED3)
/* If CONFIG_ARCH_LEDs is defined, then NuttX will control the 3 LEDs
* on board the Mikroelektronika PIC32MX7 MMB. The following definitions
* describe how NuttX controls the LEDs:
*
* ON OFF
* ------------------------- ---- ---- ---- ---- ---- ----
* LED1 LED2 LED3 LED1 LED2 LED3
* ------------------------- ---- ---- ---- ---- ---- ----
* LED_STARTED 0 OFF OFF OFF --- --- ---
* LED_HEAPALLOCATE 1 ON OFF N/C --- --- ---
* LED_IRQSENABLED 2 OFF ON N/C --- --- ---
* LED_STACKCREATED 3 ON ON N/C --- --- ---
* LED_INIRQ 4 N/C N/C ON N/C N/C OFF
* LED_SIGNAL 4 N/C N/C ON N/C N/C OFF
* LED_ASSERTION 4 N/C N/C ON N/C N/C OFF
* LED_PANIC 5 ON N/C N/C OFF N/C N/C
*/
#define LED_STARTED 0
#define LED_HEAPALLOCATE 1
#define LED_IRQSENABLED 2
#define LED_STACKCREATED 3
#define LED_INIRQ 4
#define LED_SIGNAL 4
#define LED_ASSERTION 4
#define LED_PANIC 5
#define LED_NVALUES 6
/* Switch definitions *******************************************************/
/* The PIC32 start kit has 3 switches:
*
* RD7 Switch SW2 (low when closed)
* RD6 Switch SW1 (low when closed)
* RD13 Switch SW3 (low when closed)
*/
/****************************************************************************
* Public Types
****************************************************************************/
#ifndef __ASSEMBLY__
/****************************************************************************
* Inline Functions
****************************************************************************/
/****************************************************************************
* Public Function Prototypes
****************************************************************************/
#ifdef __cplusplus
#define EXTERN extern "C"
extern "C" {
#else
#define EXTERN extern
#endif
/****************************************************************************
* Name: pic32mx_ledinit and pic32mx_setled
*
* 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 interfaces
* are available to control the LEDs from user applicaitons.
*
****************************************************************************/
#ifndef CONFIG_ARCH_LEDS
EXTERN void pic32mx_ledinit(void);
#endif
#ifndef CONFIG_ARCH_LEDS
EXTERN void pic32mx_setled(int led, bool ledon);
#endif
#ifndef CONFIG_ARCH_LEDS
EXTERN void pic32mx_setleds(uint8_t ledset);
#endif
#undef EXTERN
#ifdef __cplusplus
}
#endif
#endif /* __ASSEMBLY__ */
#endif /* __CONFIGS_MIKROELEKTRONIKA_PIC32MX7MMB_INCLUDE_BOARD_H */

View File

@ -0,0 +1,160 @@
############################################################################
# configs/pic32mx7mmb/ostest/Make.defs
#
# Copyright (C) 2012 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.
#
############################################################################
include ${TOPDIR}/.config
# Setup for the selected toolchain
ifeq ($(CONFIG_PIC32MX_MICROCHIPW),y)
# Microchip toolchain under Windows
CROSSDEV = pic32-
WINTOOL = y
MAXOPTIMIZATION = -O2
ARCHCPUFLAGS = -mprocessor=elf32pic32mx -mno-float -mlong32 -membedded-data
ARCHPICFLAGS = -fpic -membedded-pic
LDFLAGS += -nostartfiles -nodefaultlibs
endif
ifeq ($(CONFIG_PIC32MX_MICROCHIPW_LITE),y)
# Microchip toolchain under Windows
CROSSDEV = pic32-
WINTOOL = y
# MAXOPTIMIZATION = -O2
ARCHCPUFLAGS = -mprocessor=elf32pic32mx -mno-float -mlong32 -membedded-data
ARCHPICFLAGS = -fpic -membedded-pic
LDFLAGS += -nostartfiles -nodefaultlibs
endif
ifeq ($(CONFIG_PIC32MX_MICROCHIPL),y)
# Microchip toolchain under Linux
CROSSDEV = pic32-
MAXOPTIMIZATION = -O2
ARCHCPUFLAGS = -mprocessor=elf32pic32mx -mno-float -mlong32 -membedded-data
ARCHPICFLAGS = -fpic -membedded-pic
LDFLAGS += -nostartfiles -nodefaultlibs
endif
ifeq ($(CONFIG_PIC32MX_MICROCHIPL_LITE),y)
# Microchip toolchain under Linux
CROSSDEV = pic32-
# MAXOPTIMIZATION = -O2
ARCHCPUFLAGS = -mprocessor=elf32pic32mx -mno-float -mlong32 -membedded-data
ARCHPICFLAGS = -fpic -membedded-pic
LDFLAGS += -nostartfiles -nodefaultlibs
endif
ifeq ($(WINTOOL),y)
# Windows-native toolchains
DIRLINK = $(TOPDIR)/tools/winlink.sh
DIRUNLINK = $(TOPDIR)/tools/unlink.sh
MKDEP = $(TOPDIR)/tools/mknulldeps.sh
ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}"
ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}"
ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/ostest/ld.script}"
else
# Linux/Cygwin-native toolchain
MKDEP = $(TOPDIR)/tools/mkdeps.sh
ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/ostest/ld.script
endif
CC = $(CROSSDEV)gcc
CXX = $(CROSSDEV)g++
CPP = $(CROSSDEV)gcc -E
LD = $(CROSSDEV)ld
AR = $(CROSSDEV)ar rcs
NM = $(CROSSDEV)nm
OBJCOPY = $(CROSSDEV)objcopy
OBJDUMP = $(CROSSDEV)objdump
ifeq ("${CONFIG_DEBUG_SYMBOLS}","y")
ARCHOPTIMIZATION = -g
else
ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer
endif
ARCHCFLAGS = -fno-builtin
ARCHCXXFLAGS = -fno-builtin -fno-exceptions
ARCHWARNINGS = -Wall -Wstrict-prototypes -Wshadow
ARCHWARNINGSXX = -Wall -Wshadow
ARCHDEFINES =
CFLAGS = $(ARCHCFLAGS) $(ARCHWARNINGS) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe
CPICFLAGS = $(ARCHPICFLAGS) $(CFLAGS)
CXXFLAGS = $(ARCHCXXFLAGS) $(ARCHWARNINGSXX) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHXXINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe
CXXPICFLAGS = $(ARCHPICFLAGS) $(CXXFLAGS)
CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES)
AFLAGS = $(CFLAGS) -D__ASSEMBLY__
NXFLATLDFLAGS1 = -r -d -warn-common
NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections
LDNXFLATFLAGS = -e main -s 2048
OBJEXT = .o
LIBEXT = .a
EXEEXT =
define PREPROCESS
@echo "CPP: $1->$2"
@$(CPP) $(CPPFLAGS) $1 -o $2
endef
define COMPILE
@echo "CC: $1"
@$(CC) -c $(CFLAGS) $1 -o $2
endef
define COMPILEXX
@echo "CXX: $1"
@$(CXX) -c $(CXXFLAGS) $1 -o $2
endef
define ASSEMBLE
@echo "AS: $1"
@$(CC) -c $(AFLAGS) $1 -o $2
endef
define ARCHIVE
echo "AR: $2"; \
$(AR) $1 $2 || { echo "$(AR) $1 $2 FAILED!" ; exit 1 ; }
endef
define CLEAN
@rm -f *.o *.a
endef
HOSTCC = gcc
HOSTINCLUDES = -I.
HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -g -pipe
HOSTLDFLAGS =

View File

@ -0,0 +1,39 @@
############################################################################
# configs/pic32mx7mmb/ostest/appconfig
#
# Copyright (C) 2012 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.
#
############################################################################
# Path to example in apps/examples containing the user_start entry point
CONFIGURED_APPS += examples/ostest

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,317 @@
/****************************************************************************
* configs/pic32mx7mmb/ostest/ld.script
*
* Copyright (C) 2012 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.
*
****************************************************************************/
/* Memory Regions ***********************************************************/
MEMORY
{
/* The PIC32MX795F512L has 512Kb of program FLASH at physical address
* 0x1d000000 but is always accessed at KSEG0 address 0x9d00:0000
*/
kseg0_progmem (rx) : ORIGIN = 0x9d000000, LENGTH = 512K
/* The PIC32MX795F512L has 12Kb of boot FLASH at physical address
* 0x1fc00000. The initial reset vector is in KSEG1, but all other
* accesses are in KSEG0.
*
* REGION PHYSICAL KSEG SIZE
* DESCRIPTION START ADDR (BYTES)
* ------------- ---------- ------ ----------------------
* Exceptions:*
* Reset 0x1fc00000 KSEG1 512 512
* TLB Refill 0x1fc00200 KSEG1 256 768
* Cache Error 0x1fc00300 KSEG1 128 896
* Others 0x1fc00380 KSEG1 128 1024 (1Kb)
* Interrupt 0x1fc00400 KSEG1 128 1152
* JTAG 0x1fc00480 KSEG1 16 1168
* Exceptions 0x1fc00490 KSEG0 8192-1168 8192 (4Kb)
* Debug code 0x1fc02000 KSEG1 4096-16 12272
* DEVCFG3-0 0x1fc02ff0 KSEG1 16 12288 (12Kb)
*
* Exceptions assume:
*
* STATUS: BEV=0/1 and EXL=0
* CAUSE: IV=1
* JTAG: ProbEn=0
* And multi-vector support disabled
*/
kseg1_reset (rx) : ORIGIN = 0xbfc00000, LENGTH = 384
kseg1_genexcpt (rx) : ORIGIN = 0xbfc00180, LENGTH = 128
kseg1_ebexcpt (rx) : ORIGIN = 0xbfc00200, LENGTH = 128
kseg1_bevexcpt (rx) : ORIGIN = 0xbfc00380, LENGTH = 128
kseg1_intexcpt (rx) : ORIGIN = 0xbfc00400, LENGTH = 128
kseg1_dbgexcpt (rx) : ORIGIN = 0xbfc00480, LENGTH = 16
kseg0_bootmem (rx) : ORIGIN = 0x9fc00490, LENGTH = 8192-1168
kseg1_dbgcode (rx) : ORIGIN = 0xbfc02000, LENGTH = 4096-16
kseg1_devcfg (r) : ORIGIN = 0xbfc02ff0, LENGTH = 16
/* The PIC32MX795F512L has 128Kb of data memory at physical address
* 0x00000000. Since the PIC32MX has no data cache, this memory is
* always accessed through KSEG1.
*
* When used with MPLAB, we need to set aside 512 bytes of memory
* for use by MPLAB.
*/
kseg1_datamem (w!x) : ORIGIN = 0xa0000200, LENGTH = 128K - 512
}
OUTPUT_FORMAT("elf32-tradlittlemips")
OUTPUT_ARCH(pic32mx)
ENTRY(__start)
SECTIONS
{
/* Boot FLASH sections */
.reset :
{
KEEP (*(.reset))
} > kseg1_reset
/* Exception handlers. The following is assumed:
*
* STATUS: BEV=1 and EXL=0
* CAUSE: IV=1
* JTAG: ProbEn=0
* And multi-vector support disabled
*
* In that configuration, the vector locations become:
*
* Reset, Soft Reset bfc0:0000
* TLB Refill bfc0:0200
* Cache Error bfc0:0300
* All others bfc0:0380
* Interrupt bfc0:0400
* EJTAG Debug bfc0:0480
*/
/* KSEG1 exception handler "trampolines" */
.gen_excpt :
{
KEEP (*(.gen_excpt))
} > kseg1_genexcpt
.ebase_excpt :
{
KEEP (*(.ebase_excpt))
} > kseg1_ebexcpt
.bev_excpt :
{
KEEP (*(.bev_excpt))
} > kseg1_bevexcpt
.int_excpt :
{
KEEP (*(.int_excpt))
} > kseg1_intexcpt
.dbg_excpt = ORIGIN(kseg1_dbgexcpt);
.start :
{
/* KSEG0 Reset startup logic */
*(.start)
/* KSEG0 exception handlers */
*(.nmi_handler)
*(.bev_handler)
*(.int_handler)
} > kseg0_bootmem
.dbg_code = ORIGIN(kseg1_dbgcode);
.devcfg :
{
KEEP (*(.devcfg))
} > kseg1_devcfg
/* Program FLASH sections */
.text :
{
_stext = ABSOLUTE(.);
*(.text .text.*)
*(.stub)
KEEP (*(.text.*personality*))
*(.gnu.linkonce.t.*)
*(.gnu.warning)
*(.mips16.fn.*)
*(.mips16.call.*)
/* Read-only data is included in the text section */
*(.rodata .rodata.*)
*(.rodata1)
*(.gnu.linkonce.r.*)
/* Small initialized constant global and static data */
*(.sdata2 .sdata2.*)
*(.gnu.linkonce.s2.*)
/* Uninitialized constant global and static data */
*(.sbss2 .sbss2.*)
*(.gnu.linkonce.sb2.*)
_etext = ABSOLUTE(.);
} > kseg0_progmem
/* Initialization data begins here in progmem */
_data_loaddr = LOADADDR(.data);
.eh_frame_hdr : { *(.eh_frame_hdr) }
.eh_frame : ONLY_IF_RO { KEEP (*(.eh_frame)) }
/* RAM functions are positioned at the beginning of RAM so that
* they can be guaranteed to satisfy the 2Kb alignment requirement.
*/
/* This causes failures if there are no RAM functions
.ramfunc ALIGN(2K) :
{
_sramfunc = ABSOLUTE(.);
*(.ramfunc .ramfunc.*)
_eramfunc = ABSOLUTE(.);
} > kseg1_datamem AT > kseg0_progmem
_ramfunc_loadaddr = LOADADDR(.ramfunc);
_ramfunc_sizeof = SIZEOF(.ramfunc);
_bmxdkpba_address = _sramfunc - ORIGIN(kseg1_datamem) ;
_bmxdudba_address = LENGTH(kseg1_datamem) ;
_bmxdupba_address = LENGTH(kseg1_datamem) ;
*/
.data :
{
_sdata = ABSOLUTE(.);
*(.data .data.*)
*(.gnu.linkonce.d.*)
KEEP (*(.gnu.linkonce.d.*personality*))
*(.data1)
} > kseg1_datamem AT > kseg0_progmem
.eh_frame : ONLY_IF_RW { KEEP (*(.eh_frame)) }
_gp = ALIGN(16) + 0x7FF0 ;
.got :
{
*(.got.plt) *(.got)
} > kseg1_datamem AT > kseg0_progmem
.sdata :
{
*(.sdata .sdata.* .gnu.linkonce.s.*)
} > kseg1_datamem AT > kseg0_progmem
.lit8 :
{
*(.lit8)
} > kseg1_datamem AT > kseg0_progmem
.lit4 :
{
*(.lit4)
_edata = ABSOLUTE(.);
} >kseg1_datamem AT>kseg0_progmem
.sbss :
{
_sbss = ABSOLUTE(.);
*(.dynsbss)
*(.sbss .sbss.* .gnu.linkonce.sb.*)
*(.scommon)
} >kseg1_datamem
.bss :
{
*(.dynbss)
*(.bss .bss.*)
*(.gnu.linkonce.b.*)
*(COMMON)
_ebss = ABSOLUTE(.);
} > kseg1_datamem
/* Stabs debugging sections */
.stab 0 : { *(.stab) }
.stabstr 0 : { *(.stabstr) }
.stab.excl 0 : { *(.stab.excl) }
.stab.exclstr 0 : { *(.stab.exclstr) }
.stab.index 0 : { *(.stab.index) }
.stab.indexstr 0 : { *(.stab.indexstr) }
.comment 0 : { *(.comment) }
/* DWARF debug sections */
/* DWARF 1 */
.debug 0 : { *(.debug) }
.line 0 : { *(.line) }
/* GNU DWARF 1 extensions */
.debug_srcinfo 0 : { *(.debug_srcinfo) }
.debug_sfnames 0 : { *(.debug_sfnames) }
/* DWARF 1.1 and DWARF 2 */
.debug_aranges 0 : { *(.debug_aranges) }
.debug_pubnames 0 : { *(.debug_pubnames) }
/* DWARF 2 */
.debug_info 0 : { *(.debug_info .gnu.linkonce.wi.*) }
.debug_abbrev 0 : { *(.debug_abbrev) }
.debug_line 0 : { *(.debug_line) }
.debug_frame 0 : { *(.debug_frame) }
.debug_str 0 : { *(.debug_str) }
.debug_loc 0 : { *(.debug_loc) }
.debug_macinfo 0 : { *(.debug_macinfo) }
/* SGI/MIPS DWARF 2 extensions */
.debug_weaknames 0 : { *(.debug_weaknames) }
.debug_funcnames 0 : { *(.debug_funcnames) }
.debug_typenames 0 : { *(.debug_typenames) }
.debug_varnames 0 : { *(.debug_varnames) }
/DISCARD/ : { *(.note.GNU-stack) }
}

View File

@ -0,0 +1,61 @@
#!/bin/bash
# configs/pic32mx7mmb/ostest/setenv.sh
#
# Copyright (C) 2012 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.
#
if [ "$_" = "$0" ] ; then
echo "You must source this script, not run it!" 1>&2
exit 1
fi
if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi
WD=`pwd`
if [ ! -x "setenv.sh" ]; then
echo "This script must be executed from the top-level NuttX build directory"
exit 1
fi
# This the Cygwin path to the location where I installed the MicroChip
# PIC32MX toolchain under windows. This is *not* the default install
# location so you will probably have to edit this. You will also have
# to edit this if you install a different version of if you install
# the Linux PIC32MX toolchain as well
export TOOLCHAIN_BIN="/cygdrive/c/MicroChip/mplabc32/v1.12/bin"
# This is the path to the toosl subdirectory
export PIC32TOOL_DIR="${WD}/configs/pic32mx7mmb/tools"
# Add the path to the toolchain to the PATH varialble
export PATH="${TOOLCHAIN_BIN}:${PIC32TOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}"
echo "PATH : ${PATH}"

View File

@ -0,0 +1,99 @@
############################################################################
# configs/pic32mx7mmb/src/Makefile
#
# Copyright (C) 2012 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.
#
############################################################################
-include $(TOPDIR)/Make.defs
CFLAGS += -I$(TOPDIR)/sched
ASRCS =
CSRCS = up_boot.c up_leds.c up_spi.c
ifeq ($(CONFIG_PIC32MX_USBDEV),y)
CSRCS += up_usbdev.c
ifeq ($(CONFIG_EXAMPLES_USBTERM_DEVINIT),y)
CSRCS += up_usbterm.c
endif
endif
ifeq ($(CONFIG_NSH_ARCHINIT),y)
CSRCS += up_nsh.c
endif
ifeq ($(CONFIG_USBMSC),y)
CSRCS += up_usbmsc.c
endif
AOBJS = $(ASRCS:.S=$(OBJEXT))
COBJS = $(CSRCS:.c=$(OBJEXT))
SRCS = $(ASRCS) $(CSRCS)
OBJS = $(AOBJS) $(COBJS)
ARCH_SRCDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src
ifeq ($(WINTOOL),y)
CFLAGS += -I "${shell cygpath -w $(ARCH_SRCDIR)/chip}" \
-I "${shell cygpath -w $(ARCH_SRCDIR)/common}" \
-I "${shell cygpath -w $(ARCH_SRCDIR)/mips32}"
else
CFLAGS += -I$(ARCH_SRCDIR)/chip -I$(ARCH_SRCDIR)/common -I$(ARCH_SRCDIR)/mips32
endif
all: libboard$(LIBEXT)
$(AOBJS): %$(OBJEXT): %.S
$(call ASSEMBLE, $<, $@)
$(COBJS) $(LINKOBJS): %$(OBJEXT): %.c
$(call COMPILE, $<, $@)
libboard$(LIBEXT): $(OBJS)
@( for obj in $(OBJS) ; do \
$(call ARCHIVE, $@, $${obj}); \
done ; )
.depend: Makefile $(SRCS)
@$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
@touch $@
depend: .depend
clean:
@rm -f libboard$(LIBEXT) *~ .*.swp
$(call CLEAN)
distclean: clean
@rm -f Make.dep .depend
-include Make.dep

View File

@ -0,0 +1,122 @@
/****************************************************************************
* configs/pic32mx7mmb/src/pic32mx7mmb_internal.h
*
* Copyright (C) 2012 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_MIKROELEKTRONIKA_PIC32MX7MMB_SRC_PIC32MX7MMB_INTERNAL_H
#define __CONFIGS_MIKROELEKTRONIKA_PIC32MX7MMB_SRC_PIC32MX7MMB_INTERNAL_H
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
/****************************************************************************
* Pre-Processor Definitions
****************************************************************************/
/* Configuration ************************************************************/
/* The Mikroelektronika PIC32MX7 MMB has 3 user LEDs
*
* RD0 User LED D4 (high illuminates)
* RD2 User LED D5 (high illuminates)
* RD1 User LED D6 (high illuminates)
*
* There are 5 LEDs available on the MEB:
*
* RD1 LED1
* RD2 LED2
* RD3 LED3
* RC1 LED4
* RC2 LED5
*/
/* The PIC32 start kit has 3 switches:
*
* RD7 Switch SW2 (low when closed)
* RD6 Switch SW1 (low when closed)
* RD13 Switch SW3 (low when closed)
*/
/****************************************************************************
* Public Types
****************************************************************************/
#ifndef __ASSEMBLY__
/****************************************************************************
* Inline Functions
****************************************************************************/
/****************************************************************************
* Public Function Prototypes
****************************************************************************/
#ifdef __cplusplus
#define EXTERN extern "C"
extern "C" {
#else
#define EXTERN extern
#endif
/************************************************************************************
* Name: pic32mx_spiinitialize
*
* Description:
* Called to configure SPI chip select GPIO pins for the PCB Logic board.
*
************************************************************************************/
#if defined(CONFIG_PIC32MX_SPI2)
EXTERN void weak_function pic32mx_spiinitialize(void);
#endif
/************************************************************************************
* Name: pic32mx_ledinit
*
* Description:
* Configure on-board LEDs if LED support has been selected.
*
************************************************************************************/
#ifdef CONFIG_ARCH_LEDS
EXTERN void pic32mx_ledinit(void);
#endif
#undef EXTERN
#ifdef __cplusplus
}
#endif
#endif /* __ASSEMBLY__ */
#endif /* __CONFIGS_MIKROELEKTRONIKA_PIC32MX7MMB_SRC_PIC32MX7MMB_INTERNAL_H */

View File

@ -0,0 +1,94 @@
/************************************************************************************
* configs/pic32mx7mmb/src/up_boot.c
* arch/mips/src/board/up_boot.c
*
* Copyright (C) 2012 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.
*
************************************************************************************/
/************************************************************************************
* Included Files
************************************************************************************/
#include <nuttx/config.h>
#include <debug.h>
#include <arch/board/board.h>
#include "up_arch.h"
#include "up_internal.h"
#include "pic32mx-internal.h"
#include "pic32mx7mmb_internal.h"
/************************************************************************************
* Definitions
************************************************************************************/
/************************************************************************************
* Private Functions
************************************************************************************/
/************************************************************************************
* Public Functions
************************************************************************************/
/************************************************************************************
* Name: pic32mx_boardinitialize
*
* Description:
* All PIC32MX 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 pic32mx_boardinitialize(void)
{
/* Configure SPI chip selects if 1) at least one SPI is enabled, and 2) the weak
* function pic32mx_spiinitialize() has been brought into the link.
*/
#if defined(CONFIG_PIC32MX_SPI1) || defined(CONFIG_PIC32MX_SPI2) || \
defined(CONFIG_PIC32MX_SPI3) || defined(CONFIG_PIC32MX_SPI4)
if (pic32mx_spiinitialize)
{
pic32mx_spiinitialize();
}
#endif
/* Configure on-board LEDs if LED support has been selected. */
#ifdef CONFIG_ARCH_LEDS
pic32mx_ledinit();
#endif
}

View File

@ -0,0 +1,266 @@
/****************************************************************************
* configs/pic32mx7mmb/src/up_leds.c
* arch/arm/src/board/up_leds.c
*
* Copyright (C) 2012 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.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <stdint.h>
#include <stdbool.h>
#include <debug.h>
#include <arch/board/board.h>
#include "chip.h"
#include "up_arch.h"
#include "up_internal.h"
#include "pic32mx-internal.h"
#include "pic32mx-ioport.h"
#include "pic32mx7mmb_internal.h"
/****************************************************************************
* Definitions
****************************************************************************/
/* LED Configuration ********************************************************/
/* The Mikroelektronika PIC32MX7 MMB has 3 user LEDs labeled LED1-3 on the
* board graphics (but referred to as LED4-6 in the schematic):
*
* PIN User's Guide Board Stencil Notes
* --- ------------- -------------- -------------------------
* RD0 "User LED D4" "LED1 (RD0") High illuminates (RED)
* RD2 "User LED D5" "LED3 (RD2)" High illuminates (YELLOW)
* RD1 "User LED D6" "LED2 (RD1)" High illuminates (GREEN)
*
* We will use the labels on the board to identify LEDs
*
* ON OFF
* ------------------------- ---- ---- ---- ---- ---- ----
* LED1 LED2 LED3 LED1 LED2 LED3
* ------------------------- ---- ---- ---- ---- ---- ----
* LED_STARTED 0 OFF OFF OFF --- --- ---
* LED_HEAPALLOCATE 1 ON OFF N/C --- --- ---
* LED_IRQSENABLED 2 OFF ON N/C --- --- ---
* LED_STACKCREATED 3 ON ON N/C --- --- ---
* LED_INIRQ 4 N/C N/C ON N/C N/C OFF
* LED_SIGNAL 4 N/C N/C ON N/C N/C OFF
* LED_ASSERTION 4 N/C N/C ON N/C N/C OFF
* LED_PANIC 5 ON N/C N/C OFF N/C N/C
*/
#define GPIO_LED_1 (GPIO_OUTPUT|GPIO_VALUE_ZERO|GPIO_PORTD|GPIO_PIN0)
#define GPIO_LED_2 (GPIO_OUTPUT|GPIO_VALUE_ZERO|GPIO_PORTD|GPIO_PIN1)
#define GPIO_LED_3 (GPIO_OUTPUT|GPIO_VALUE_ZERO|GPIO_PORTD|GPIO_PIN2)
/* LED Management Definitions ***********************************************/
#ifdef CONFIG_ARCH_LEDS
# define LED_OFF 0
# define LED_ON 1
# define LED_NC 2
#endif
/* Debug ********************************************************************/
#if defined(CONFIG_DEBUG) && defined(CONFIG_DEBUG_LEDS)
# define leddbg lldbg
# ifdef CONFIG_DEBUG_VERBOSE
# define ledvdbg lldbg
# else
# define ledvdbg(x...)
# endif
#else
# undef CONFIG_DEBUG_LEDS
# undef CONFIG_DEBUG_VERBOSE
# define leddbg(x...)
# define ledvdbg(x...)
#endif
/****************************************************************************
* Private types
****************************************************************************/
#ifdef CONFIG_ARCH_LEDS
struct led_setting_s
{
uint8_t led1 : 2;
uint8_t led2 : 2;
uint8_t led3 : 2;
uint8_t unused : 2;
};
#endif
/****************************************************************************
* Private Data
****************************************************************************/
/* If CONFIG_ARCH_LEDS is defined then NuttX will control the LEDs. The
* following structures identified the LED settings for each NuttX LED state.
*/
#ifdef CONFIG_ARCH_LEDS
static const struct led_setting_s g_ledonvalues[LED_NVALUES] =
{
{LED_OFF, LED_OFF, LED_OFF, LED_OFF},
{LED_ON, LED_OFF, LED_NC, LED_OFF},
{LED_OFF, LED_ON, LED_NC, LED_OFF},
{LED_ON, LED_ON, LED_NC, LED_OFF},
{LED_NC, LED_NC, LED_ON, LED_OFF},
{LED_ON, LED_NC, LED_NC, LED_OFF},
};
static const struct led_setting_s g_ledoffvalues[LED_NVALUES] =
{
{LED_NC, LED_NC, LED_NC, LED_OFF},
{LED_NC, LED_NC, LED_NC, LED_OFF},
{LED_NC, LED_NC, LED_NC, LED_OFF},
{LED_NC, LED_NC, LED_NC, LED_OFF},
{LED_NC, LED_NC, LED_OFF, LED_OFF},
{LED_OFF, LED_NC, LED_NC, LED_OFF},
};
/* If CONFIG_ARCH_LEDS is not defined, the the user can control the LEDs in
* any way. The following array simply maps the PIC32MX_PIC32MX7MMB_LEDn
* index values to the correct LED pin configuration.
*/
#else
static const uint16_t g_ledpincfg[PIC32MX_PIC32MX7MMB_NLEDS] =
{
GPIO_LED_1, GPIO_LED_2, GPIO_LED_3
};
#endif
/****************************************************************************
* Private Functions
****************************************************************************/
/****************************************************************************
* Name: up_setleds
****************************************************************************/
#ifdef CONFIG_ARCH_LEDS
void up_setleds(FAR const struct led_setting_s *setting)
{
if (setting->led1 != LED_NC)
{
pic32mx_gpiowrite(GPIO_LED_1, setting->led1 == LED_ON);
}
if (setting->led2 != LED_NC)
{
pic32mx_gpiowrite(GPIO_LED_2, setting->led2 == LED_ON);
}
if (setting->led3 != LED_NC)
{
pic32mx_gpiowrite(GPIO_LED_3, setting->led3 == LED_ON);
}
}
#endif
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: pic32mx_ledinit
****************************************************************************/
void pic32mx_ledinit(void)
{
/* Configure output pins */
pic32mx_configgpio(GPIO_LED_1);
pic32mx_configgpio(GPIO_LED_2);
pic32mx_configgpio(GPIO_LED_3);
}
/****************************************************************************
* Name: pic32mx_setled
****************************************************************************/
#ifndef CONFIG_ARCH_LEDS
void pic32mx_setled(int led, bool ledon)
{
if ((unsigned)led < PIC32MX_PIC32MX7MMB_NLEDS)
{
pic32mx_gpiowrite(g_ledpincfg[led], ledon);
}
}
#endif
/****************************************************************************
* Name: pic32mx_setleds
****************************************************************************/
#ifndef CONFIG_ARCH_LEDS
void pic32mx_setleds(uint8_t ledset)
{
pic32mx_setled(PIC32MX_PIC32MX7MMB_LED1, (ledset & PIC32MX_PIC32MX7MMB_LED1_BIT) != 0);
pic32mx_setled(PIC32MX_PIC32MX7MMB_LED2, (ledset & PIC32MX_PIC32MX7MMB_LED2_BIT) != 0);
pic32mx_setled(PIC32MX_PIC32MX7MMB_LED3, (ledset & PIC32MX_PIC32MX7MMB_LED3_BIT) != 0);
}
#endif
/****************************************************************************
* Name: up_ledon
****************************************************************************/
#ifdef CONFIG_ARCH_LEDS
void up_ledon(int led)
{
if ((unsigned)led < LED_NVALUES)
{
up_setleds(&g_ledonvalues[led]);
}
}
#endif
/****************************************************************************
* Name: up_ledoff
****************************************************************************/
#ifdef CONFIG_ARCH_LEDS
void up_ledoff(int led)
{
if ((unsigned)led < LED_NVALUES)
{
up_setleds(&g_ledoffvalues[led]);
}
}
#endif

View File

@ -0,0 +1,382 @@
/****************************************************************************
* config/pic32mx7mmb/src/up_nsh.c
* arch/arm/src/board/up_nsh.c
*
* Copyright (C) 2012 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.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <stdio.h>
#include <unistd.h>
#include <debug.h>
#include <errno.h>
#include <nuttx/spi.h>
#include <nuttx/mmcsd.h>
#include <nuttx/usb/usbhost.h>
#include "pic32mx-internal.h"
#include "pic32mx7mmb_internal.h"
/****************************************************************************
* Pre-Processor Definitions
****************************************************************************/
/* Configuration ************************************************************/
/* Assume that we have MMC/SD, USB host (and USB device) */
#define CONFIG_NSH_HAVEMMCSD 1
#define CONFIG_NSH_HAVEUSBHOST 1
/* TheMikroelektronika PIC32MX7 MMB does not have an SD slot on board. If one
* is added, then it must be specified by defining which SPI bus that it
* is connected on.
*/
#ifndef CONFIG_PIC32MX_MMCSDSPIPORTNO
# undef CONFIG_NSH_HAVEMMCSD
#endif
/* Make sure that the configuration will support the SD card */
#ifdef CONFIG_NSH_HAVEMMCSD
/* Make sure that the NSH configuration uses the correct SPI */
# if !defined(CONFIG_NSH_MMCSDSPIPORTNO)
# define CONFIG_NSH_MMCSDSPIPORTNO CONFIG_PIC32MX_MMCSDSPIPORTNO
# elif CONFIG_NSH_MMCSDSPIPORTNO != CONFIG_PIC32MX_MMCSDSPIPORTNO
# warning "CONFIG_PIC32MX_MMCSDSPIPORTNO does not match CONFIG_NSH_MMCSDSPIPORTNO"
# undef CONFIG_NSH_MMCSDSPIPORTNO
# define CONFIG_NSH_MMCSDSPIPORTNO CONFIG_PIC32MX_MMCSDSPIPORTNO
# endif
/* Make sure that the NSH configuration uses the slot */
# if !defined(CONFIG_NSH_MMCSDSLOTNO) || CONFIG_NSH_MMCSDSLOTNO != 0
# warning "The Mikroelektronika PIC32MX7 MMB has only one slot (0)"
# undef CONFIG_NSH_MMCSDSLOTNO
# define CONFIG_NSH_MMCSDSLOTNO 0
# endif
/* Make sure that the correct SPI is enabled in the configuration */
# if CONFIG_PIC32MX_MMCSDSPIPORTNO == 1 && !defined(CONFIG_PIC32MX_SPI1)
# warning "CONFIG_PIC32MX_SPI1 is not enabled"
# undef CONFIG_NSH_HAVEMMCSD
# elif CONFIG_PIC32MX_MMCSDSPIPORTNO == 2 && !defined(CONFIG_PIC32MX_SPI2)
# warning "CONFIG_PIC32MX_SPI2 is not enabled"
# undef CONFIG_NSH_HAVEMMCSD
# elif CONFIG_PIC32MX_MMCSDSPIPORTNO == 3 && !defined(CONFIG_PIC32MX_SPI3)
# warning "CONFIG_PIC32MX_SPI3 is not enabled"
# undef CONFIG_NSH_HAVEMMCSD
# elif CONFIG_PIC32MX_MMCSDSPIPORTNO == 4 && !defined(CONFIG_PIC32MX_SPI4)
# warning "CONFIG_PIC32MX_SPI4 is not enabled"
# undef CONFIG_NSH_HAVEMMCSD
# endif
#endif
/* Can't support MMC/SD features if mountpoints are disabled */
#if defined(CONFIG_DISABLE_MOUNTPOINT)
# undef CONFIG_NSH_HAVEMMCSD
#endif
/* Select /dev/mmcsd0 if no other minor number is provided */
#ifndef CONFIG_NSH_MMCSDMINOR
# define CONFIG_NSH_MMCSDMINOR 0
#endif
/* USB Host */
#ifdef CONFIG_USBHOST
# ifndef CONFIG_PIC32MX_USBHOST
# error "CONFIG_PIC32MX_USBHOST is not selected"
# undef CONFIG_NSH_HAVEUSBHOST
# endif
#endif
#ifdef CONFIG_PIC32MX_USBHOST
# ifndef CONFIG_USBHOST
# warning "CONFIG_USBHOST is not selected"
# undef CONFIG_NSH_HAVEUSBHOST
# endif
#endif
#if !defined(CONFIG_USBHOST) || !defined(CONFIG_PIC32MX_USBHOST)
# undef CONFIG_NSH_HAVEUSBHOST
#endif
#ifdef CONFIG_NSH_HAVEUSBHOST
# ifndef CONFIG_USBHOST_DEFPRIO
# define CONFIG_USBHOST_DEFPRIO 50
# endif
# ifndef CONFIG_USBHOST_STACKSIZE
# define CONFIG_USBHOST_STACKSIZE 1024
# endif
#endif
/* Debug ********************************************************************/
#ifdef CONFIG_CPP_HAVE_VARARGS
# ifdef CONFIG_DEBUG
# define message(...) lib_lowprintf(__VA_ARGS__)
# else
# define message(...) printf(__VA_ARGS__)
# endif
#else
# ifdef CONFIG_DEBUG
# define message lib_lowprintf
# else
# define message printf
# endif
#endif
/****************************************************************************
* Private Data
****************************************************************************/
#ifdef CONFIG_NSH_HAVEUSBHOST
static struct usbhost_driver_s *g_drvr;
#endif
/****************************************************************************
* Private Functions
****************************************************************************/
/****************************************************************************
* Name: nsh_waiter
*
* Description:
* Wait for USB devices to be connected.
*
****************************************************************************/
#ifdef CONFIG_NSH_HAVEUSBHOST
static int nsh_waiter(int argc, char *argv[])
{
bool connected = false;
int ret;
message("nsh_waiter: Running\n");
for (;;)
{
/* Wait for the device to change state */
ret = DRVR_WAIT(g_drvr, connected);
DEBUGASSERT(ret == OK);
connected = !connected;
message("nsh_waiter: %s\n", connected ? "connected" : "disconnected");
/* Did we just become connected? */
if (connected)
{
/* Yes.. enumerate the newly connected device */
(void)DRVR_ENUMERATE(g_drvr);
}
}
/* Keep the compiler from complaining */
return 0;
}
#endif
/****************************************************************************
* Name: nsh_sdinitialize
*
* Description:
* Initialize SPI-based microSD.
*
****************************************************************************/
#ifdef CONFIG_NSH_HAVEMMCSD
static int nsh_sdinitialize(void)
{
FAR struct spi_dev_s *ssp;
int ret;
/* Get the SPI port */
ssp = up_spiinitialize(CONFIG_NSH_MMCSDSPIPORTNO);
if (!ssp)
{
message("nsh_archinitialize: Failed to initialize SPI port %d\n",
CONFIG_NSH_MMCSDSPIPORTNO);
ret = -ENODEV;
goto errout;
}
message("Successfully initialized SPI port %d\n",
CONFIG_NSH_MMCSDSPIPORTNO);
/* Bind the SPI port to the slot */
ret = mmcsd_spislotinitialize(CONFIG_NSH_MMCSDMINOR,
CONFIG_NSH_MMCSDSLOTNO, ssp);
if (ret < 0)
{
message("nsh_sdinitialize: "
"Failed to bind SPI port %d to MMC/SD slot %d: %d\n",
CONFIG_NSH_MMCSDSPIPORTNO,
CONFIG_NSH_MMCSDSLOTNO, ret);
goto errout;
}
message("Successfuly bound SPI port %d to MMC/SD slot %d\n",
CONFIG_NSH_MMCSDSPIPORTNO,
CONFIG_NSH_MMCSDSLOTNO);
return OK;
errout:
return ret;
}
#else
# define nsh_sdinitialize() (OK)
#endif
/****************************************************************************
* Name: nsh_usbhostinitialize
*
* Description:
* Initialize SPI-based microSD.
*
****************************************************************************/
#ifdef CONFIG_NSH_HAVEUSBHOST
static int nsh_usbhostinitialize(void)
{
int pid;
int ret;
/* First, register all of the class drivers needed to support the drivers
* that we care about:
*/
message("nsh_usbhostinitialize: Register class drivers\n");
ret = usbhost_storageinit();
if (ret != OK)
{
message("nsh_usbhostinitialize: Failed to register the mass storage class\n");
}
/* Then get an instance of the USB host interface */
message("nsh_usbhostinitialize: Initialize USB host\n");
g_drvr = usbhost_initialize(0);
if (g_drvr)
{
/* Start a thread to handle device connection. */
message("nsh_usbhostinitialize: Start nsh_waiter\n");
#ifndef CONFIG_CUSTOM_STACK
pid = task_create("usbhost", CONFIG_USBHOST_DEFPRIO,
CONFIG_USBHOST_STACKSIZE,
(main_t)nsh_waiter, (const char **)NULL);
#else
pid = task_create("usbhost", CONFIG_USBHOST_DEFPRIO,
(main_t)nsh_waiter, (const char **)NULL);
#endif
return pid < 0 ? -ENOEXEC : OK;
}
return -ENODEV;
}
#else
# define nsh_usbhostinitialize() (OK)
#endif
/****************************************************************************
* Name: nsh_usbdevinitialize
*
* Description:
* Initialize SPI-based microSD.
*
****************************************************************************/
#ifdef CONFIG_USBDEV
static int nsh_usbdevinitialize(void)
{
/* The Mikroelektronika PIC32MX7 MMB has no way to know when the USB is
* connected. So we will fake it and tell the USB driver that the USB is
* connected now.
*/
pic32mx_usbattach();
return OK;
}
#else
# define nsh_usbdevinitialize() (OK)
#endif
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: nsh_archinitialize
*
* Description:
* Perform architecture specific initialization
*
****************************************************************************/
int nsh_archinitialize(void)
{
int ret;
/* Initialize SPI-based microSD */
ret = nsh_sdinitialize();
if (ret == OK)
{
/* Initialize USB host */
ret = nsh_usbhostinitialize();
}
if (ret == OK)
{
/* Initialize USB device */
ret = nsh_usbdevinitialize();
}
return ret;
}

View File

@ -0,0 +1,223 @@
/************************************************************************************
* configs/pic32mx7mmb/src/up_ssp.c
* arch/arm/src/board/up_ssp.c
*
* Copyright (C) 2012 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.
*
************************************************************************************/
/************************************************************************************
* Included Files
************************************************************************************/
#include <nuttx/config.h>
#include <stdint.h>
#include <stdbool.h>
#include <debug.h>
#include <nuttx/spi.h>
#include <arch/board/board.h>
#include "up_arch.h"
#include "chip.h"
#include "pic32mx-internal.h"
#include "pic32mx7mmb_internal.h"
#if defined(CONFIG_PIC32MX_SPI1) || defined(CONFIG_PIC32MX_SPI2) || \
defined(CONFIG_PIC32MX_SPI3) || defined(CONFIG_PIC32MX_SPI4)
/************************************************************************************
* Definitions
************************************************************************************/
/* The following enable debug output from this file (needs CONFIG_DEBUG too).
*
* CONFIG_SPI_DEBUG - Define to enable basic SPI debug
* CONFIG_SPI_VERBOSE - Define to enable verbose SPI debug
*/
#ifdef CONFIG_SPI_DEBUG
# define sspdbg lldbg
# ifdef CONFIG_SPI_VERBOSE
# define sspvdbg lldbg
# else
# define sspvdbg(x...)
# endif
#else
# undef CONFIG_SPI_VERBOSE
# define sspdbg(x...)
# define sspvdbg(x...)
#endif
/************************************************************************************
* Private Functions
************************************************************************************/
/************************************************************************************
* Public Functions
************************************************************************************/
/************************************************************************************
* Name: pic32mx_sspinitialize
*
* Description:
* Called to configure SPI chip select GPIO pins for the Sure PIC32MX board.
*
************************************************************************************/
void weak_function pic32mx_sspinitialize(void)
{
/* Configure the SPI chip select GPIOs */
#warning "Missing logic"
}
/************************************************************************************
* Name: pic32mx_spiNselect, pic32mx_spiNstatus, and pic32mx_spiNcmddata
*
* Description:
* These external functions must be provided by board-specific logic. They are
* implementations of the select, status, and cmddata methods of the SPI interface
* defined by struct spi_ops_s (see include/nuttx/spi.h). All other methods
* including up_spiinitialize()) are provided by common PIC32MX logic. To use
* this common SPI logic on your board:
*
* 1. Provide logic in pic32mx_boardinitialize() to configure SPI/SSP chip select
* pins.
* 2. Provide pic32mx_spiNselect() and pic32mx_spiNstatus() functions
* in your board-specific logic. These functions will perform chip selection
* and status operations using GPIOs in the way your board is configured.
* 2. If CONFIG_SPI_CMDDATA is defined in the NuttX configuration, provide
* pic32mx_spiNcmddata() functions in your board-specific logic. These
* functions will perform cmd/data selection operations using GPIOs in the way
* your board is configured.
* 3. Add a call to up_spiinitialize() in your low level application
* initialization logic
* 4. The handle returned by up_spiinitialize() may then be used to bind the
* SPI driver to higher level logic (e.g., calling
* mmcsd_spislotinitialize(), for example, will bind the SPI driver to
* the SPI MMC/SD driver).
*
************************************************************************************/
struct spi_dev_s;
enum spi_dev_e;
#ifdef CONFIG_PIC32MX_SPI1
void pic32mx_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected)
{
sspdbg("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert");
#warning "Missing logic"
}
uint8_t pic32mx_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
{
sspdbg("Returning nothing\n");
#warning "Missing logic"
return 0;
}
#ifdef CONFIG_SPI_CMDDATA
int pic32mx_spi1cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd)
{
#warning "Missing logic"
return 0;
}
#endif
#endif
#ifdef CONFIG_PIC31MX_SPI1
void pic31mx_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected)
{
sspdbg("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert");
#warning "Missing logic"
}
uint8_t pic31mx_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
{
sspdbg("Returning nothing\n");
#warning "Missing logic"
return 0;
}
#ifdef CONFIG_SPI_CMDDATA
int pic31mx_spi1cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd)
{
#warning "Missing logic"
return 0;
}
#endif
#endif
#ifdef CONFIG_PIC31MX_SPI3
void pic32mx_spi3select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected)
{
sspdbg("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert");
#warning "Missing logic"
}
uint8_t pic32mx_spi3status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
{
sspdbg("Returning nothing\n");
#warning "Missing logic"
return 0;
}
#ifdef CONFIG_SPI_CMDDATA
int pic32mx_spi3cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd)
{
#warning "Missing logic"
return 0;
}
#endif
#endif
#ifdef CONFIG_PIC32MX_SPI4
void pic32mx_spi4select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected)
{
sspdbg("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert");
#warning "Missing logic"
}
uint8_t pic32mx_spi4status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
{
sspdbg("Returning nothing\n");
#warning "Missing logic"
return 0;
}
#ifdef CONFIG_SPI_CMDDATA
int pic32mx_spi4cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd)
{
#warning "Missing logic"
return 0;
}
#endif
#endif
#endif /* CONFIG_PIC32MX_SPI1..4 */

View File

@ -0,0 +1,163 @@
/************************************************************************************
* configs/pic32mx7mmb/src/up_usbdev.c
* arch/arm/src/board/up_usbdev.c
*
* Copyright (C) 2012 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.
*
************************************************************************************/
/************************************************************************************
* Included Files
************************************************************************************/
#include <nuttx/config.h>
#include <stdbool.h>
#include <debug.h>
#include <nuttx/usb/usbdev.h>
#include "pic32mx-internal.h"
#include "pic32mx7mmb_internal.h"
#if defined(CONFIG_PIC32MX_USBDEV)
/************************************************************************************
* Definitions
************************************************************************************/
/*
* PIN NAME SIGNAL NOTES
* ---- ------------------------------- -------------- ------------------------------
* 20 VBUSON/C1IN+/AN5/CN7/RB5 VBUSON To USB VBUS circuitry
* 43 C2IN+/AN3/CN5/RB3 USB_PGOOD Power good (low if bad)
*/
#define GPIO_USB_VBUSON (GPIO_INPUT|GPIO_PORTB|GPIO_PIN5)
#define GPIO_USB_PGOOD (GPIO_INPUT|GPIO_PORTB|GPIO_PIN3)
/************************************************************************************
* Private Functions
************************************************************************************/
/************************************************************************************
* Public Functions
************************************************************************************/
/************************************************************************************
* Name: pic32mx_usbdevinitialize
*
* Description:
* Called to configure the mini-A/B J5 on the Mikroelektronika PIC32MX7 MMB for the
* USB device
*
************************************************************************************/
void weak_function pic32mx_usbdevinitialize(void)
{
/* Connect the PHY to the USB mini-B port. Order and timing matter! */
pic32mx_configgpio(GPIO_USB_PGOOD);
/* Notes from the Sure Electronics sample code:
*
* "The USB specifications require that USB peripheral devices must never source
* current onto the Vbus pin. Additionally, USB peripherals should not source
* current on D+ or D- when the host/hub is not actively powering the Vbus line.
* When designing a self powered (as opposed to bus powered) USB peripheral
* device, the firmware should make sure not to turn on the USB module and D+
* or D- pull up resistor unless Vbus is actively powered. Therefore, the
* firmware needs some means to detect when Vbus is being powered by the host.
* A 5V tolerant I/O pin can be connected to Vbus (through a resistor), and
* can be used to detect when Vbus is high (host actively powering), or low
* (host is shut down or otherwise not supplying power). The USB firmware
* can then periodically poll this I/O pin to know when it is okay to turn on
* the USB module/D+/D- pull up resistor. When designing a purely bus powered
* peripheral device, it is not possible to source current on D+ or D- when the
* host is not actively providing power on Vbus. Therefore, implementing this
* bus sense feature is optional. ..."
*/
#ifdef CONFIG_USBHOST
// pic32mx_configgpio(GPIO_USB_VBUSON);
#endif
/* "If the host PC sends a GetStatus (device) request, the firmware must respond
* and let the host know if the USB peripheral device is currently bus powered
* or self powered. See chapter 9 in the official USB specifications for details
* regarding this request. If the peripheral device is capable of being both
* self and bus powered, it should not return a hard coded value for this request.
* Instead, firmware should check if it is currently self or bus powered, and
* respond accordingly. If the hardware has been configured like demonstrated
* on the PICDEM FS USB Demo Board, an I/O pin can be polled to determine the
* currently selected power source. ..."
*/
#ifdef CONFIG_USB_PWRSENSE
// pic32mx_configgpio(GPIO_USB_PWRSENSE);
#endif
}
/************************************************************************************
* Name: pic32mx_usbpullup
*
* Description:
* If USB is supported and the board supports a pullup via GPIO (for USB
* software connect and disconnect), then the board software must provide
* stm32_pullup. See include/nuttx/usb/usbdev.h for additional description
* of this method. Alternatively, if no pull-up GPIO the following EXTERN
* can be redefined to be NULL.
*
************************************************************************************/
int pic32mx_usbpullup(FAR struct usbdev_s *dev, bool enable)
{
/* The Mikroelektronika PIC32MX7 MMB does not have a USB pull-up */
return OK;
}
/************************************************************************************
* Name: pic32mx_usbsuspend
*
* Description:
* Board logic must provide the stm32_usbsuspend logic if the USBDEV driver
* is used. This function is called whenever the USB enters or leaves
* suspend mode. This is an opportunity for the board logic to shutdown
* clocks, power, etc. while the USB is suspended.
*
************************************************************************************/
void pic32mx_usbsuspend(FAR struct usbdev_s *dev, bool resume)
{
/* Do nothing */
}
#endif /* CONFIG_PIC32MX_USBDEV */

View File

@ -0,0 +1,95 @@
/****************************************************************************
* configs/pic32mx7mmb/src/up_usbmsc.c
*
* Copyright (C) 2012 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.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include "pic32mx7mmb_internal.h"
/****************************************************************************
* Pre-Processor Definitions
****************************************************************************/
/* Configuration ************************************************************/
/* Debug ********************************************************************/
#ifdef CONFIG_CPP_HAVE_VARARGS
# ifdef CONFIG_DEBUG
# define message(...) lib_lowprintf(__VA_ARGS__)
# define msgflush()
# else
# define message(...) printf(__VA_ARGS__)
# define msgflush() fflush(stdout)
# endif
#else
# ifdef CONFIG_DEBUG
# define message lib_lowprintf
# define msgflush()
# else
# define message printf
# define msgflush() fflush(stdout)
# endif
#endif
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: usbmsc_archinitialize
*
* Description:
* Perform architecture specific initialization as needed to establish
* the mass storage device that will be exported by the USB MSC device.
*
****************************************************************************/
int usbmsc_archinitialize(void)
{
/* If examples/usbmsc is built as an NSH command, then SD slot should
* already have been initized in nsh_archinitialize() (see up_nsh.c). In
* this case, there is nothing further to be done here.
*/
#ifndef CONFIG_EXAMPLES_USBMSC_BUILTIN
# warning "Missing Logic"
#endif /* CONFIG_EXAMPLES_USBMSC_BUILTIN */
return 0;
}

View File

@ -0,0 +1,106 @@
/************************************************************************************
* configs/pic32mx7mmb/src/up_usbterm.c
* arch/arm/src/board/up_usbterm.c
*
* Copyright (C) 2012 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.
*
************************************************************************************/
/************************************************************************************
* Included Files
************************************************************************************/
#include <nuttx/config.h>
#include <stdbool.h>
#include <debug.h>
#include <nuttx/usb/usbdev.h>
#include "pic32mx-internal.h"
#include "pic32mx7mmb_internal.h"
#if defined(CONFIG_PIC32MX_USBDEV) && defined(CONFIG_EXAMPLES_USBTERM_DEVINIT)
/************************************************************************************
* Definitions
************************************************************************************/
/************************************************************************************
* Private Functions
************************************************************************************/
/************************************************************************************
* Public Functions
************************************************************************************/
/****************************************************************************
* Name:
*
* Description:
* If CONFIG_EXAMPLES_USBTERM_DEVINIT is defined, then the example will
* call this user provided function as part of its initialization.
*
****************************************************************************/
int usbterm_devinit(void)
{
/* The Mikroelektronika PIC32MX7 MMB has no way to know when the USB is
* connected. So we will fake it and tell the USB driver that the USB is
* connected now.
*
* If examples/usbterm is built as an NSH built-in application, then
* pic32mx_usbattach() will be called in nsh_archinitialize().
*/
#ifndef CONFIG_EXAMPLES_USBTERM_BUILTIN
pic32mx_usbattach();
#endif
return OK;
}
/****************************************************************************
* Name:
*
* Description:
* If CONFIG_EXAMPLES_USBTERM_DEVINIT is defined, then the example will
* call this user provided function as part of its termination sequence.
*
****************************************************************************/
void usbterm_devuninit(void)
{
/* Tell the USB driver that the USB is no longer connected */
pic32mx_usbdetach();
}
#endif /* CONFIG_PIC32MX_USBDEV && CONFIG_EXAMPLES_USBTERM_DEVINIT */

View File

@ -0,0 +1,51 @@
############################################################################
# configs/pic32mx7mmb/tools/Makefile
#
# Copyright (C) 2011-2012 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.
#
############################################################################
all: mkpichex
default: mkpichex
.PHONY: clean
# Add CFLAGS=-g on the make command line to build debug versions
CFLAGS = -O2 -Wall -I.
# mkpichex - Convert virtual addresses in nuttx.hex to physical addresses
mkconfig: mkpichex.c mkpichex.c
@gcc $(CFLAGS) -o mkpichex mkpichex.c
clean:
@rm -f *.o *.a *~ .*.swp
@rm -f mkpichex mkpichex.exe

View File

@ -0,0 +1,315 @@
/****************************************************************************
* configs/pic32mx7mmb/tools/mkpichex.c
*
* Copyright (C) 2011-2012 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.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include <stdio.h>
#include <string.h>
#include <stdlib.h>
#include <errno.h>
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
#define MAX_LINE 1024
/* Line offsets */
#define START_OFFSET 0
#define LEN_OFFSET 1
#define ADDR_OFFSET (LEN_OFFSET + 2)
#define TYPE_OFFSET (ADDR_OFFSET + 4)
#define PAYLOAD_OFFSET (TYPE_OFFSET + 2)
#define CHKSUM_OFFSET(n) (PAYLOAD_OFFSET+2*(n))
/* Record types:
*
* 00, data record, contains data and 16-bit address. The format described
* above.
* 01, End Of File record, a file termination record. No data. Has to be
* the last line of the file, only one per file permitted. Usually
* ':00000001FF'. Originally the End Of File record could contain a
* start address for the program being loaded, e.g. :00AB2F0125
* would make a jump to address AB2F. This was convenient when programs
* were loaded from punched paper tape.
* 02, Extended Segment Address Record, segment-base address. Used when 16
* bits are not enough, identical to 80x86 real mode addressing. The
* address specified by the 02 record is multiplied by 16 (shifted 4
* bits left) and added to the subsequent 00 record addresses. This
* allows addressing of up to a megabyte of address space. The address
* field of this record has to be 0000, the byte count is 02 (the segment
* is 16-bit). The least significant hex digit of the segment address is
* always 0.
* 03, Start Segment Address Record. For 80x86 processors, it specifies the
* initial content of the CS:IP registers. The address field is 0000, the
* byte count is 04, the first two bytes are the CS value, the latter two
* are the IP value.
* 04, Extended Linear Address Record, allowing for fully 32 bit addressing.
* The address field is 0000, the byte count is 02. The two data bytes
* represent the upper 16 bits of the 32 bit address, when combined with
* the address of the 00 type record.
* 05, Start Linear Address Record. The address field is 0000, the byte
* count is 04. The 4 data bytes represent the 32-bit value loaded into
* the EIP register of the 80386 and higher CPU.
*/
#define TYPE_DATA 0
#define TYPE_EOF 1
#define TYPE_EXTSEG 2
#define TYPE_STARTSEG 3
#define TYPE_EXTLIN 4
#define TYPE_STARTLIN 5
/****************************************************************************
* Private Types
****************************************************************************/
struct hex_s
{
unsigned char len; /* Length of the data payload */
unsigned char type; /* Record type */
unsigned short addr; /* Lower 16-bit address */
};
/****************************************************************************
* Private Data
****************************************************************************/
static char line[MAX_LINE+1];
/****************************************************************************
* Private Functions
****************************************************************************/
static inline char *getfilepath(const char *path, const char *name, const char *extension)
{
snprintf(line, MAX_LINE, "%s/%s.%s", path, name, extension);
line[MAX_LINE] = '\0';
return strdup(line);
}
static void show_usage(const char *progname)
{
fprintf(stderr, "USAGE: %s <abs path to nuttx.hex>\n", progname);
exit(1);
}
static unsigned char get4(char hex)
{
if (hex >= '0' && hex <= '9')
{
return hex - '0';
}
else if (hex >= 'a' && hex <= 'f')
{
return hex - 'a' + 10;
}
else if (hex >= 'A' && hex <= 'F')
{
return hex - 'A' + 10;
}
fprintf(stderr, "Bad hex character code: %s\n", line);
exit(2);
}
static unsigned char get8(const char *ptr)
{
return get4(ptr[0]) << 4 | get4(ptr[1]);
}
static unsigned short get16(const char *ptr)
{
return (unsigned short)get8(&ptr[0]) << 8 | (unsigned short)get8(&ptr[2]);
}
static int parse_line(struct hex_s *hexline)
{
/* :LLAAAATT... */
if (line[START_OFFSET] != ':')
{
fprintf(stderr, "Bad start code: %s\n", line);
return 1;
}
hexline->len = get8(&line[LEN_OFFSET]);
hexline->addr = get16(&line[ADDR_OFFSET]);
hexline->type = get8(&line[TYPE_OFFSET]);
return 0;
}
#if 0
static unsigned char checksum(chksum_ndx)
{
int chksum = 0;
int ndx;
for (ndx = 1; ndx < chksum_ndx; ndx += 2)
{
chksum += (int)get8(&line[ndx]);
}
return (unsigned char)((-chksum) & 0xff);
}
#endif
static void adjust_extlin(struct hex_s *hexline)
{
unsigned short segment;
int chksum;
/* Make sure that the payload is exactly 2 bytes */
if (hexline->len != 2)
{
fprintf(stderr, "Bad length on extended segment address record\n");
fprintf(stderr, " %s", line);
}
/* And the address field is supposed to be zero */
if (hexline->addr != 0)
{
fprintf(stderr, "Bad address on extended segment address record\n");
fprintf(stderr, " %s", line);
}
/* Decode the 2 byte payload */
segment = get16(&line[PAYLOAD_OFFSET]);
/* Convert the address to a 29-bit physical address */
segment &= 0x1fff;
/* Recalculate the checksum and make sure that there is a null terminator
* Since len=2, addr=0, type=4, the is a trivial calculation.
*/
chksum = (-(segment + (segment >> 8) + 6)) & 0xff;
/* Then create the new output record */
snprintf(line, MAX_LINE-PAYLOAD_OFFSET, ":02000004%04X%02X\n", segment, chksum);
}
/****************************************************************************
* Public Functions
****************************************************************************/
int main(int argc, char **argv, char **envp)
{
struct hex_s hexline;
char *srcfile;
char *destfile;
FILE *src;
FILE *dest;
if (argc != 2)
{
fprintf(stderr, "Unexpected number of arguments\n");
show_usage(argv[0]);
}
srcfile = getfilepath(argv[1], "nuttx", "hex");
if (!srcfile)
{
fprintf(stderr, "getfilepath failed\n");
exit(2);
}
destfile = getfilepath(argv[1], "nuttx", "tmp");
if (!destfile)
{
fprintf(stderr, "getfilepath failed\n");
exit(2);
}
src = fopen(srcfile, "r");
if (!src)
{
fprintf(stderr, "open %s failed: %s\n", srcfile, strerror(errno));
exit(3);
}
dest = fopen(destfile, "w");
if (!dest)
{
fprintf(stderr, "open %s failed: %s\n", destfile, strerror(errno));
exit(3);
}
/* Read each line from the source file */
while (fgets(line, MAX_LINE, src) != NULL)
{
if (parse_line(&hexline))
{
fprintf(stderr, "Failed to parse line\n");
exit(1);
}
/* Adjust 'Extended Segment Address Records'. */
if (hexline.type == TYPE_EXTLIN)
{
adjust_extlin(&hexline);
}
fputs(line, dest);
}
fclose(src);
fclose(dest);
/* Remove the original nuttx.hex file */
if (remove(srcfile) != 0)
{
fprintf(stderr, "Failed to remove the old '%s'\n", srcfile);
}
/* Rename the new nuttx.tmp file to nuttx.hex */
if (rename(destfile, srcfile) != 0)
{
fprintf(stderr, "Failed to rename '%s' to '%s'\n", destfile, srcfile);
}
return 0;
}