From 9ae3b13c2cbbfc7602cc2fb643e290bbd3ba802b Mon Sep 17 00:00:00 2001 From: patacongo Date: Wed, 20 Jun 2012 17:37:20 +0000 Subject: PIC32MX1/2 pin selection logic; Mirtoo LEDs, SPI2, and UART2 configuration git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@4853 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/configs/mirtoo/README.txt | 40 ++++- nuttx/configs/mirtoo/include/board.h | 63 ++++++- nuttx/configs/mirtoo/ostest/defconfig | 18 +- nuttx/configs/mirtoo/src/Makefile | 6 +- nuttx/configs/mirtoo/src/mirtoo-internal.h | 8 +- nuttx/configs/mirtoo/src/up_boot.c | 48 +++++- nuttx/configs/mirtoo/src/up_leds.c | 258 +++++++++++++++++++++++++++++ nuttx/configs/mirtoo/src/up_spi2.c | 200 ++++++++++++++++++++++ nuttx/configs/pic32mx7mmb/include/board.h | 4 +- 9 files changed, 614 insertions(+), 31 deletions(-) create mode 100644 nuttx/configs/mirtoo/src/up_leds.c create mode 100644 nuttx/configs/mirtoo/src/up_spi2.c (limited to 'nuttx/configs') diff --git a/nuttx/configs/mirtoo/README.txt b/nuttx/configs/mirtoo/README.txt index 6125c40d1..055a71c2e 100644 --- a/nuttx/configs/mirtoo/README.txt +++ b/nuttx/configs/mirtoo/README.txt @@ -1,4 +1,4 @@ -configs/pic32mx README +configs/mirtoo README ===================== This README file discusses the port of NuttX to the DTX1-4000L "Mirtoo" module. @@ -11,6 +11,7 @@ Contents PIC32MX250F128D Pin Out Toolchains Loading NuttX with ICD3 + LED Usage PIC32MX Configuration Options Configurations @@ -53,15 +54,15 @@ PIN PIC32 SIGNAL(s) BOARD SIGNAL/USAGE --- ------------------------------------------------ ---------------------------------- ---------------------------------- 7 VCAP VCAP Not available off module --- ------------------------------------------------ ---------------------------------- ---------------------------------- - 8 PGED2/RPB10/D+/CTED11/RB10 FUNC0 FUNC0, to FT230XS RXD - PGED2 Debug Channel 2 data Not available + 8 PGED2/RPB10/D+/CTED11/RB10 FUNC0 FUNC0, to FT230XS RXD and debug port + PGED2 Debug Channel 2 data Used at boot time for ICD3 RPB10 Peripheral Selection, PORTB, Pin 10 Used for UART RXD D+ USB D+ Not available CTED11 CTMU External Edge Input 11 Not available RB10 PORTB, Pin 10 Not available --- ------------------------------------------------ ---------------------------------- ---------------------------------- 9 PGEC2/RPB11/D-/RB11 FUNC1 FUNC1, to FT230XS TXD - PGEC2 Debug Channel 2 clock Not available + PGEC2 Debug Channel 2 clock Used at boot time for ICD3 RPB11 Peripheral Selection, PORTB, Pin 11 Used for UART TXD D- USB D- Not available RB11 PORTB, Pin 11 Not available @@ -412,6 +413,35 @@ Loading NuttX with ICD3 # to the top-level build directory. It is the only # required input to mkpichex. +LED Usage +========= + + The Mirtoo module has 2 user LEDs labeled LED0 and LED1 in the schematics: + + --- ----- -------------------------------------------------------------- + PIN Board Notes + --- ----- -------------------------------------------------------------- + RC8 LED0 Grounded, high value illuminates + RC9 LED1 Grounded, high value illuminates + + The Dimitech DTX1-4000L EV-kit1 supports 3 more LEDs, but there are not + controllable from software. + + If CONFIG_ARCH_LEDS is defined, then NuttX will control these LEDs as + follows: + ON OFF + ------------------------- ---- ---- ---- ---- + LED0 LED1 LED0 LED1 + ------------------------- ---- ---- ---- ---- + LED_STARTED 0 OFF OFF --- --- + LED_HEAPALLOCATE 1 ON OFF --- --- + LED_IRQSENABLED 2 OFF ON --- --- + LED_STACKCREATED 3 ON ON --- --- + LED_INIRQ 4 ON N/C OFF N/C + LED_SIGNAL 4 ON N/C OFF N/C + LED_ASSERTION 4 ON N/C OFF N/C + LED_PANIC 4 ON N/C OFF N/C + PIC32MX Configuration Options ============================= @@ -522,11 +552,13 @@ PIC32MX Configuration Options CONFIG_PIC32MX_PMP - Parallel Master Port CONFIG_PIC32MX_CM1 - Comparator 1 CONFIG_PIC32MX_CM2 - Comparator 2 + CONFIG_PIC32MX_CM3 - Comparator 3 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_CTMU - CTMU PIC32MX Configuration Settings DEVCFG0: diff --git a/nuttx/configs/mirtoo/include/board.h b/nuttx/configs/mirtoo/include/board.h index ba6b0482d..98aa904a3 100644 --- a/nuttx/configs/mirtoo/include/board.h +++ b/nuttx/configs/mirtoo/include/board.h @@ -42,6 +42,9 @@ ****************************************************************************/ #include +#ifndef __ASSEMBLY__ +# include +#endif /**************************************************************************** * Pre-Processor Definitions @@ -85,15 +88,53 @@ #define BOARD_WD_PRESCALER 8 /* Watchdog pre-scaler */ /* LED definitions **********************************************************/ +/* The Mirtoo module has 2 user LEDs labeled LED0 and LED1 in the schematics: + * + * --- ----- -------------------------------------------------------------- + * PIN Board Notes + * --- ----- -------------------------------------------------------------- + * RC8 LED0 Grounded, high value illuminates + * RC9 LED1 Grounded, high value illuminates + * + * The Dimitech DTX1-4000L EV-kit1 supports 3 more LEDs, but there are not + * controllable from software. + */ + + /* LED index values for use with pic32mx_setled() */ + +#define PIC32MX_MIRTOO_LED0 0 +#define PIC32MX_MIRTOO_LED1 1 +#define PIC32MX_MIRTOO_NLEDS 2 + +/* LED bits for use with pic32mx_setleds() */ + +#define PIC32MX_MIRTOO_LED0_BIT (1 << PIC32MX_MIRTOO_LED0) +#define PIC32MX_MIRTOO_LED1_BIT (1 << PIC32MX_MIRTOO_LED1) + +/* If CONFIG_ARCH_LEDS is defined, then NuttX will control these LEDs as + * follows: + * ON OFF + * ------------------------- ---- ---- ---- ---- + * LED0 LED1 LED0 LED1 + * ------------------------- ---- ---- ---- ---- + * LED_STARTED 0 OFF OFF --- --- + * LED_HEAPALLOCATE 1 ON OFF --- --- + * LED_IRQSENABLED 2 OFF ON --- --- + * LED_STACKCREATED 3 ON ON --- --- + * LED_INIRQ 4 ON N/C OFF N/C + * LED_SIGNAL 4 ON N/C OFF N/C + * LED_ASSERTION 4 ON N/C OFF N/C + * LED_PANIC 4 ON N/C OFF 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 5 -#define LED_ASSERTION 6 -#define LED_PANIC 7 +#define LED_SIGNAL 4 +#define LED_ASSERTION 4 +#define LED_PANIC 4 /**************************************************************************** * Public Types @@ -116,6 +157,22 @@ extern "C" { #define EXTERN extern #endif +/**************************************************************************** + * Name: pic32mx_ledinit, pic32mx_setled, and pic32mx_setleds + * + * Description: + * If CONFIG_ARCH_LEDS is defined, then NuttX will control the on-board + * LEDs. If CONFIG_ARCH_LEDS is not defined, then the following interfaces + * are available to control the LEDs from user applicaitons. + * + ****************************************************************************/ + +#ifndef CONFIG_ARCH_LEDS +EXTERN void pic32mx_ledinit(void); +EXTERN void pic32mx_setled(int led, bool ledon); +EXTERN void pic32mx_setleds(uint8_t ledset); +#endif + #undef EXTERN #ifdef __cplusplus } diff --git a/nuttx/configs/mirtoo/ostest/defconfig b/nuttx/configs/mirtoo/ostest/defconfig index 51e2a4f58..6c2f0b89a 100644 --- a/nuttx/configs/mirtoo/ostest/defconfig +++ b/nuttx/configs/mirtoo/ostest/defconfig @@ -123,8 +123,6 @@ CONFIG_PIC32MX_MICROCHIPL_LITE=n # CONFIG_PIC32MX_WDT=n -CONFIG_PIC32MX_RTCC=n -CONFIG_PIC32MX_TIMER1=n CONFIG_PIC32MX_TIMER2=n CONFIG_PIC32MX_TIMER3=n CONFIG_PIC32MX_TIMER4=n @@ -143,13 +141,15 @@ CONFIG_PIC32MX_I2C1=n CONFIG_PIC32MX_I2C2=n CONFIG_PIC32MX_SPI1=n CONFIG_PIC32MX_SPI2=n -CONFIG_PIC32MX_UART1=y -CONFIG_PIC32MX_UART2=n -CONFIG_PIC32MX_PMP=n +CONFIG_PIC32MX_UART1=n +CONFIG_PIC32MX_UART2=y CONFIG_PIC32MX_ADC=n +CONFIG_PIC32MX_PMP=n CONFIG_PIC32MX_CVR=n CONFIG_PIC32MX_CM1=n CONFIG_PIC32MX_CM2=n +CONFIG_PIC32MX_CM3=n +CONFIG_PIC32MX_RTCC=n CONFIG_PIC32MX_OSC=y CONFIG_PIC32MX_DDP=n CONFIG_PIC32MX_FLASH=n @@ -161,10 +161,6 @@ CONFIG_PIC32MX_USBHOST=n CONFIG_PIC32MX_IOPORTA=y CONFIG_PIC32MX_IOPORTB=y CONFIG_PIC32MX_IOPORTC=y -CONFIG_PIC32MX_IOPORTD=y -CONFIG_PIC32MX_IOPORTE=y -CONFIG_PIC32MX_IOPORTF=y -CONFIG_PIC32MX_IOPORTG=y # # PIC32MX Configuration Settings @@ -204,8 +200,8 @@ CONFIG_PIC32MX_ICESEL=1 # CONFIG_UARTn_PARTIY - 0=no parity, 1=odd parity, 2=even parity # CONFIG_UARTn_2STOP - Two stop bits # -CONFIG_UART1_SERIAL_CONSOLE=y -CONFIG_UART2_SERIAL_CONSOLE=n +CONFIG_UART1_SERIAL_CONSOLE=n +CONFIG_UART2_SERIAL_CONSOLE=y CONFIG_UART1_TXBUFSIZE=256 CONFIG_UART2_TXBUFSIZE=256 diff --git a/nuttx/configs/mirtoo/src/Makefile b/nuttx/configs/mirtoo/src/Makefile index ed4a6e00a..fbde5728f 100644 --- a/nuttx/configs/mirtoo/src/Makefile +++ b/nuttx/configs/mirtoo/src/Makefile @@ -38,10 +38,10 @@ CFLAGS += -I$(TOPDIR)/sched ASRCS = -CSRCS = up_boot.c +CSRCS = up_boot.c up_leds.c -ifeq ($(CONFIG_ARCH_LEDS),y) -CSRCS += up_leds.c +ifeq ($(CONFIG_PIC32MX_SPI2),y) +CSRCS += up_spi2.c endif AOBJS = $(ASRCS:.S=$(OBJEXT)) diff --git a/nuttx/configs/mirtoo/src/mirtoo-internal.h b/nuttx/configs/mirtoo/src/mirtoo-internal.h index 69da95faf..7709e35e1 100644 --- a/nuttx/configs/mirtoo/src/mirtoo-internal.h +++ b/nuttx/configs/mirtoo/src/mirtoo-internal.h @@ -69,15 +69,15 @@ extern "C" { #endif /************************************************************************************ - * Name: pic32mx_spiinitialize + * Name: pic32mx_spi2initialize * * Description: - * Called to configure SPI chip select GPIO pins for the PCB Logic board. + * Called to configure SPI2 chip select GPIO pins for the Mirtoo module. * ************************************************************************************/ -#if defined(CONFIG_PIC32MX_SPI1) || defined(CONFIG_PIC32MX_SPI2) -EXTERN void weak_function pic32mx_spiinitialize(void); +#ifdef CONFIG_PIC32MX_SPI2 +EXTERN void weak_function pic32mx_spi2initialize(void); #endif /************************************************************************************ diff --git a/nuttx/configs/mirtoo/src/up_boot.c b/nuttx/configs/mirtoo/src/up_boot.c index 6ad41cf61..9dad76d0a 100644 --- a/nuttx/configs/mirtoo/src/up_boot.c +++ b/nuttx/configs/mirtoo/src/up_boot.c @@ -48,16 +48,52 @@ #include "up_internal.h" #include "pic32mx-internal.h" +#include "pic32mx-pps.h" #include "mirtoo-internal.h" /************************************************************************************ * Definitions ************************************************************************************/ +#define GPIO_U2TX (GPIO_OUTPUT|GPIO_PORTB|GPIO_PIN10) +#define GPIO_U2RX (GPIO_INPUT|GPIO_PORTB|GPIO_PIN11) + /************************************************************************************ * Private Functions ************************************************************************************/ +/************************************************************************************ + * Name: pic32mx_uartinitialize + * + * Description: + * When mounted on the DTX1-4000L EV-kit1 board, serial output is avaiable through + * an FT230X device via the FUNC0 and FUNC1 module outputs + * + * ---------- ------ ----- ------ ------------------------- + * BOARD OUTPUT PIN SIGNAL NOTES + * ---------- ------ ----- ------ ------------------------- + * FT230X RXD FUNC0 RPB11 U2RX UART2 RX (Also PGEC2) + * FT230X TXD FUNC1 RPB10 U2TX UART2 TX (Also PGED2) + * + ************************************************************************************/ + +static inline void pic32mx_uartinitialize(void) +{ +#ifdef CONFIG_PIC32MX_UART2 + /* Make sure that TRIS pins are set correctly. Configure the UART pins as digital + * inputs and outputs first. + */ + + pic32mx_configgpio(GPIO_U2TX); + pic32mx_configgpio(GPIO_U2RX); + + /* Configure UART TX and RX pins to RPB10 and 11, respectively */ + + putreg32(PPS_INSEL_RPB11, PIC32MX_PPS_U2RXR); + putreg32(PPS_OUTSEL_U2TX, PIC32MX_PPS_RPB10R); +#endif +} + /************************************************************************************ * Public Functions ************************************************************************************/ @@ -74,14 +110,18 @@ void pic32mx_boardinitialize(void) { + /* Configure the console UART */ + + pic32mx_uartinitialize(); + /* 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. + * function pic32mx_spi2initialize() has been brought into the link. */ -#if defined(CONFIG_PIC32MX_SPI1) || defined(CONFIG_PIC32MX_SPI2) - if (pic32mx_spiinitialize) +#ifdef CONFIG_PIC32MX_SPI2 + if (pic32mx_spi2initialize) { - pic32mx_spiinitialize(); + pic32mx_spi2initialize(); } #endif diff --git a/nuttx/configs/mirtoo/src/up_leds.c b/nuttx/configs/mirtoo/src/up_leds.c new file mode 100644 index 000000000..8eb719717 --- /dev/null +++ b/nuttx/configs/mirtoo/src/up_leds.c @@ -0,0 +1,258 @@ +/**************************************************************************** + * configs/mirtoo/src/up_leds.c + * arch/arm/src/board/up_leds.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 "pic32mx-internal.h" +#include "mirtoo-internal.h" + +/**************************************************************************** + * Definitions + ****************************************************************************/ +/* LED Configuration ********************************************************/ +/* The Mirtoo module has 2 user LEDs labeled LED0 and LED1 in the schematics: + * + * --- ----- -------------------------------------------------------------- + * PIN Board Notes + * --- ----- -------------------------------------------------------------- + * RC8 LED0 Grounded, high value illuminates + * RC9 LED1 Grounded, high value illuminates + * + * The Dimitech DTX1-4000L EV-kit1 supports 3 more LEDs, but there are not + * controllable from software. + * + * If CONFIG_ARCH_LEDS is defined, then NuttX will control these LEDs as + * follows: + * ON OFF + * ------------------------- ---- ---- ---- ---- + * LED0 LED1 LED0 LED1 + * ------------------------- ---- ---- ---- ---- + * LED_STARTED 0 OFF OFF --- --- + * LED_HEAPALLOCATE 1 ON OFF --- --- + * LED_IRQSENABLED 2 OFF ON --- --- + * LED_STACKCREATED 3 ON ON --- --- + * LED_INIRQ 4 ON N/C OFF N/C + * LED_SIGNAL 4 ON N/C OFF N/C + * LED_ASSERTION 4 ON N/C OFF N/C + * LED_PANIC 4 ON N/C OFF N/C + */ + +#define GPIO_LED_0 (GPIO_OUTPUT|GPIO_VALUE_ZERO|GPIO_PORTC|GPIO_PIN8) +#define GPIO_LED_1 (GPIO_OUTPUT|GPIO_VALUE_ZERO|GPIO_PORTC|GPIO_PIN9) + +/* 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 led0 : 2; + uint8_t led1 : 2; + uint8_t unused : 4; +}; +#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, 0}, + {LED_ON, LED_OFF, 0}, + {LED_OFF, LED_ON, 0}, + {LED_ON, LED_ON, 0}, + {LED_ON, LED_NC, 0}, +}; + +static const struct led_setting_s g_ledoffvalues[LED_NVALUES] = +{ + {LED_NC, LED_NC, 0}, + {LED_NC, LED_NC, 0}, + {LED_NC, LED_NC, 0}, + {LED_NC, LED_NC, 0}, + {LED_OFF, LED_NC, 0}, +}; + +/* If CONFIG_ARCH_LEDS is not defined, the the user can control the LEDs in + * any way. The following array simply maps the PIC32MX_MIRTOO_LEDn + * index values to the correct LED pin configuration. + */ + +#else +static const uint16_t g_ledpincfg[PIC32MX_MIRTOO_NLEDS] = +{ + GPIO_LED_0, GPIO_LED_1 +}; +#endif + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: up_setleds + ****************************************************************************/ + +#ifdef CONFIG_ARCH_LEDS +void up_setleds(FAR const struct led_setting_s *setting) +{ + /* LEDs are pulled up so writing a low value (false) illuminates them */ + + if (setting->led0 != LED_NC) + { + pic32mx_gpiowrite(GPIO_LED_0, setting->led0 == LED_ON); + } + + if (setting->led1 != LED_NC) + { + pic32mx_gpiowrite(GPIO_LED_1, setting->led1 == LED_ON); + } +} +#endif + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: pic32mx_ledinit + ****************************************************************************/ + +void pic32mx_ledinit(void) +{ + /* Configure output pins */ + + pic32mx_configgpio(GPIO_LED_0); + pic32mx_configgpio(GPIO_LED_1); +} + +/**************************************************************************** + * Name: pic32mx_setled + ****************************************************************************/ + +#ifndef CONFIG_ARCH_LEDS +void pic32mx_setled(int led, bool ledon) +{ + /* LEDs are pulled up so writing a low value (false) illuminates them */ + + if ((unsigned)led < PIC32MX_MIRTOO_NLEDS) + { + pic32mx_gpiowrite(g_ledpincfg[led], ledon); + } +} +#endif + +/**************************************************************************** + * Name: pic32mx_setleds + ****************************************************************************/ + +#ifndef CONFIG_ARCH_LEDS +void pic32mx_setleds(uint8_t ledset) +{ + /* Call pic32mx_setled() with ledon == true to illuminated the LED */ + + pic32mx_setled(PIC32MX_MIRTOO_LED0, (ledset & PIC32MX_MIRTOO_LED0_BIT) != 0); + pic32mx_setled(PIC32MX_MIRTOO_LED1, (ledset & PIC32MX_MIRTOO_LED1_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 diff --git a/nuttx/configs/mirtoo/src/up_spi2.c b/nuttx/configs/mirtoo/src/up_spi2.c new file mode 100644 index 000000000..785eadb80 --- /dev/null +++ b/nuttx/configs/mirtoo/src/up_spi2.c @@ -0,0 +1,200 @@ +/************************************************************************************ + * configs/mirtoo/src/up_spi2.c + * arch/arm/src/board/up_spi2.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 "up_arch.h" +#include "chip.h" +#include "pic32mx-internal.h" +#include "pic32mx-pps.h" +#include "mirtoo_internal.h" + +#ifdef CONFIG_PIC32MX_SPI2 + +/************************************************************************************ + * Definitions + ************************************************************************************/ + +/* The Mirtoo module as two on-board SPI devices: + * + * SST25VF032B - 32-Mbit SPI Serial FLASH + * + * PGA117 - Zero drift programmable gain amplifier with MUX. The PGA117 offers 10 + * analog inputs, a four-pin SPI interface with daisy-chain capability, and hardware + * and software shutdown in a TSSOP-20 package. Only 8 of the analog inputs (PORT0-7) + * are used on the Mirtoo module. + * + * Chip selects: + * + * ------ -------- ------------------------- -------------------------------- + * PIN SIGNAL BOARD CONNECTION NOTES + * ------ -------- ------------------------- -------------------------------- + * RPA1 SI PGA117 and SST25VF032B SPI2 data OUT (SDO2) + * RPA2 SO PGA117 and SST25VF032B SPI2 data IN (SDI2) + * SCK2 SCK PGA117 and SST25VF032B SPI2 clock + * + * RB7 ~CSAI PGA117 PGA117 chip select (active low) + * RB13 ~CSM SST25VF032B SST25VF032B chip select (active low) + */ + +#define GPIO_SI (GPIO_OUTPUT|GPIO_PORTA|GPIO_PIN1) +#define GPIO_SO (GPIO_INPUT|GPIO_PORTA|GPIO_PIN1) +#define GPIO_SCK (GPIO_OUTPUT|GPIO_PORTA|GPIO_PIN1) + +#define GPIO_PGA117_CS (GPIO_OUTPUT|GPIO_VALUE_ONE|GPIO_PORTB|GPIO_PIN7) +#define GPIO_SST25VF032B_CS (GPIO_OUTPUT|GPIO_VALUE_ONE|GPIO_PORTB|GPIO_PIN13) + +/* The following enable debug output from this file (needs CONFIG_DEBUG too). + * + * CONFIG_DEBUG_SPI - Define to enable basic SPI debug + */ + +#ifdef CONFIG_DEBUG_SPI +# define spidbg lldbg +# define spivdbg llvdbg +#else +# define spidbg(x...) +# define spivdbg(x...) +#endif + +/************************************************************************************ + * Private Functions + ************************************************************************************/ + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +/************************************************************************************ + * Name: pic32mx_spi2initialize + * + * Description: + * Called to configure SPI2 chip select GPIO pins for the Mirtoo module. + * + ************************************************************************************/ + +void weak_function pic32mx_spi2initialize(void) +{ + uint32_t regval; + + /* Make sure that TRIS pins are set correctly. Configure the SPI pins as digital + * inputs and outputs first. + */ + + pic32mx_configgpio(GPIO_SI); + pic32mx_configgpio(GPIO_SO); + pic32mx_configgpio(GPIO_SCK); + + /* Configure SPI2 data in and data out to use RPA2 and 1, respectively */ + + putreg32(PPS_INSEL_RPA2, PIC32MX_PPS_SDI2R); + putreg32(PPS_OUTSEL_SDO2, PIC32MX_PPS_RPA1R); + + /* Configure the SPI chip select GPIOs */ + + pic32mx_configgpio(GPIO_PGA117_CS); + pic32mx_configgpio(GPIO_SST25VF032B_CS); +} + +/************************************************************************************ + * Name: pic32mx_spi2select, pic32mx_spi2status, and pic32mx_spi2cmddata + * + * 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 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; + +void pic31mx_spi2select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +{ + spidbg("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); + + if (devid == SPIDEV_FLASH) + { + pic32mx_gpiowrite(GPIO_SST25VF032B_CS, !selected); + } + else if (devid == SPIDEV_MUX) + { + pic32mx_gpiowrite(GPIO_PGA117_CS, !selected); + } +} + +uint8_t pic31mx_spi2status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +{ + return 0; +} + +#ifdef CONFIG_SPI_CMDDATA +int pic31mx_spi2cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd) +{ + return 0; +} +#endif + +#endif /* CONFIG_PIC32MX_SPI2 */ diff --git a/nuttx/configs/pic32mx7mmb/include/board.h b/nuttx/configs/pic32mx7mmb/include/board.h index e8b244283..c4bf715e4 100644 --- a/nuttx/configs/pic32mx7mmb/include/board.h +++ b/nuttx/configs/pic32mx7mmb/include/board.h @@ -134,8 +134,8 @@ /* LED bits for use with pic32mx_setleds() */ #define PIC32MX_PIC32MX7MMB_LED0_BIT (1 << PIC32MX_PIC32MX7MMB_LED0) -#define PIC32MX_PIC32MX7MMB_LED1_BIT (1 << PIC32MX_PIC32MX7MMB_LED2) -#define PIC32MX_PIC32MX7MMB_LED2_BIT (1 << PIC32MX_PIC32MX7MMB_LED3) +#define PIC32MX_PIC32MX7MMB_LED1_BIT (1 << PIC32MX_PIC32MX7MMB_LED1) +#define PIC32MX_PIC32MX7MMB_LED2_BIT (1 << PIC32MX_PIC32MX7MMB_LED2) /* If CONFIG_ARCH_LEDs is defined, then NuttX will control the 3 LEDs * on board the Mikroelektronika PIC32MX7 MMB. The following definitions -- cgit v1.2.3