diff --git a/ChangeLog b/ChangeLog index ee494ee592..f3ccb3f583 100644 --- a/ChangeLog +++ b/ChangeLog @@ -2534,4 +2534,6 @@ * configs/sure-pic32mx/usbnsh and configs/sure-pic32mx/src: Add support for NSH using only USB serial I/O to support the console. This is useful on devices that have USB, but no serial port. + * arch/mips/src/pic32mx/pic32mx_spi.c: Add a PIC32 SPI driver. Initial + checkin is primitive, incomplete (lacks interrupt logic), and untested. diff --git a/arch/arm/src/lpc17xx/Make.defs b/arch/arm/src/lpc17xx/Make.defs old mode 100755 new mode 100644 diff --git a/arch/arm/src/lpc17xx/chip.h b/arch/arm/src/lpc17xx/chip.h old mode 100755 new mode 100644 diff --git a/arch/arm/src/lpc17xx/lpc17_adc.h b/arch/arm/src/lpc17xx/lpc17_adc.h old mode 100755 new mode 100644 diff --git a/arch/arm/src/lpc17xx/lpc17_allocateheap.c b/arch/arm/src/lpc17xx/lpc17_allocateheap.c old mode 100755 new mode 100644 diff --git a/arch/arm/src/lpc17xx/lpc17_can.c b/arch/arm/src/lpc17xx/lpc17_can.c old mode 100755 new mode 100644 diff --git a/arch/arm/src/lpc17xx/lpc17_can.h b/arch/arm/src/lpc17xx/lpc17_can.h old mode 100755 new mode 100644 diff --git a/arch/arm/src/lpc17xx/lpc17_clockconfig.c b/arch/arm/src/lpc17xx/lpc17_clockconfig.c old mode 100755 new mode 100644 diff --git a/arch/arm/src/lpc17xx/lpc17_clrpend.c b/arch/arm/src/lpc17xx/lpc17_clrpend.c old mode 100755 new mode 100644 diff --git a/arch/arm/src/lpc17xx/lpc17_dac.h b/arch/arm/src/lpc17xx/lpc17_dac.h old mode 100755 new mode 100644 diff --git a/arch/arm/src/lpc17xx/lpc17_emacram.h b/arch/arm/src/lpc17xx/lpc17_emacram.h old mode 100755 new mode 100644 diff --git a/arch/arm/src/lpc17xx/lpc17_ethernet.h b/arch/arm/src/lpc17xx/lpc17_ethernet.h old mode 100755 new mode 100644 diff --git a/arch/arm/src/lpc17xx/lpc17_gpdma.c b/arch/arm/src/lpc17xx/lpc17_gpdma.c old mode 100755 new mode 100644 diff --git a/arch/arm/src/lpc17xx/lpc17_gpdma.h b/arch/arm/src/lpc17xx/lpc17_gpdma.h old mode 100755 new mode 100644 diff --git a/arch/arm/src/lpc17xx/lpc17_gpio.c b/arch/arm/src/lpc17xx/lpc17_gpio.c old mode 100755 new mode 100644 diff --git a/arch/arm/src/lpc17xx/lpc17_gpio.h b/arch/arm/src/lpc17xx/lpc17_gpio.h old mode 100755 new mode 100644 diff --git a/arch/arm/src/lpc17xx/lpc17_gpiodbg.c b/arch/arm/src/lpc17xx/lpc17_gpiodbg.c old mode 100755 new mode 100644 diff --git a/arch/arm/src/lpc17xx/lpc17_gpioint.c b/arch/arm/src/lpc17xx/lpc17_gpioint.c old mode 100755 new mode 100644 diff --git a/arch/arm/src/lpc17xx/lpc17_i2c.c b/arch/arm/src/lpc17xx/lpc17_i2c.c old mode 100755 new mode 100644 diff --git a/arch/arm/src/lpc17xx/lpc17_i2c.h b/arch/arm/src/lpc17xx/lpc17_i2c.h old mode 100755 new mode 100644 diff --git a/arch/arm/src/lpc17xx/lpc17_i2s.h b/arch/arm/src/lpc17xx/lpc17_i2s.h old mode 100755 new mode 100644 diff --git a/arch/arm/src/lpc17xx/lpc17_idle.c b/arch/arm/src/lpc17xx/lpc17_idle.c old mode 100755 new mode 100644 diff --git a/arch/arm/src/lpc17xx/lpc17_internal.h b/arch/arm/src/lpc17xx/lpc17_internal.h old mode 100755 new mode 100644 diff --git a/arch/arm/src/lpc17xx/lpc17_irq.c b/arch/arm/src/lpc17xx/lpc17_irq.c old mode 100755 new mode 100644 diff --git a/arch/arm/src/lpc17xx/lpc17_lowputc.c b/arch/arm/src/lpc17xx/lpc17_lowputc.c old mode 100755 new mode 100644 diff --git a/arch/arm/src/lpc17xx/lpc17_mcpwm.h b/arch/arm/src/lpc17xx/lpc17_mcpwm.h old mode 100755 new mode 100644 diff --git a/arch/arm/src/lpc17xx/lpc17_memorymap.h b/arch/arm/src/lpc17xx/lpc17_memorymap.h old mode 100755 new mode 100644 diff --git a/arch/arm/src/lpc17xx/lpc17_ohciram.h b/arch/arm/src/lpc17xx/lpc17_ohciram.h old mode 100755 new mode 100644 diff --git a/arch/arm/src/lpc17xx/lpc17_pinconn.h b/arch/arm/src/lpc17xx/lpc17_pinconn.h old mode 100755 new mode 100644 diff --git a/arch/arm/src/lpc17xx/lpc17_pwm.h b/arch/arm/src/lpc17xx/lpc17_pwm.h old mode 100755 new mode 100644 diff --git a/arch/arm/src/lpc17xx/lpc17_qei.h b/arch/arm/src/lpc17xx/lpc17_qei.h old mode 100755 new mode 100644 diff --git a/arch/arm/src/lpc17xx/lpc17_rit.h b/arch/arm/src/lpc17xx/lpc17_rit.h old mode 100755 new mode 100644 diff --git a/arch/arm/src/lpc17xx/lpc17_rtc.h b/arch/arm/src/lpc17xx/lpc17_rtc.h old mode 100755 new mode 100644 diff --git a/arch/arm/src/lpc17xx/lpc17_serial.c b/arch/arm/src/lpc17xx/lpc17_serial.c old mode 100755 new mode 100644 diff --git a/arch/arm/src/lpc17xx/lpc17_serial.h b/arch/arm/src/lpc17xx/lpc17_serial.h old mode 100755 new mode 100644 diff --git a/arch/arm/src/lpc17xx/lpc17_spi.c b/arch/arm/src/lpc17xx/lpc17_spi.c old mode 100755 new mode 100644 diff --git a/arch/arm/src/lpc17xx/lpc17_spi.h b/arch/arm/src/lpc17xx/lpc17_spi.h old mode 100755 new mode 100644 diff --git a/arch/arm/src/lpc17xx/lpc17_ssp.c b/arch/arm/src/lpc17xx/lpc17_ssp.c old mode 100755 new mode 100644 diff --git a/arch/arm/src/lpc17xx/lpc17_ssp.h b/arch/arm/src/lpc17xx/lpc17_ssp.h old mode 100755 new mode 100644 diff --git a/arch/arm/src/lpc17xx/lpc17_start.c b/arch/arm/src/lpc17xx/lpc17_start.c old mode 100755 new mode 100644 diff --git a/arch/arm/src/lpc17xx/lpc17_syscon.h b/arch/arm/src/lpc17xx/lpc17_syscon.h old mode 100755 new mode 100644 diff --git a/arch/arm/src/lpc17xx/lpc17_timer.h b/arch/arm/src/lpc17xx/lpc17_timer.h old mode 100755 new mode 100644 diff --git a/arch/arm/src/lpc17xx/lpc17_timerisr.c b/arch/arm/src/lpc17xx/lpc17_timerisr.c old mode 100755 new mode 100644 diff --git a/arch/arm/src/lpc17xx/lpc17_uart.h b/arch/arm/src/lpc17xx/lpc17_uart.h old mode 100755 new mode 100644 diff --git a/arch/arm/src/lpc17xx/lpc17_usb.h b/arch/arm/src/lpc17xx/lpc17_usb.h old mode 100755 new mode 100644 diff --git a/arch/arm/src/lpc17xx/lpc17_usbdev.c b/arch/arm/src/lpc17xx/lpc17_usbdev.c old mode 100755 new mode 100644 diff --git a/arch/arm/src/lpc17xx/lpc17_usbhost.c b/arch/arm/src/lpc17xx/lpc17_usbhost.c old mode 100755 new mode 100644 diff --git a/arch/arm/src/lpc17xx/lpc17_vectors.S b/arch/arm/src/lpc17xx/lpc17_vectors.S old mode 100755 new mode 100644 diff --git a/arch/arm/src/lpc17xx/lpc17_wdt.h b/arch/arm/src/lpc17xx/lpc17_wdt.h old mode 100755 new mode 100644 diff --git a/arch/mips/include/pic32mx/irq_5xx6xx7xx.h b/arch/mips/include/pic32mx/irq_5xx6xx7xx.h index 05bd8bf197..e940793143 100755 --- a/arch/mips/include/pic32mx/irq_5xx6xx7xx.h +++ b/arch/mips/include/pic32mx/irq_5xx6xx7xx.h @@ -1,7 +1,7 @@ /**************************************************************************** * arch/mips/include/pic32mx/irq_5xx6xx7xx.h * - * Copyright (C) 2011 Gregory Nutt. All rights reserved. + * Copyright (C) 2011-2012 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -148,8 +148,8 @@ #define PIC32MX_IRQSRC_IC5 (128+21) /* Vector: 21, Input Capture 5 */ #define PIC32MX_IRQSRC_OC5 (128+22) /* Vector: 22, Output Compare 5 */ #define PIC32MX_IRQSRC_SPI1E (128+23) /* Vector: 23, SPI1 Fault */ -#define PIC32MX_IRQSRC_SPI1TX (128+24) /* Vector: 23, " " Receive done */ -#define PIC32MX_IRQSRC_SPI1RX (128+25) /* Vector: 23, " " Transfer done */ +#define PIC32MX_IRQSRC_SPI1RX (128+24) /* Vector: 23, " " Receive done */ +#define PIC32MX_IRQSRC_SPI1TX (128+25) /* Vector: 23, " " Transfer done */ #define PIC32MX_IRQSRC_26 (128+26) /* Vector: 24, UART1, SPI3, I2C3 */ # define PIC32MX_IRQSRC_U1E (128+26) /* Vector: 24, UART1 Error */ # define PIC32MX_IRQSRC_SPI3E (128+26) /* Vector: 24, SPI3 Fault */ diff --git a/arch/mips/src/pic32mx/Make.defs b/arch/mips/src/pic32mx/Make.defs index 504348c60f..44469b927e 100644 --- a/arch/mips/src/pic32mx/Make.defs +++ b/arch/mips/src/pic32mx/Make.defs @@ -1,7 +1,7 @@ ############################################################################ # arch/mips/src/pic32mx/Make.defs # -# Copyright (C) 2011 Gregory Nutt. All rights reserved. +# Copyright (C) 2011-2012 Gregory Nutt. All rights reserved. # Author: Gregory Nutt # # Redistribution and use in source and binary forms, with or without @@ -62,7 +62,8 @@ endif CHIP_ASRCS = CHIP_CSRCS = pic32mx-irq.c pic32mx-decodeirq.c pic32mx-exception.c pic32mx-gpio.c \ - pic32mx-lowconsole.c pic32mx-lowinit.c pic32mx-serial.c pic32mx-timerisr.c + pic32mx-lowconsole.c pic32mx-lowinit.c pic32mx-serial.c pic32mx-spi.c \ + pic32mx-timerisr.c # Configuration-dependent PIC32MX files diff --git a/arch/mips/src/pic32mx/pic32mx-spi.c b/arch/mips/src/pic32mx/pic32mx-spi.c new file mode 100644 index 0000000000..d884511e8d --- /dev/null +++ b/arch/mips/src/pic32mx/pic32mx-spi.c @@ -0,0 +1,852 @@ +/**************************************************************************** + * arch/mips/src/pic32mx/pic32mx-spi.c + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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 + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "up_internal.h" +#include "up_arch.h" + +#include "chip.h" +#include "pic32mx-internal.h" +#include "pic32mx-spi.h" + +#if defined(CONFIG_PIC32MX_SPI1) || defined(CONFIG_PIC32MX_SPI2) || \ + defined(CONFIG_PIC32MX_SPI3) || defined(CONFIG_PIC32MX_SPI4) + +/**************************************************************************** + * Definitions + ****************************************************************************/ +/* Enables non-standard debug output from this file */ + +#ifndef CONFIG_DEBUG +# undef CONFIG_DEBUG_SPI +#endif + +#ifdef CONFIG_DEBUG_SPI +# define spidbg lldbg +# ifdef CONFIG_DEBUG_VERBOSE +# define spivdbg lldbg +# else +# define spivdbg(x...) +# endif +#else +# undef CONFIG_DEBUG_VERBOSE +# define spidbg(x...) +# define spivdbg(x...) +#endif + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +/* This structure descibes the state of the SSP driver */ + +struct pic32mx_dev_s +{ + struct spi_dev_s spidev; /* Externally visible part of the SPI interface */ + uint32_t base; /* SPI register base address */ +#ifdef CONFIG_PIC32MX_SPI_INTERRUPTS + uint8_t vector; /* Interrupt vector number(for attaching) */ + uint8_t eirq; /* SPI fault interrupt number */ + uint8_t rxirq; /* SPI receive done interrupt number */ + uint8_t txirq; /* SPI transfer done interrupt number */ +#endif +#ifndef CONFIG_SPI_OWNBUS + sem_t exclsem; /* Held while chip is selected for mutual exclusion */ + uint32_t frequency; /* Requested clock frequency */ + uint32_t actual; /* Actual clock frequency */ + uint8_t nbits; /* Width of word in bits (8 to 16) */ + uint8_t mode; /* Mode 0,1,2,3 */ +#endif +}; + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ +/* Low-level register access */ + +static uint32_t spi_getreg(FAR struct pic32mx_dev_s *priv, + unsigned int offset); +static void spi_putreg(FAR struct pic32mx_dev_s *priv, + unsigned int offset, uint32_t value); + +/* SPI methods */ + +#ifndef CONFIG_SPI_OWNBUS +static int spi_lock(FAR struct spi_dev_s *dev, bool lock); +#endif +static uint32_t spi_setfrequency(FAR struct spi_dev_s *dev, uint32_t frequency); +static void spi_setmode(FAR struct spi_dev_s *dev, enum spi_mode_e mode); +static void spi_setbits(FAR struct spi_dev_s *dev, int nbits); +static uint16_t spi_send(FAR struct spi_dev_s *dev, uint16_t ch); +static void spi_sndblock(FAR struct spi_dev_s *dev, FAR const void *buffer, size_t nwords); +static void spi_recvblock(FAR struct spi_dev_s *dev, FAR void *buffer, size_t nwords); + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +#ifdef CONFIG_PIC32MX_SPI1 + +static const struct spi_ops_s g_spi1ops = +{ +#ifndef CONFIG_SPI_OWNBUS + .lock = spi_lock, +#endif + .select = pic32mx_spi1select, + .setfrequency = spi_setfrequency, + .setmode = spi_setmode, + .setbits = spi_setbits, + .status = pic32mx_spi1status, +#ifdef CONFIG_SPI_CMDDATA + .cmddata = pic32mx_spi1cmddata, +#endif + .send = spi_send, + .sndblock = spi_sndblock, + .recvblock = spi_recvblock, +#ifdef CONFIG_SPI_CALLBACK + .registercallback = pic32mx_spi1register, /* Provided externally */ +#else + .registercallback = 0, /* Not implemented */ +#endif +}; + +static struct pic32mx_dev_s g_spi1dev = +{ + .spidev = { &g_spi1ops }, + .base = PIC32MX_SPI1_K1BASE, +#ifdef CONFIG_PIC32MX_SPI_INTERRUPTS + .vector = PIC32MX_IRQ_SPI1, + .eirq = PIC32MX_IRQSRC_SPI1E, + .rxirq = PIC32MX_IRQSRC_SPI1RX, + .txirq = PIC32MX_IRQSRC_SPI1TX, +#endif +}; +#endif + +#ifdef CONFIG_PIC32MX_SPI2 +static const struct spi_ops_s g_spi2ops = +{ +#ifndef CONFIG_SPI_OWNBUS + .lock = spi_lock, +#endif + .select = pic32mx_spi2select, + .setfrequency = spi_setfrequency, + .setmode = spi_setmode, + .setbits = spi_setbits, + .status = pic32mx_spi2status, +#ifdef CONFIG_SPI_CMDDATA + .cmddata = pic32mx_spi2cmddata, +#endif + .send = spi_send, + .sndblock = spi_sndblock, + .recvblock = spi_recvblock, +#ifdef CONFIG_SPI_CALLBACK + .registercallback = pic32mx_spi2register, /* Provided externally */ +#else + .registercallback = 0, /* Not implemented */ +#endif +}; + +static struct pic32mx_dev_s g_spi2dev = +{ + .spidev = { &g_spi2ops }, + .base = PIC32MX_SPI2_K1BASE, +#ifdef CONFIG_PIC32MX_SPI_INTERRUPTS + .vector = PIC32MX_IRQ_SPI2, + .eirq = PIC32MX_IRQSRC_SPI2E, + .rxirq = PIC32MX_IRQSRC_SPI2RX, + .txirq = PIC32MX_IRQSRC_SPI2TX, +#endif +}; +#endif + +#ifdef CONFIG_PIC32MX_SPI3 +static const struct spi_ops_s g_spi3ops = +{ +#ifndef CONFIG_SPI_OWNBUS + .lock = spi_lock, +#endif + .select = pic32mx_spi3select, + .setfrequency = spi_setfrequency, + .setmode = spi_setmode, + .setbits = spi_setbits, + .status = pic32mx_spi3status, +#ifdef CONFIG_SPI_CMDDATA + .cmddata = pic32mx_spi3cmddata, +#endif + .send = spi_send, + .sndblock = spi_sndblock, + .recvblock = spi_recvblock, +#ifdef CONFIG_SPI_CALLBACK + .registercallback = pic32mx_spi3register, /* Provided externally */ +#else + .registercallback = 0, /* Not implemented */ +#endif +}; + +static struct pic32mx_dev_s g_spi3dev = +{ + .spidev = { &g_spi3ops }, + .base = PIC32MX_SPI3_K1BASE, +#ifdef CONFIG_PIC32MX_SPI_INTERRUPTS + .vector = PIC32MX_IRQ_SPI4, + .eirq = PIC32MX_IRQSRC_SPI3E, + .rxirq = PIC32MX_IRQSRC_SPI3RX, + .txirq = PIC32MX_IRQSRC_SPI3TX, +#endif +}; +#endif + +#ifdef CONFIG_PIC32MX_SPI4 +static const struct spi_ops_s g_spi4ops = +{ +#ifndef CONFIG_SPI_OWNBUS + .lock = spi_lock, +#endif + .select = pic32mx_spi4select, + .setfrequency = spi_setfrequency, + .setmode = spi_setmode, + .setbits = spi_setbits, + .status = pic32mx_spi4status, +#ifdef CONFIG_SPI_CMDDATA + .cmddata = pic32mx_spi4cmddata, +#endif + .send = spi_send, + .sndblock = spi_sndblock, + .recvblock = spi_recvblock, +#ifdef CONFIG_SPI_CALLBACK + .registercallback = pic32mx_spi4register, /* Provided externally */ +#else + .registercallback = 0, /* Not implemented */ +#endif +}; + +static struct pic32mx_dev_s g_spi4dev = +{ + .spidev = { &g_spi4ops }, + .base = PIC32MX_SPI4_K1BASE, +#ifdef CONFIG_PIC32MX_SPI_INTERRUPTS + .vector = PIC32MX_IRQ_SPI4, + .eirq = PIC32MX_IRQSRC_SPI4E, + .rxirq = PIC32MX_IRQSRC_SPI4RX, + .txirq = PIC32MX_IRQSRC_SPI4TX, +#endif +}; +#endif + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: spi_getreg + * + * Description: + * Return the contents of one, 32-bit SPI register + * + * Input Parameters: + * priv - A pointer to a PIC32MX SPI state structure + * offset - Offset from the SPI base address to the register of interest + * + * Returned Value: + * The current contents of the register + * + ****************************************************************************/ + +static uint32_t spi_getreg(FAR struct pic32mx_dev_s *priv, unsigned int offset) +{ + return getreg32(priv->base + offset); +} + +/**************************************************************************** + * Name: spi_getreg + * + * Description: + * Write a value to one, 32-bit SPI register + * + * Input Parameters: + * priv - A pointer to a PIC32MX SPI state structure + * offset - Offset from the SPI base address to the register of interest + * value - The value to write to the SPI register + * + * Returned Value: + * None + * + ****************************************************************************/ + +static void spi_putreg(FAR struct pic32mx_dev_s *priv, unsigned int offset, + uint32_t value) +{ + putreg32(value, priv->base + offset); +} + +/**************************************************************************** + * Name: spi_lock + * + * Description: + * On SPI busses where there are multiple devices, it will be necessary to + * lock SPI to have exclusive access to the busses for a sequence of + * transfers. The bus should be locked before the chip is selected. After + * locking the SPI bus, the caller should then also call the setfrequency, + * setbits, and setmode methods to make sure that the SPI is properly + * configured for the device. If the SPI buss is being shared, then it + * may have been left in an incompatible state. + * + * Input Parameters: + * dev - Device-specific state data + * lock - true: Lock spi bus, false: unlock SPI bus + * + * Returned Value: + * None + * + ****************************************************************************/ + +#ifndef CONFIG_SPI_OWNBUS +static int spi_lock(FAR struct spi_dev_s *dev, bool lock) +{ + FAR struct pic32mx_dev_s *priv = (FAR struct pic32mx_dev_s *)dev; + + if (lock) + { + /* Take the semaphore (perhaps waiting) */ + + while (sem_wait(&priv->exclsem) != 0) + { + /* The only case that an error should occur here is if the wait was awakened + * by a signal. + */ + + ASSERT(errno == EINTR); + } + } + else + { + (void)sem_post(&priv->exclsem); + } + return OK; +} +#endif + +/**************************************************************************** + * Name: spi_setfrequency + * + * Description: + * Set the SPI frequency. + * + * Input Parameters: + * dev - Device-specific state data + * frequency - The SPI frequency requested + * + * Returned Value: + * Returns the actual frequency selected + * + ****************************************************************************/ + +static uint32_t spi_setfrequency(FAR struct spi_dev_s *dev, uint32_t frequency) +{ + FAR struct pic32mx_dev_s *priv = (FAR struct pic32mx_dev_s *)dev; + uint32_t divisor; + uint32_t actual; + uint32_t regval; + + /* Check if the requested frequency is the same as the frequency selection */ + +#ifndef CONFIG_SPI_OWNBUS + if (priv->frequency == frequency) + { + /* We are already at this frequency. Return the actual. */ + + return priv->actual; + } +#endif + + /* Calculate the divisor + * + * frequency = BOARD_PBCLOCK / (2 * divisor), or + * divisor = (BOARD_PBCLOCK / 2) / frequency + */ + + divisor = (BOARD_PBCLOCK / 2) / frequency; + + /* The a BRG register value is that divisor minus one + * + * frequency = BOARD_PBCLOCK /(2 * (BRG + 1)), or + * BRG = (BOARD_PBCLOCK / 2) / frequency - 1 + */ + + regval = divisor; + if (regval > 0) + { + regval--; + } + + /* Save the new BRG value */ + + spi_putreg(priv, PIC32MX_SPI_BRG_OFFSET, regval); + + /* Calculate the new actual frequency" + * + * frequency = BOARD_PBCLOCK / (2 * divisor) + */ + + actual = (BOARD_PBCLOCK / 2) / divisor; + + /* Save the frequency setting */ + +#ifndef CONFIG_SPI_OWNBUS + priv->frequency = frequency; + priv->actual = actual; +#endif + + spidbg("Frequency %d->%d\n", frequency, actual); + return actual; +} + +/**************************************************************************** + * Name: spi_setmode + * + * Description: + * Set the SPI mode. Optional. See enum spi_mode_e for mode definitions + * + * Input Parameters: + * dev - Device-specific state data + * mode - The SPI mode requested + * + * Returned Value: + * none + * + ****************************************************************************/ + +static void spi_setmode(FAR struct spi_dev_s *dev, enum spi_mode_e mode) +{ + FAR struct pic32mx_dev_s *priv = (FAR struct pic32mx_dev_s *)dev; + uint32_t regval; + + /* Has the mode changed? */ + +#ifndef CONFIG_SPI_OWNBUS + if (mode != priv->mode) + { +#endif + /* Yes... Set CR appropriately */ + + regval = spi_getreg(priv, PIC32MX_SPI_CON_OFFSET); + regval &= ~(SPI_CON_CKP|SPI_CON_SMP); + + switch (mode) + { + case SPIDEV_MODE0: /* CPOL=0; CPHA=0 */ + break; + + case SPIDEV_MODE1: /* CPOL=0; CPHA=1 */ + regval |= SPI_CON_SMP; + break; + + case SPIDEV_MODE2: /* CPOL=1; CPHA=0 */ + regval |= SPI_CON_CKP; + break; + + case SPIDEV_MODE3: /* CPOL=1; CPHA=1 */ + regval |= (SPI_CON_CKP|SPI_CON_SMP); + break; + + default: + DEBUGASSERT(FALSE); + return; + } + + spi_putreg(priv, PIC32MX_SPI_CON_OFFSET, regval); + + /* Save the mode so that subsequent re-configuratins will be faster */ + +#ifndef CONFIG_SPI_OWNBUS + priv->mode = mode; + } +#endif +} + +/**************************************************************************** + * Name: spi_setbits + * + * Description: + * Set the number if bits per word. + * + * Input Parameters: + * dev - Device-specific state data + * nbits - The number of bits requests + * + * Returned Value: + * none + * + ****************************************************************************/ + +static void spi_setbits(FAR struct spi_dev_s *dev, int nbits) +{ + FAR struct pic32mx_dev_s *priv = (FAR struct pic32mx_dev_s *)dev; + uint32_t mode; + uint32_t regval; + + /* Has the number of bits changed? */ + + DEBUGASSERT(priv && nbits > 7 && nbits < 17); +#ifndef CONFIG_SPI_OWNBUS + if (nbits != priv->nbits) + { +#endif + /* Yes... Set the CON register appropriately */ + + if (nbits == 8) + { + mode = SPI_CON_MODE_8BIT; + } + else if (nbits == 16) + { + mode = SPI_CON_MODE_8BIT; + } + else if (nbits == 32) + { + mode = SPI_CON_MODE_8BIT; + } + else + { + spidbg("Unsupported nbits: %d\n", nbits); + return; + } + + regval = spi_getreg(priv, PIC32MX_SPI_CON_OFFSET); + regval &= ~SPI_CON_MODE_MASK; + regval |= mode; + regval = spi_getreg(priv, PIC32MX_SPI_CON_OFFSET); + + /* Save the selection so the subsequence re-configurations will be faster */ + +#ifndef CONFIG_SPI_OWNBUS + priv->nbits = nbits; + } +#endif +} + +/**************************************************************************** + * Name: spi_send + * + * Description: + * Exchange one word on SPI + * + * Input Parameters: + * dev - Device-specific state data + * wd - The word to send. the size of the data is determined by the + * number of bits selected for the SPI interface. + * + * Returned Value: + * response + * + ****************************************************************************/ + +static uint16_t spi_send(FAR struct spi_dev_s *dev, uint16_t wd) +{ + FAR struct pic32mx_dev_s *priv = (FAR struct pic32mx_dev_s *)dev; + + /* Write the data to transmitted to the SPI Data Register */ + + spi_putreg(priv, PIC32MX_SPI_BUF_OFFSET, (uint32_t)wd); + + /* Wait for the SPITBE bit in the SPI Status Register to be set to 1. The + * SPITBE bit will be set when the receive buffer is not empty. + */ + + while ((spi_getreg(priv, PIC32MX_SPI_STAT_OFFSET) & SPI_STAT_SPITBE) == 0); + + /* Return the SPI data */ + + return (uint16_t)spi_getreg(priv, PIC32MX_SPI_BUF_OFFSET); +} + +/************************************************************************* + * Name: spi_sndblock + * + * Description: + * Send a block of data on SPI + * + * Input Parameters: + * dev - Device-specific state data + * buffer - A pointer to the buffer of data to be sent + * nwords - the length of data to send from the buffer in number of words. + * The wordsize is determined by the number of bits-per-word + * selected for the SPI interface. If nbits <= 8, the data is + * packed into uint8_t's; if nbits >8, the data is packed into uint16_t's + * + * Returned Value: + * None + * + ****************************************************************************/ + +static void spi_sndblock(FAR struct spi_dev_s *dev, FAR const void *buffer, size_t nwords) +{ + FAR struct pic32mx_dev_s *priv = (FAR struct pic32mx_dev_s *)dev; + FAR uint8_t *ptr = (FAR uint8_t*)buffer; + uint32_t regval; + uint8_t data; + + spidbg("nwords: %d\n", nwords); + while (nwords) + { + /* Write the data to transmitted to the SPI Data Register */ + + data = *ptr++; + spi_putreg(priv, PIC32MX_SPI_BUF_OFFSET, (uint32_t)data); + + /* Wait for the SPITBE bit in the SPI Status Register to be set to 1. + * The SPITBE bit will be set when the receive buffer is not empty. + */ + + while ((spi_getreg(priv, PIC32MX_SPI_STAT_OFFSET) & SPI_STAT_SPITBE) == 0); + + /* Read from the buffer register to clear the status bit */ + + regval = spi_getreg(priv, PIC32MX_SPI_BUF_OFFSET); + nwords--; + } +} + +/**************************************************************************** + * Name: spi_recvblock + * + * Description: + * Revice a block of data from SPI + * + * Input Parameters: + * dev - Device-specific state data + * buffer - A pointer to the buffer in which to recieve data + * nwords - the length of data that can be received in the buffer in number + * of words. The wordsize is determined by the number of bits-per-word + * selected for the SPI interface. If nbits <= 8, the data is + * packed into uint8_t's; if nbits >8, the data is packed into uint16_t's + * + * Returned Value: + * None + * + ****************************************************************************/ + +static void spi_recvblock(FAR struct spi_dev_s *dev, FAR void *buffer, size_t nwords) +{ + FAR struct pic32mx_dev_s *priv = (FAR struct pic32mx_dev_s *)dev; + FAR uint8_t *ptr = (FAR uint8_t*)buffer; + + spidbg("nwords: %d\n", nwords); + while (nwords) + { + /* Write some dummy data to the SPI Data Register in order to clock the + * read data. + */ + + spi_putreg(priv, PIC32MX_SPI_BUF_OFFSET, 0xff); + + /* Wait for the SPITBE bit in the SPI Status Register to be set to 1. + * The SPITBE bit will be set when the receive buffer is not empty. + */ + + while ((spi_getreg(priv, PIC32MX_SPI_STAT_OFFSET) & SPI_STAT_SPITBE) == 0); + + /* Read the received data from the SPI Data Register */ + + *ptr++ = (uint8_t)spi_getreg(priv, PIC32MX_SPI_BUF_OFFSET); + nwords--; + } +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: up_spiinitialize + * + * Description: + * Initialize the selected SPI port + * + * Input Parameter: + * Port number (for hardware that has mutiple SPI interfaces) + * + * Returned Value: + * Valid SPI device structure reference on succcess; a NULL on failure + * + ****************************************************************************/ + +FAR struct spi_dev_s *up_spiinitialize(int port) +{ + FAR struct pic32mx_dev_s *priv; + irqstate_t flags; + uint32_t regval; + + /* Select the SPI state structure for this port */ + +#ifdef CONFIG_PIC32MX_SPI1 + if (port == 1) + { + priv = &g_spi1dev; + } + else +#endif +#ifdef CONFIG_PIC32MX_SPI2 + if (port == 2) + { + priv = &g_spi2dev; + } + else +#endif +#ifdef CONFIG_PIC32MX_SPI3 + if (port == 3) + { + priv = &g_spi3dev; + } + else +#endif +#ifdef CONFIG_PIC32MX_SPI4 + if (port == 4) + { + priv = &g_spi4dev; + } + else +#endif + { + spidbg("Unsuppport port: %d\n", port); + return NULL; + } + + /* Disable SPI interrupts */ + + flags = irqsave(); +#ifdef CONFIG_PIC32MX_SPI_INTERRUPTS + up_disable_irq(priv->eirq); + up_disable_irq(priv->txirq); + up_disable_irq(priv->rxirq); +#endif + + /* Stop and reset the SPI module by clearing the ON bit in the CON register. */ + + spi_putreg(priv, PIC32MX_SPI_CON_OFFSET, 0); + + /* Clear the receive buffer by reading from the BUF register */ + + regval = spi_getreg(priv, PIC32MX_SPI_BUF_OFFSET); + + /* Set the ENHBUF bit if using Enhanced Buffer mode. */ + +#ifdef CONFIG_PIC32MX_SPI_INTERRUPTS + /* Attach the interrupt vector */ + + ret = irq_attach(priv->vector, spi_interrupt); + if (ret < 0) + { + spidbg("Failed to attach vector: %d port: %d\n", priv->vector, port); + goto errout; + } + + /* Enable SPI interrupts */ + + up_enable_irq(priv->eirq); + up_enable_irq(priv->txirq); + up_enable_irq(priv->rxirq); + + /* Set the interrupt priority */ + + ret = up_prioritize_irq(priv->vector, CONFIG_PIC32MX_SPI_PRIORITY) + if (ret < 0) + { + spidbg("up_prioritize_irq failed: %d\n", ret); + goto errout; + } +#endif + + /* Select a default frequency of approx. 400KHz */ + + spi_setfrequency((FAR struct spi_dev_s *)priv, 400000); + + /* Clear the SPIROV overflow bit (SPIxSTAT:6). */ + + spi_putreg(priv, PIC32MX_SPI_STATCLR_OFFSET, SPI_STAT_SPIROV); + + /* Initial settings 8 bit + master mode + mode 0*/ + + regval = (SPI_CON_MSTEN | SPI_CON_MODE_8BIT | SPI_CON_ON); +#ifdef CONFIG_PIC32MX_SPI_INTERRUPTS + regval |= (SPI_CON_RTXISEL_HALF | SPI_CON_STXISEL_HALF); +#endif + spi_putreg(priv, PIC32MX_SPI_CON_OFFSET, regval); + + /* Set the initial SPI configuration */ + +#ifndef CONFIG_SPI_OWNBUS + priv->nbits = 8; + priv->mode = SPIDEV_MODE0; +#endif + + /* Initialize the SPI semaphore that enforces mutually exclusive access */ + +#ifndef CONFIG_SPI_OWNBUS + sem_init(&priv->exclsem, 0, 1); +#endif + irqrestore(flags); + return &priv->spidev; + +#ifdef CONFIG_PIC32MX_SPI_INTERRUPTS +errout: + irqrestore(flags); + return NULL; +#endif +} + +#endif /* CONFIG_PIC32MX_SPI */ + diff --git a/arch/mips/src/pic32mx/pic32mx-spi.h b/arch/mips/src/pic32mx/pic32mx-spi.h index 8b1ad900d1..fd01091e52 100644 --- a/arch/mips/src/pic32mx/pic32mx-spi.h +++ b/arch/mips/src/pic32mx/pic32mx-spi.h @@ -1,231 +1,230 @@ -/**************************************************************************** - * arch/mips/src/pic32mx/pic32mx-spi.h - * - * Copyright (C) 2011 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name NuttX nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -#ifndef __ARCH_MIPS_SRC_PIC32MX_PIC32MX_SPI_H -#define __ARCH_MIPS_SRC_PIC32MX_PIC32MX_SPI_H - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include "chip.h" -#include "pic32mx-memorymap.h" - -/**************************************************************************** - * Pre-Processor Definitions - ****************************************************************************/ -/* Register Offsets *********************************************************/ - -#define PIC32MX_SPI_CON_OFFSET 0x0000 /* SPI control register */ -#define PIC32MX_SPI_CONCLR_OFFSET 0x0004 /* SPI control clear register */ -#define PIC32MX_SPI_CONSET_OFFSET 0x0008 /* SPI control set register */ -#define PIC32MX_SPI_CONINV_OFFSET 0x000c /* SPI control invert register */ -#define PIC32MX_SPI_STAT_OFFSET 0x0010 /* SPI status register */ -#define PIC32MX_SPI_STATSET_OFFSET 0x0018 /* SPI status set register */ -#define PIC32MX_SPI_BUF_OFFSET 0x0020 /* SPI buffer register */ -#define PIC32MX_SPI_BRG_OFFSET 0x0030 /* SPI baud rate register */ -#define PIC32MX_SPI_BRGCLR_OFFSET 0x0034 /* SPI baud rate clear register */ -#define PIC32MX_SPI_BRGSET_OFFSET 0x0038 /* SPI baud rate set register */ -#define PIC32MX_SPI_BRGINV_OFFSET 0x003c /* SPI baud rate invert register */ - -/* Register Addresses *******************************************************/ - -#ifdef PIC32MX_SPI1_K1BASE -# define PIC32MX_SPI1_CON (PIC32MX_SPI1_K1BASE+PIC32MX_SPI_CON_OFFSET) -# define PIC32MX_SPI1_CONCLR (PIC32MX_SPI1_K1BASE+PIC32MX_SPI_CONCLR_OFFSET) -# define PIC32MX_SPI1_CONSET (PIC32MX_SPI1_K1BASE+PIC32MX_SPI_CONSET_OFFSET) -# define PIC32MX_SPI1_CONINV (PIC32MX_SPI1_K1BASE+PIC32MX_SPI_CONINV_OFFSET) -# define PIC32MX_SPI1_STAT (PIC32MX_SPI1_K1BASE+PIC32MX_SPI_STAT_OFFSET) -# define PIC32MX_SPI1_STATSET (PIC32MX_SPI1_K1BASE+PIC32MX_SPI_STATSET_OFFSET) -# define PIC32MX_SPI1_BUF (PIC32MX_SPI1_K1BASE+PIC32MX_SPI_BUF_OFFSET) -# define PIC32MX_SPI1_BRG (PIC32MX_SPI1_K1BASE+PIC32MX_SPI_BRG_OFFSET) -# define PIC32MX_SPI1_BRGCLR (PIC32MX_SPI1_K1BASE+PIC32MX_SPI_BRGCLR_OFFSET) -# define PIC32MX_SPI1_BRGSET (PIC32MX_SPI1_K1BASE+PIC32MX_SPI_BRGSET_OFFSET) -# define PIC32MX_SPI1_BRGINV (PIC32MX_SPI1_K1BASE+PIC32MX_SPI_BRGINV_OFFSET) -#endif - -#ifdef PIC32MX_SPI2_K1BASE -# define PIC32MX_SPI2_CON (PIC32MX_SPI2_K1BASE+PIC32MX_SPI_CON_OFFSET) -# define PIC32MX_SPI2_CONCLR (PIC32MX_SPI2_K1BASE+PIC32MX_SPI_CONCLR_OFFSET) -# define PIC32MX_SPI2_CONSET (PIC32MX_SPI2_K1BASE+PIC32MX_SPI_CONSET_OFFSET) -# define PIC32MX_SPI2_CONINV (PIC32MX_SPI2_K1BASE+PIC32MX_SPI_CONINV_OFFSET) -# define PIC32MX_SPI2_STAT (PIC32MX_SPI2_K1BASE+PIC32MX_SPI_STAT_OFFSET) -# define PIC32MX_SPI2_STATSET (PIC32MX_SPI2_K1BASE+PIC32MX_SPI_STATSET_OFFSET) -# define PIC32MX_SPI2_BUF (PIC32MX_SPI2_K1BASE+PIC32MX_SPI_BUF_OFFSET) -# define PIC32MX_SPI2_BRG (PIC32MX_SPI2_K1BASE+PIC32MX_SPI_BRG_OFFSET) -# define PIC32MX_SPI2_BRGCLR (PIC32MX_SPI2_K1BASE+PIC32MX_SPI_BRGCLR_OFFSET) -# define PIC32MX_SPI2_BRGSET (PIC32MX_SPI2_K1BASE+PIC32MX_SPI_BRGSET_OFFSET) -# define PIC32MX_SPI2_BRGINV (PIC32MX_SPI2_K1BASE+PIC32MX_SPI_BRGINV_OFFSET) -#endif - -#ifdef PIC32MX_SPI3_K1BASE -# define PIC32MX_SPI3_CON (PIC32MX_SPI3_K1BASE+PIC32MX_SPI_CON_OFFSET) -# define PIC32MX_SPI3_CONCLR (PIC32MX_SPI3_K1BASE+PIC32MX_SPI_CONCLR_OFFSET) -# define PIC32MX_SPI3_CONSET (PIC32MX_SPI3_K1BASE+PIC32MX_SPI_CONSET_OFFSET) -# define PIC32MX_SPI3_CONINV (PIC32MX_SPI3_K1BASE+PIC32MX_SPI_CONINV_OFFSET) -# define PIC32MX_SPI3_STAT (PIC32MX_SPI3_K1BASE+PIC32MX_SPI_STAT_OFFSET) -# define PIC32MX_SPI3_STATSET (PIC32MX_SPI3_K1BASE+PIC32MX_SPI_STATSET_OFFSET) -# define PIC32MX_SPI3_BUF (PIC32MX_SPI3_K1BASE+PIC32MX_SPI_BUF_OFFSET) -# define PIC32MX_SPI3_BRG (PIC32MX_SPI3_K1BASE+PIC32MX_SPI_BRG_OFFSET) -# define PIC32MX_SPI3_BRGCLR (PIC32MX_SPI3_K1BASE+PIC32MX_SPI_BRGCLR_OFFSET) -# define PIC32MX_SPI3_BRGSET (PIC32MX_SPI3_K1BASE+PIC32MX_SPI_BRGSET_OFFSET) -# define PIC32MX_SPI3_BRGINV (PIC32MX_SPI3_K1BASE+PIC32MX_SPI_BRGINV_OFFSET) -#endif - -#ifdef PIC32MX_SPI4_K1BASE -# define PIC32MX_SPI4_CON (PIC32MX_SPI4_K1BASE+PIC32MX_SPI_CON_OFFSET) -# define PIC32MX_SPI4_CONCLR (PIC32MX_SPI4_K1BASE+PIC32MX_SPI_CONCLR_OFFSET) -# define PIC32MX_SPI4_CONSET (PIC32MX_SPI4_K1BASE+PIC32MX_SPI_CONSET_OFFSET) -# define PIC32MX_SPI4_CONINV (PIC32MX_SPI4_K1BASE+PIC32MX_SPI_CONINV_OFFSET) -# define PIC32MX_SPI4_STAT (PIC32MX_SPI4_K1BASE+PIC32MX_SPI_STAT_OFFSET) -# define PIC32MX_SPI4_STATSET (PIC32MX_SPI4_K1BASE+PIC32MX_SPI_STATSET_OFFSET) -# define PIC32MX_SPI4_BUF (PIC32MX_SPI4_K1BASE+PIC32MX_SPI_BUF_OFFSET) -# define PIC32MX_SPI4_BRG (PIC32MX_SPI4_K1BASE+PIC32MX_SPI_BRG_OFFSET) -# define PIC32MX_SPI4_BRGCLR (PIC32MX_SPI4_K1BASE+PIC32MX_SPI_BRGCLR_OFFSET) -# define PIC32MX_SPI4_BRGSET (PIC32MX_SPI4_K1BASE+PIC32MX_SPI_BRGSET_OFFSET) -# define PIC32MX_SPI4_BRGINV (PIC32MX_SPI4_K1BASE+PIC32MX_SPI_BRGINV_OFFSET) -#endif - -/* Register Bit-Field Definitions *******************************************/ - -/* SPI control register */ - -#if defined(CHIP_PIC32MX5) || defined(CHIP_PIC32MX6) || defined(CHIP_PIC32MX7) -# define SPI_CON_RTXISEL_SHIFT (0) /* Bits 0-1: SPI Receive Buffer Full Interrupt Mode */ -# define SPI_CON_RTXISEL_MASK (3 << SPI_CON_RTXISEL_SHIFT) -# define SPI_CON_RTXISEL_EMPTY (0 << SPI_CON_RTXISEL_SHIFT) /* Buffer empty*/ -# define SPI_CON_RTXISEL_NEMPTY (1 << SPI_CON_RTXISEL_SHIFT) /* Buffer not empty*/ -# define SPI_CON_RTXISEL_HALF (2 << SPI_CON_RTXISEL_SHIFT) /* Buffer half full or more */ -# define SPI_CON_RTXISEL_FULL (3 << SPI_CON_RTXISEL_SHIFT) /* Buffer full */ -# define SPI_CON_STXISEL_SHIFT (2) /* Bits 2-3: SPI Transmit Buffer Empty Interrupt Mode */ -# define SPI_CON_STXISEL_MASK (3 << SPI_CON_STXISEL_SHIFT) -# define SPI_CON_STXISEL_DONE (0 << SPI_CON_STXISEL_SHIFT) /* Buffer empty (and data shifted out) */ -# define SPI_CON_STXISEL_EMPTY (1 << SPI_CON_STXISEL_SHIFT) /* Buffer empty */ -# define SPI_CON_STXISEL_HALF (2 << SPI_CON_STXISEL_SHIFT) /* Buffer half empty or more */ -# define SPI_CON_STXISEL_NFULL (3 << SPI_CON_STXISEL_SHIFT) /* Buffer not full */ -#endif - /* Bit 4: Reserved */ -#define SPI_CON_MSTEN (1 << 5) /* Bits 5: Master mode enable */ -#define SPI_CON_CKP (1 << 6) /* Bits 6: Clock polarity select */ -#define SPI_CON_SSEN (1 << 7) /* Bits 7: Slave select enable (slave mode) */ -#define SPI_CON_CKE (1 << 8) /* Bits 8: SPI clock edge select */ -#define SPI_CON_SMP (1 << 9) /* Bits 9: SPI data input sample phase */ -#define SPI_CON_MODE_SHIFT (10) /* Bits 10-11: 32/16-Bit Communication Select */ -#define SPI_CON_MODE_MASK (3 << SPI_CON_MODE_SHIFT) -#define SPI_CON_MODE32 (1 << 11) /* Bits 11: xx */ -# define SPI_CON_MODE_8BIT (0 << SPI_CON_MODE_SHIFT) /* 8-bit data width */ -# define SPI_CON_MODE_16BIT (1 << SPI_CON_MODE_SHIFT) /* 16-bit data width */ -# define SPI_CON_MODE_32BIT (2 << SPI_CON_MODE_SHIFT) /* 2-bit data width */ -#define SPI_CON_DISSDO (1 << 12) /* Bits 12: Disable SDOx pin */ -#define SPI_CON_SIDL (1 << 13) /* Bits 13: Stop in idle mode */ -#define SPI_CON_FRZ (1 << 14) /* Bits 14: Freeze in debug exception */ -#define SPI_CON_ON (1 << 15) /* Bits 15: SPI peripheral on */ -#define SPI_CON_ENHBUF (1 << 16) /* Bits 16: Enhanced buffer enable */ -#define SPI_CON_SPIFE (1 << 17) /* Bits 17: Frame sync pulse edge select */ - /* Bits 18-23: Reserved */ -#if defined(CHIP_PIC32MX5) || defined(CHIP_PIC32MX6) || defined(CHIP_PIC32MX7) -# define SPI_CON_FRMCNT_SHIFT (24) /* Bits 24-26: Frame Sync Pulse Counter bits */ -# define SPI_CON_FRMCNT_MASK (7 << SPI_CON_FRMCNT_SHIFT) -# define SPI_CON_FRMCNT_CHAR1 (0 << SPI_CON_FRMCNT_SHIFT) /* Frame sync pulse each char */ -# define SPI_CON_FRMCNT_CHAR2 (1 << SPI_CON_FRMCNT_SHIFT) /* Frame sync pulse every 2 chars */ -# define SPI_CON_FRMCNT_CHAR4 (2 << SPI_CON_FRMCNT_SHIFT) /* Frame sync pulse every 4 chars */ -# define SPI_CON_FRMCNT_CHAR8 (3 << SPI_CON_FRMCNT_SHIFT) /* Frame sync pulse every 8 chars */ -# define SPI_CON_FRMCNT_CHAR16 (4 << SPI_CON_FRMCNT_SHIFT) /* Frame sync pulse every 16 chars */ -# define SPI_CON_FRMCNT_CHAR32 (5 << SPI_CON_FRMCNT_SHIFT) /* Frame sync pulse every 32 chars */ -# define SPI_CON_FRMSYPW (1 << 27) /* Bits 27: Frame sync pulse width */ -# define SPI_CON_MSSEN (1 << 28) /* Bits 28: Master mode slave select enable */ -#endif -#define SPI_CON_FRMPOL (1 << 29) /* Bits 29: Frame sync polarity */ -#define SPI_CON_FRMSYNC (1 << 30) /* Bits 30: Frame sync pulse direction control on SSx pin */ -#define SPI_CON_FRMEN (1 << 31) /* Bits 31: Framed SPI support */ - -/* SPI status register */ - -#if defined(CHIP_PIC32MX3) || defined(CHIP_PIC32MX4) -# define SPI_STAT_SPIRBF (1 << 0) /* Bits 0: SPI receive buffer full status */ -# define SPI_STAT_SPITBE (1 << 3) /* Bits 3: SPI transmit buffer empty status */ -# define SPI_STAT_SPIROV (1 << 6) /* Bits 6: Receive overflow flag */ -# define SPI_STAT_SPIBUSY (1 << 11) /* Bits 11: SPI activity status */ -#elif defined(CHIP_PIC32MX5) || defined(CHIP_PIC32MX6) || defined(CHIP_PIC32MX7) -# define SPI_STAT_SPIRBF (1 << 0) /* Bits 0: SPI receive buffer full status */ -# define SPI_STAT_SPITBF (1 << 1) /* Bits 1: SPI transmit buffer full status */ -# define SPI_STAT_SPITBE (1 << 3) /* Bits 3: SPI transmit buffer empty status */ -# define SPI_STAT_SPIRBE (1 << 5) /* Bits 5: RX FIFO Empty */ -# define SPI_STAT_SPIROV (1 << 6) /* Bits 6: Receive overflow flag */ -# define SPI_STAT_SRMT (1 << 7) /* Bits 6: Shift Register Empty */ -# define SPI_STAT_SPITUR (1 << 6) /* Bits 8: Transmit under run */ -# define SPI_STAT_SPIBUSY (1 << 11) /* Bits 11: SPI activity status */ -# define SPI_STAT_TXBUFELM_SHIFT (16) /* Bits 16-20: Transmit Buffer Element Count bits */ -# define SPI_STAT_TXBUFELM_MASK (31 << SPI_STAT_TXBUFELM_SHIFT) -# define SPI_STAT_RXBUFELM_SHIFT (24) /* Bits 24-28: Receive Buffer Element Count bits */ -# define SPI_STAT_RXBUFELM_MASK (31 << SPI_STAT_RXBUFELM_SHIFT) -#endif - -/* SPI buffer register (32-bits wide) */ - -/* SPI baud rate register */ - -#define SPI_BRG_MASK 0x1ff - -/**************************************************************************** - * Public Types - ****************************************************************************/ - -#ifndef __ASSEMBLY__ - -/**************************************************************************** - * Inline Functions - ****************************************************************************/ - -/**************************************************************************** - * Public Function Prototypes - ****************************************************************************/ - -#ifdef __cplusplus -#define EXTERN extern "C" -extern "C" { -#else -#define EXTERN extern -#endif - -#undef EXTERN -#ifdef __cplusplus -} -#endif - -#endif /* __ASSEMBLY__ */ -#endif /* __ARCH_MIPS_SRC_PIC32MX_PIC32MX_SPI_H */ +/**************************************************************************** + * arch/mips/src/pic32mx/pic32mx-spi.h + * + * Copyright (C) 2011-2012 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#ifndef __ARCH_MIPS_SRC_PIC32MX_PIC32MX_SPI_H +#define __ARCH_MIPS_SRC_PIC32MX_PIC32MX_SPI_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include "chip.h" +#include "pic32mx-memorymap.h" + +/**************************************************************************** + * Pre-Processor Definitions + ****************************************************************************/ +/* Register Offsets *********************************************************/ + +#define PIC32MX_SPI_CON_OFFSET 0x0000 /* SPI control register */ +#define PIC32MX_SPI_CONCLR_OFFSET 0x0004 /* SPI control clear register */ +#define PIC32MX_SPI_CONSET_OFFSET 0x0008 /* SPI control set register */ +#define PIC32MX_SPI_CONINV_OFFSET 0x000c /* SPI control invert register */ +#define PIC32MX_SPI_STAT_OFFSET 0x0010 /* SPI status register */ +#define PIC32MX_SPI_STATCLR_OFFSET 0x0014 /* SPI status clear register */ +#define PIC32MX_SPI_BUF_OFFSET 0x0020 /* SPI buffer register */ +#define PIC32MX_SPI_BRG_OFFSET 0x0030 /* SPI baud rate register */ +#define PIC32MX_SPI_BRGCLR_OFFSET 0x0034 /* SPI baud rate clear register */ +#define PIC32MX_SPI_BRGSET_OFFSET 0x0038 /* SPI baud rate set register */ +#define PIC32MX_SPI_BRGINV_OFFSET 0x003c /* SPI baud rate invert register */ + +/* Register Addresses *******************************************************/ + +#ifdef PIC32MX_SPI1_K1BASE +# define PIC32MX_SPI1_CON (PIC32MX_SPI1_K1BASE+PIC32MX_SPI_CON_OFFSET) +# define PIC32MX_SPI1_CONCLR (PIC32MX_SPI1_K1BASE+PIC32MX_SPI_CONCLR_OFFSET) +# define PIC32MX_SPI1_CONSET (PIC32MX_SPI1_K1BASE+PIC32MX_SPI_CONSET_OFFSET) +# define PIC32MX_SPI1_CONINV (PIC32MX_SPI1_K1BASE+PIC32MX_SPI_CONINV_OFFSET) +# define PIC32MX_SPI1_STAT (PIC32MX_SPI1_K1BASE+PIC32MX_SPI_STAT_OFFSET) +# define PIC32MX_SPI1_STATCLR (PIC32MX_SPI1_K1BASE+PIC32MX_SPI_STATCLR_OFFSET) +# define PIC32MX_SPI1_BUF (PIC32MX_SPI1_K1BASE+PIC32MX_SPI_BUF_OFFSET) +# define PIC32MX_SPI1_BRG (PIC32MX_SPI1_K1BASE+PIC32MX_SPI_BRG_OFFSET) +# define PIC32MX_SPI1_BRGCLR (PIC32MX_SPI1_K1BASE+PIC32MX_SPI_BRGCLR_OFFSET) +# define PIC32MX_SPI1_BRGSET (PIC32MX_SPI1_K1BASE+PIC32MX_SPI_BRGSET_OFFSET) +# define PIC32MX_SPI1_BRGINV (PIC32MX_SPI1_K1BASE+PIC32MX_SPI_BRGINV_OFFSET) +#endif + +#ifdef PIC32MX_SPI2_K1BASE +# define PIC32MX_SPI2_CON (PIC32MX_SPI2_K1BASE+PIC32MX_SPI_CON_OFFSET) +# define PIC32MX_SPI2_CONCLR (PIC32MX_SPI2_K1BASE+PIC32MX_SPI_CONCLR_OFFSET) +# define PIC32MX_SPI2_CONSET (PIC32MX_SPI2_K1BASE+PIC32MX_SPI_CONSET_OFFSET) +# define PIC32MX_SPI2_CONINV (PIC32MX_SPI2_K1BASE+PIC32MX_SPI_CONINV_OFFSET) +# define PIC32MX_SPI2_STAT (PIC32MX_SPI2_K1BASE+PIC32MX_SPI_STAT_OFFSET) +# define PIC32MX_SPI2_STATCLR (PIC32MX_SPI2_K1BASE+PIC32MX_SPI_STATCLR_OFFSET) +# define PIC32MX_SPI2_BUF (PIC32MX_SPI2_K1BASE+PIC32MX_SPI_BUF_OFFSET) +# define PIC32MX_SPI2_BRG (PIC32MX_SPI2_K1BASE+PIC32MX_SPI_BRG_OFFSET) +# define PIC32MX_SPI2_BRGCLR (PIC32MX_SPI2_K1BASE+PIC32MX_SPI_BRGCLR_OFFSET) +# define PIC32MX_SPI2_BRGSET (PIC32MX_SPI2_K1BASE+PIC32MX_SPI_BRGSET_OFFSET) +# define PIC32MX_SPI2_BRGINV (PIC32MX_SPI2_K1BASE+PIC32MX_SPI_BRGINV_OFFSET) +#endif + +#ifdef PIC32MX_SPI3_K1BASE +# define PIC32MX_SPI3_CON (PIC32MX_SPI3_K1BASE+PIC32MX_SPI_CON_OFFSET) +# define PIC32MX_SPI3_CONCLR (PIC32MX_SPI3_K1BASE+PIC32MX_SPI_CONCLR_OFFSET) +# define PIC32MX_SPI3_CONSET (PIC32MX_SPI3_K1BASE+PIC32MX_SPI_CONSET_OFFSET) +# define PIC32MX_SPI3_CONINV (PIC32MX_SPI3_K1BASE+PIC32MX_SPI_CONINV_OFFSET) +# define PIC32MX_SPI3_STAT (PIC32MX_SPI3_K1BASE+PIC32MX_SPI_STAT_OFFSET) +# define PIC32MX_SPI3_STATCLR (PIC32MX_SPI3_K1BASE+PIC32MX_SPI_STATCLR_OFFSET) +# define PIC32MX_SPI3_BUF (PIC32MX_SPI3_K1BASE+PIC32MX_SPI_BUF_OFFSET) +# define PIC32MX_SPI3_BRG (PIC32MX_SPI3_K1BASE+PIC32MX_SPI_BRG_OFFSET) +# define PIC32MX_SPI3_BRGCLR (PIC32MX_SPI3_K1BASE+PIC32MX_SPI_BRGCLR_OFFSET) +# define PIC32MX_SPI3_BRGSET (PIC32MX_SPI3_K1BASE+PIC32MX_SPI_BRGSET_OFFSET) +# define PIC32MX_SPI3_BRGINV (PIC32MX_SPI3_K1BASE+PIC32MX_SPI_BRGINV_OFFSET) +#endif + +#ifdef PIC32MX_SPI4_K1BASE +# define PIC32MX_SPI4_CON (PIC32MX_SPI4_K1BASE+PIC32MX_SPI_CON_OFFSET) +# define PIC32MX_SPI4_CONCLR (PIC32MX_SPI4_K1BASE+PIC32MX_SPI_CONCLR_OFFSET) +# define PIC32MX_SPI4_CONSET (PIC32MX_SPI4_K1BASE+PIC32MX_SPI_CONSET_OFFSET) +# define PIC32MX_SPI4_CONINV (PIC32MX_SPI4_K1BASE+PIC32MX_SPI_CONINV_OFFSET) +# define PIC32MX_SPI4_STAT (PIC32MX_SPI4_K1BASE+PIC32MX_SPI_STAT_OFFSET) +# define PIC32MX_SPI4_STATCLR (PIC32MX_SPI4_K1BASE+PIC32MX_SPI_STATCLR_OFFSET) +# define PIC32MX_SPI4_BUF (PIC32MX_SPI4_K1BASE+PIC32MX_SPI_BUF_OFFSET) +# define PIC32MX_SPI4_BRG (PIC32MX_SPI4_K1BASE+PIC32MX_SPI_BRG_OFFSET) +# define PIC32MX_SPI4_BRGCLR (PIC32MX_SPI4_K1BASE+PIC32MX_SPI_BRGCLR_OFFSET) +# define PIC32MX_SPI4_BRGSET (PIC32MX_SPI4_K1BASE+PIC32MX_SPI_BRGSET_OFFSET) +# define PIC32MX_SPI4_BRGINV (PIC32MX_SPI4_K1BASE+PIC32MX_SPI_BRGINV_OFFSET) +#endif + +/* Register Bit-Field Definitions *******************************************/ + +/* SPI control register */ + +#if defined(CHIP_PIC32MX5) || defined(CHIP_PIC32MX6) || defined(CHIP_PIC32MX7) +# define SPI_CON_RTXISEL_SHIFT (0) /* Bits 0-1: SPI Receive Buffer Full Interrupt Mode */ +# define SPI_CON_RTXISEL_MASK (3 << SPI_CON_RTXISEL_SHIFT) +# define SPI_CON_RTXISEL_EMPTY (0 << SPI_CON_RTXISEL_SHIFT) /* Buffer empty*/ +# define SPI_CON_RTXISEL_NEMPTY (1 << SPI_CON_RTXISEL_SHIFT) /* Buffer not empty*/ +# define SPI_CON_RTXISEL_HALF (2 << SPI_CON_RTXISEL_SHIFT) /* Buffer half full or more */ +# define SPI_CON_RTXISEL_FULL (3 << SPI_CON_RTXISEL_SHIFT) /* Buffer full */ +# define SPI_CON_STXISEL_SHIFT (2) /* Bits 2-3: SPI Transmit Buffer Empty Interrupt Mode */ +# define SPI_CON_STXISEL_MASK (3 << SPI_CON_STXISEL_SHIFT) +# define SPI_CON_STXISEL_DONE (0 << SPI_CON_STXISEL_SHIFT) /* Buffer empty (and data shifted out) */ +# define SPI_CON_STXISEL_EMPTY (1 << SPI_CON_STXISEL_SHIFT) /* Buffer empty */ +# define SPI_CON_STXISEL_HALF (2 << SPI_CON_STXISEL_SHIFT) /* Buffer half empty or more */ +# define SPI_CON_STXISEL_NFULL (3 << SPI_CON_STXISEL_SHIFT) /* Buffer not full */ +#endif + /* Bit 4: Reserved */ +#define SPI_CON_MSTEN (1 << 5) /* Bits 5: Master mode enable */ +#define SPI_CON_CKP (1 << 6) /* Bits 6: Clock polarity select */ +#define SPI_CON_SSEN (1 << 7) /* Bits 7: Slave select enable (slave mode) */ +#define SPI_CON_CKE (1 << 8) /* Bits 8: SPI clock edge select */ +#define SPI_CON_SMP (1 << 9) /* Bits 9: SPI data input sample phase */ +#define SPI_CON_MODE_SHIFT (10) /* Bits 10-11: 32/16-Bit Communication Select */ +#define SPI_CON_MODE_MASK (3 << SPI_CON_MODE_SHIFT) +# define SPI_CON_MODE_8BIT (0 << SPI_CON_MODE_SHIFT) /* 8-bit data width */ +# define SPI_CON_MODE_16BIT (1 << SPI_CON_MODE_SHIFT) /* 16-bit data width */ +# define SPI_CON_MODE_32BIT (2 << SPI_CON_MODE_SHIFT) /* 2-bit data width */ +#define SPI_CON_DISSDO (1 << 12) /* Bits 12: Disable SDOx pin */ +#define SPI_CON_SIDL (1 << 13) /* Bits 13: Stop in idle mode */ +#define SPI_CON_FRZ (1 << 14) /* Bits 14: Freeze in debug exception */ +#define SPI_CON_ON (1 << 15) /* Bits 15: SPI peripheral on */ +#define SPI_CON_ENHBUF (1 << 16) /* Bits 16: Enhanced buffer enable */ +#define SPI_CON_SPIFE (1 << 17) /* Bits 17: Frame sync pulse edge select */ + /* Bits 18-23: Reserved */ +#if defined(CHIP_PIC32MX5) || defined(CHIP_PIC32MX6) || defined(CHIP_PIC32MX7) +# define SPI_CON_FRMCNT_SHIFT (24) /* Bits 24-26: Frame Sync Pulse Counter bits */ +# define SPI_CON_FRMCNT_MASK (7 << SPI_CON_FRMCNT_SHIFT) +# define SPI_CON_FRMCNT_CHAR1 (0 << SPI_CON_FRMCNT_SHIFT) /* Frame sync pulse each char */ +# define SPI_CON_FRMCNT_CHAR2 (1 << SPI_CON_FRMCNT_SHIFT) /* Frame sync pulse every 2 chars */ +# define SPI_CON_FRMCNT_CHAR4 (2 << SPI_CON_FRMCNT_SHIFT) /* Frame sync pulse every 4 chars */ +# define SPI_CON_FRMCNT_CHAR8 (3 << SPI_CON_FRMCNT_SHIFT) /* Frame sync pulse every 8 chars */ +# define SPI_CON_FRMCNT_CHAR16 (4 << SPI_CON_FRMCNT_SHIFT) /* Frame sync pulse every 16 chars */ +# define SPI_CON_FRMCNT_CHAR32 (5 << SPI_CON_FRMCNT_SHIFT) /* Frame sync pulse every 32 chars */ +# define SPI_CON_FRMSYPW (1 << 27) /* Bits 27: Frame sync pulse width */ +# define SPI_CON_MSSEN (1 << 28) /* Bits 28: Master mode slave select enable */ +#endif +#define SPI_CON_FRMPOL (1 << 29) /* Bits 29: Frame sync polarity */ +#define SPI_CON_FRMSYNC (1 << 30) /* Bits 30: Frame sync pulse direction control on SSx pin */ +#define SPI_CON_FRMEN (1 << 31) /* Bits 31: Framed SPI support */ + +/* SPI status register */ + +#if defined(CHIP_PIC32MX3) || defined(CHIP_PIC32MX4) +# define SPI_STAT_SPIRBF (1 << 0) /* Bits 0: SPI receive buffer full status */ +# define SPI_STAT_SPITBE (1 << 3) /* Bits 3: SPI transmit buffer empty status */ +# define SPI_STAT_SPIROV (1 << 6) /* Bits 6: Receive overflow flag */ +# define SPI_STAT_SPIBUSY (1 << 11) /* Bits 11: SPI activity status */ +#elif defined(CHIP_PIC32MX5) || defined(CHIP_PIC32MX6) || defined(CHIP_PIC32MX7) +# define SPI_STAT_SPIRBF (1 << 0) /* Bits 0: SPI receive buffer full status */ +# define SPI_STAT_SPITBF (1 << 1) /* Bits 1: SPI transmit buffer full status */ +# define SPI_STAT_SPITBE (1 << 3) /* Bits 3: SPI transmit buffer empty status */ +# define SPI_STAT_SPIRBE (1 << 5) /* Bits 5: RX FIFO Empty */ +# define SPI_STAT_SPIROV (1 << 6) /* Bits 6: Receive overflow flag */ +# define SPI_STAT_SRMT (1 << 7) /* Bits 6: Shift Register Empty */ +# define SPI_STAT_SPITUR (1 << 6) /* Bits 8: Transmit under run */ +# define SPI_STAT_SPIBUSY (1 << 11) /* Bits 11: SPI activity status */ +# define SPI_STAT_TXBUFELM_SHIFT (16) /* Bits 16-20: Transmit Buffer Element Count bits */ +# define SPI_STAT_TXBUFELM_MASK (31 << SPI_STAT_TXBUFELM_SHIFT) +# define SPI_STAT_RXBUFELM_SHIFT (24) /* Bits 24-28: Receive Buffer Element Count bits */ +# define SPI_STAT_RXBUFELM_MASK (31 << SPI_STAT_RXBUFELM_SHIFT) +#endif + +/* SPI buffer register (32-bits wide) */ + +/* SPI baud rate register */ + +#define SPI_BRG_MASK 0x1ff + +/**************************************************************************** + * Public Types + ****************************************************************************/ + +#ifndef __ASSEMBLY__ + +/**************************************************************************** + * Inline Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Function Prototypes + ****************************************************************************/ + +#ifdef __cplusplus +#define EXTERN extern "C" +extern "C" { +#else +#define EXTERN extern +#endif + +#undef EXTERN +#ifdef __cplusplus +} +#endif + +#endif /* __ASSEMBLY__ */ +#endif /* __ARCH_MIPS_SRC_PIC32MX_PIC32MX_SPI_H */ diff --git a/configs/sure-pic32mx/README.txt b/configs/sure-pic32mx/README.txt index a7ca6a5906..a9076171b6 100644 --- a/configs/sure-pic32mx/README.txt +++ b/configs/sure-pic32mx/README.txt @@ -452,10 +452,12 @@ selected as follow: Where is one of the following: ostest: + ------- This configuration directory, performs a simple OS test using apps/examples/ostest. nsh: + ---- Configures the NuttShell (nsh) located at apps/examples/nsh. The Configuration enables only the serial NSH interface. @@ -489,7 +491,8 @@ Where is one of the following: to enable the USB mass storage device. However, this device cannot work until support for the SD card is also incorporated. - usbnsh + usbnsh: + ------- This is another NSH example. If differs from the 'nsh' configuration above in that this configurations uses a USB serial device for console I/O. This configuration was created to support the "DB-DP11212 PIC32