configs/mcb1700: Add support for Keil MCB1700 board

This commit is contained in:
Alan Carvalho de Assis 2017-11-18 10:57:25 -06:00 committed by Gregory Nutt
parent 55a17d80cd
commit 494d2a486c
20 changed files with 2220 additions and 1 deletions

View File

@ -8,7 +8,7 @@
<tr align="center" bgcolor="#e4e4e4">
<td>
<h1><big><font color="#3c34ec"><i>NuttX README Files</i></font></big></h1>
<p>Last Updated: November 13, 2017</p>
<p>Last Updated: November 18, 2017</p>
</td>
</tr>
</table>
@ -142,6 +142,8 @@ nuttx/
| | `- <a href="https://bitbucket.org/nuttx/nuttx/src/master/configs/maple/README.txt" target="_blank"><b><i>README.txt</i></b></a>
| |- mbed/
| | `- <a href="https://bitbucket.org/nuttx/nuttx/src/master/configs/mbed/README.txt" target="_blank"><b><i>README.txt</i></b></a>
| |- mcb1700/
| | `- <a href="https://bitbucket.org/nuttx/nuttx/src/master/configs/mcb1700/README.txt" target="_blank"><b><i>README.txt</i></b></a>
| |- mcu123-lpc214x/
| | `- <a href="https://bitbucket.org/nuttx/nuttx/src/master/configs/mcu123-lpc214x/README.txt" target="_blank"><b><i>README.txt</i></b></a>
| |- micropendous3/

View File

@ -1685,6 +1685,8 @@ nuttx/
| | `- README.txt
| |- mbed/
| | `- README.txt
| |- mcb1700/
| | `- README.txt
| |- mcu123-lpc214x/
| | `- README.txt
| |- micropendous3/

View File

@ -381,6 +381,13 @@ config ARCH_BOARD_MBED
that features the NXP LPC1768 microcontroller. This OS is also built
with the arm-nuttx-elf toolchain*. STATUS: Contributed.
config ARCH_BOARD_MCB1700
bool "Keil MCB1700"
depends on ARCH_CHIP_LPC1768
select ARCH_HAVE_LEDS
---help---
The configurations in this directory support the Keil MCB1700.
config ARCH_BOARD_MCU123_LPC214X
bool "mcu123.com LPC2148 Development Board"
depends on ARCH_CHIP_LPC214X
@ -1599,6 +1606,7 @@ config ARCH_BOARD
default "lpcxpresso-lpc1768" if ARCH_BOARD_LPCXPRESSO
default "maple" if ARCH_BOARD_MAPLE
default "mbed" if ARCH_BOARD_MBED
default "mcb1700" if ARCH_BOARD_MCB1700
default "mcu123-lpc214x" if ARCH_BOARD_MCU123_LPC214X
default "micropendous3" if ARCH_BOARD_MICROPENDOUS3
default "mirtoo" if ARCH_BOARD_MIRTOO
@ -1859,6 +1867,9 @@ endif
if ARCH_BOARD_MBED
source "configs/mbed/Kconfig"
endif
if ARCH_BOARD_MCB1700
source "configs/mcb1700/Kconfig"
endif
if ARCH_BOARD_MCU123_LPC214X
source "configs/mcu123-lpc214x/Kconfig"
endif

View File

@ -342,6 +342,9 @@ configs/mbed
that features the NXP LPC1768 microcontroller. This OS is also built
with the arm-nuttx-elf toolchain*. STATUS: Contributed.
configs/mcb1700
Board support for the Keil MCB1700
configs/mikroe-stm32f4
This is the port of NuttX to the MikroElektronika Mikromedia for STM32F4
development board. Contributed by Ken Petit.

7
configs/mcb1700/Kconfig Normal file
View File

@ -0,0 +1,7 @@
#
# For a description of the syntax of this configuration file,
# see the file kconfig-language.txt in the NuttX tools repository.
#
if ARCH_BOARD_MCB1700
endif

278
configs/mcb1700/README.txt Normal file
View File

@ -0,0 +1,278 @@
README
^^^^^^
README for NuttX port to the Keil mcb1700 LPC1768 board.
Contents
^^^^^^^^
USB Device Controller Functions
mcb1700 Configuration Options
USB Host Configuration
Configurations
mcb1700 Configuration Options
^^^^^^^^^^^^^^^^^^^^^^^^^^
CONFIG_ARCH - Identifies the arch/ subdirectory. This should
be set to:
CONFIG_ARCH=arm
CONFIG_ARCH_family - For use in C code:
CONFIG_ARCH_ARM=y
CONFIG_ARCH_architecture - For use in C code:
CONFIG_ARCH_CORTEXM3=y
CONFIG_ARCH_CHIP - Identifies the arch/*/chip subdirectory
CONFIG_ARCH_CHIP=lpc17xx
CONFIG_ARCH_CHIP_name - For use in C code to identify the exact
chip:
CONFIG_ARCH_CHIP_LPC1768=y
CONFIG_ARCH_BOARD - Identifies the configs subdirectory and
hence, the board that supports the particular chip or SoC.
CONFIG_ARCH_BOARD=mcb1700 (for the mcb1700.org board)
CONFIG_ARCH_BOARD_name - For use in C code
CONFIG_ARCH_BOARD_MCB1700=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_RAM_SIZE - Describes the installed DRAM (CPU SRAM in this case):
CONFIG_RAM_SIZE=(32*1024) (32Kb)
There is an additional 32Kb of SRAM in AHB SRAM banks 0 and 1.
CONFIG_RAM_START - The start address of installed DRAM
CONFIG_RAM_START=0x10000000
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.
Individual subsystems can be enabled:
CONFIG_LPC17_MAINOSC=y
CONFIG_LPC17_PLL0=y
CONFIG_LPC17_PLL1=n
CONFIG_LPC17_ETHERNET=n
CONFIG_LPC17_USBHOST=n
CONFIG_LPC17_USBOTG=n
CONFIG_LPC17_USBDEV=n
CONFIG_LPC17_UART0=y
CONFIG_LPC17_UART1=n
CONFIG_LPC17_UART2=n
CONFIG_LPC17_UART3=n
CONFIG_LPC17_CAN1=n
CONFIG_LPC17_CAN2=n
CONFIG_LPC17_SPI=n
CONFIG_LPC17_SSP0=n
CONFIG_LPC17_SSP1=n
CONFIG_LPC17_I2C0=n
CONFIG_LPC17_I2C1=n
CONFIG_LPC17_I2S=n
CONFIG_LPC17_TMR0=n
CONFIG_LPC17_TMR1=n
CONFIG_LPC17_TMR2=n
CONFIG_LPC17_TMR3=n
CONFIG_LPC17_RIT=n
CONFIG_LPC17_PWM0=n
CONFIG_LPC17_MCPWM=n
CONFIG_LPC17_QEI=n
CONFIG_LPC17_RTC=n
CONFIG_LPC17_WDT=n
CONFIG_LPC17_ADC=n
CONFIG_LPC17_DAC=n
CONFIG_LPC17_GPDMA=n
CONFIG_LPC17_FLASH=n
LPC17xx specific device driver settings
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
LPC17xx specific CAN device driver settings. These settings all
require CONFIG_CAN:
CONFIG_CAN_EXTID - Enables support for the 29-bit extended ID. Default
Standard 11-bit IDs.
CONFIG_CAN1_BAUD - CAN1 BAUD rate. Required if CONFIG_LPC17_CAN1 is defined.
CONFIG_CAN2_BAUD - CAN1 BAUD rate. Required if CONFIG_LPC17_CAN2 is defined.
CONFIG_CAN1_DIVISOR - CAN1 is clocked at CCLK divided by this number.
(the CCLK frequency is divided by this number to get the CAN clock).
Options = {1,2,4,6}. Default: 4.
CONFIG_CAN2_DIVISOR - CAN2 is clocked at CCLK divided by this number.
(the CCLK frequency is divided by this number to get the CAN clock).
Options = {1,2,4,6}. Default: 4.
CONFIG_CAN_TSEG1 - The number of CAN time quanta in segment 1. Default: 6
CONFIG_CAN_TSEG2 = the number of CAN time quanta in segment 2. Default: 7
LPC17xx specific PHY/Ethernet device driver settings. These setting
also require CONFIG_NET and CONFIG_LPC17_ETHERNET.
CONFIG_ETH0_PHY_KS8721 - Selects Micrel KS8721 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_EMACRAM_SIZE - Size of EMAC RAM. Default: 16Kb
CONFIG_NET_NTXDESC - Configured number of Tx descriptors. Default: 18
CONFIG_NET_NRXDESC - Configured number of Rx descriptors. Default: 18
CONFIG_NET_WOL - Enable Wake-up on Lan (not fully implemented).
CONFIG_NET_REGDEBUG - Enabled low level register debug. Also needs
CONFIG_DEBUG_FEATURES.
CONFIG_NET_DUMPPACKET - Dump all received and transmitted packets.
Also needs CONFIG_DEBUG_FEATURES.
CONFIG_NET_HASH - Enable receipt of near-perfect match frames.
CONFIG_LPC17_MULTICAST - Enable receipt of multicast (and unicast) frames.
Automatically set if CONFIG_NET_IGMP is selected.
LPC17xx USB Device Configuration
CONFIG_LPC17_USBDEV_FRAME_INTERRUPT
Handle USB Start-Of-Frame events.
Enable reading SOF from interrupt handler vs. simply reading on demand.
Probably a bad idea... Unless there is some issue with sampling the SOF
from hardware asynchronously.
CONFIG_LPC17_USBDEV_EPFAST_INTERRUPT
Enable high priority interrupts. I have no idea why you might want to
do that
CONFIG_LPC17_USBDEV_NDMADESCRIPTORS
Number of DMA descriptors to allocate in SRAM.
CONFIG_LPC17_USBDEV_DMA
Enable lpc17xx-specific DMA support
CONFIG_LPC17_USBDEV_NOVBUS
Define if the hardware implementation does not support the VBUS signal
CONFIG_LPC17_USBDEV_NOLED
Define if the hardware implementation does not support the LED output
LPC17xx USB Host Configuration
CONFIG_USBHOST_OHCIRAM_SIZE
Total size of OHCI RAM (in AHB SRAM Bank 1)
CONFIG_USBHOST_NEDS
Number of endpoint descriptors
CONFIG_USBHOST_NTDS
Number of transfer descriptors
CONFIG_USBHOST_TDBUFFERS
Number of transfer descriptor buffers
CONFIG_USBHOST_TDBUFSIZE
Size of one transfer descriptor buffer
CONFIG_USBHOST_IOBUFSIZE
Size of one end-user I/O buffer. This can be zero if the
application can guarantee that all end-user I/O buffers
reside in AHB SRAM.
USB Host Configuration
^^^^^^^^^^^^^^^^^^^^^^
The mcb1700 board can be easily modified to support a USB host interface
(Remember to add 2 resistors of 15K to D+ and D- pins).
The NuttShell (NSH) mcb1700 can also be modified in order to support USB
host operations. To make these modifications, do the following:
1. First configure to build the NSH configuration from the top-level
NuttX directory:
cd tools
./configure mcb1700/nsh
cd ..
2. Then edit the top-level .config file to enable USB host. Make the
following changes using 'make menuconfig':
System Type -> LPC17xx Peripheral Support
CONFIG_LPC17_USBHOST=y : USB host controller driver support
Device Drivers -> USB Host Driver Support
CONFIG_USBHOST=y : USB host support
CONFIG_USBHOST_ISOC_DISABLE=y : Not needed
CONFIG_USBHOST_MSC=y : Mass storage class support
Library Routines
CONFIG_SCHED_WORKQUEUE=y : Enable worker thread
When this change is made, NSH should be extended to support USB flash
devices. When a FLASH device is inserted, you should see a device
appear in the /dev (pseudo) directory. The device name should be
like /dev/sda, /dev/sdb, etc. The USB mass storage device, is present
it can be mounted from the NSH command line like:
ls /dev
mount -t vfat /dev/sda /mnt/flash
Files on the connect USB flash device should then be accessible under
the mountpoint /mnt/flash.
Configurations
^^^^^^^^^^^^^^
General
-------
Each mcb1700 configuration is maintained in a sub-directory and can be selected
as follow:
cd tools
./configure.sh mcb1700/<subdir>
cd -
Where <subdir> is one of the mcb1700 subdirectories described in the
following paragraph.
NOTES:
1. These configurations use the mconf-based configuration tool. To
change any of these configurations using that tool, you should:
a. Build and install the kconfig-mconf tool. See nuttx/README.txt
see additional README.txt files in the NuttX tools repository.
b. Execute 'make menuconfig' in nuttx/ in order to start the
reconfiguration process.
Configuration Sub-directories
-----------------------------
nsh:
Configures the NuttShell (nsh) located at examples/nsh. The
Configuration enables only the serial NSH interfaces. See notes
above for enabling USB host support in this configuration.

View File

@ -0,0 +1,328 @@
/************************************************************************************
* configs/mcb1700/include/board.h
*
* Copyright (C) 2017 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_MCB1700_INCLUDE_BOARD_H
#define __CONFIGS_MCB1700_INCLUDE_BOARD_H
/************************************************************************************
* Included Files
************************************************************************************/
#include <nuttx/config.h>
/************************************************************************************
* Pre-processor Definitions
************************************************************************************/
/* Clocking *************************************************************************/
/* NOTE: The following definitions require lpc17_syscon.h. It is not included here
* because the including C file may not have that file in its include path.
*/
#define BOARD_XTAL_FREQUENCY (12000000) /* XTAL oscillator frequency */
#define BOARD_OSCCLK_FREQUENCY BOARD_XTAL_FREQUENCY /* Main oscillator frequency */
#define BOARD_RTCCLK_FREQUENCY (32000) /* RTC oscillator frequency */
#define BOARD_INTRCOSC_FREQUENCY (4000000) /* Internal RC oscillator frequency */
/* This is the clock setup we configure for:
*
* SYSCLK = BOARD_OSCCLK_FREQUENCY = 12MHz -> Select Main oscillator for source
* PLL0CLK = (2 * 20 * SYSCLK) / 1 = 480MHz -> PLL0 multiplier=20, pre-divider=1
* CCLCK = 480MHz / 6 = 80MHz -> CCLK divider = 6
*/
#define LPC17_CCLK 80000000 /* 80Mhz*/
/* Select the main oscillator as the frequency source. SYSCLK is then the frequency
* of the main oscillator.
*/
#undef CONFIG_LPC17_MAINOSC
#define CONFIG_LPC17_MAINOSC 1
#define BOARD_SCS_VALUE SYSCON_SCS_OSCEN
/* Select the main oscillator and CCLK divider. The output of the divider is CCLK.
* The input to the divider (PLLCLK) will be determined by the PLL output.
*/
#define BOARD_CCLKCFG_DIVIDER 6
#define BOARD_CCLKCFG_VALUE ((BOARD_CCLKCFG_DIVIDER-1) << SYSCON_CCLKCFG_SHIFT)
/* PLL0. PLL0 is used to generate the CPU clock divider input (PLLCLK).
*
* Source clock: Main oscillator
* PLL0 Multiplier value (M): 20
* PLL0 Pre-divider value (N): 1
*
* PLL0CLK = (2 * 20 * SYSCLK) / 1 = 480MHz
*/
#undef CONFIG_LPC17_PLL0
#define CONFIG_LPC17_PLL0 1
#define BOARD_CLKSRCSEL_VALUE SYSCON_CLKSRCSEL_MAIN
#define BOARD_PLL0CFG_MSEL 20
#define BOARD_PLL0CFG_NSEL 1
#define BOARD_PLL0CFG_VALUE \
(((BOARD_PLL0CFG_MSEL-1) << SYSCON_PLL0CFG_MSEL_SHIFT) | \
((BOARD_PLL0CFG_NSEL-1) << SYSCON_PLL0CFG_NSEL_SHIFT))
/* PLL1 -- Not used. */
#undef CONFIG_LPC17_PLL1
#define BOARD_PLL1CFG_MSEL 36
#define BOARD_PLL1CFG_NSEL 1
#define BOARD_PLL1CFG_VALUE \
(((BOARD_PLL1CFG_MSEL-1) << SYSCON_PLL1CFG_MSEL_SHIFT) | \
((BOARD_PLL1CFG_NSEL-1) << SYSCON_PLL1CFG_NSEL_SHIFT))
/* USB divider. This divider is used when PLL1 is not enabled to get the
* USB clock from PLL0:
*
* USBCLK = PLL0CLK / 10 = 48MHz
*/
#define BOARD_USBCLKCFG_VALUE SYSCON_USBCLKCFG_DIV10
/* FLASH Configuration */
#undef CONFIG_LPC17_FLASH
#define CONFIG_LPC17_FLASH 1
#define BOARD_FLASHCFG_VALUE 0x0000303a
/* Ethernet configuration */
//#define ETH_MCFG_CLKSEL_DIV ETH_MCFG_CLKSEL_DIV44
#define ETH_MCFG_CLKSEL_DIV ETH_MCFG_CLKSEL_DIV20
/* LED definitions ******************************************************************/
/* The MCB1700 has 4 LEDs along the bottom of the board. Blue or off.
* If CONFIG_ARCH_LEDS is defined, the LEDs will be controlled as follows for NuttX
* debug functionality (where NC means "No Change").
*
* During the boot phases. LED1 and LED2 will show boot status. LED3/4 Not used.
*/
/* LED1 LED2 */
#define LED_STARTED 0 /* OFF OFF */
#define LED_HEAPALLOCATE 1 /* BLUE OFF */
#define LED_IRQSENABLED 2 /* OFF BLUE */
#define LED_STACKCREATED 3 /* OFF OFF */
/* After the system is booted, this logic will no longer use LEDs 1 & 2. They
* are available together with LED3 for use the application software using
* lpc17_led (prototyped below)
*/
/* LED1 LED2 LED3 LED4 */
#define LED_INIRQ 4 /* NC NC NC ON (momentary) */
#define LED_SIGNAL 5 /* NC NC NC ON (momentary) */
#define LED_ASSERTION 6 /* NC NC NC ON (momentary) */
#define LED_PANIC 7 /* NC NC NC ON (1Hz flashing) */
#define GPIO_SSP0_SCK GPIO_SSP0_SCK_1
#define GPIO_SSP0_SSEL GPIO_SSP0_SSEL_1
#define GPIO_SSP0_MISO GPIO_SSP0_MISO_1
#define GPIO_SSP0_MOSI GPIO_SSP0_MOSI_1
/* We need to redefine USB_PWRD as GPIO to get USB Host working
* Also remember to add 2 resistors of 15K to D+ and D- pins.
*/
#ifdef CONFIG_USBHOST
# ifdef GPIO_USB_PWRD
# undef GPIO_USB_PWRD
# define GPIO_USB_PWRD (GPIO_INPUT | GPIO_PORT1 | GPIO_PIN22)
# endif
#endif
/* Alternate pin selections *********************************************************/
/* Pin Description Connector On Board Base Board
* -------------------------------- --------- -------------- ---------------------
* P0[0]/RD1/TXD3/SDA1 J6-9 I2C E2PROM SDA TXD3/SDA1
* P0[1]/TD1/RXD3/SCL J6-10 RXD3/SCL1
* P0[2]/TXD0/AD0[7] J6-21
* P0[3]/RXD0/AD0[6] J6-22
* P0[4]/I2SRX-CLK/RD2/CAP2.0 J6-38 CAN_RX2
* P0[5]/I2SRX-WS/TD2/CAP2.1 J6-39 CAN_TX2
* P0[6]/I2SRX_SDA/SSEL1/MAT2[0] J6-8 SSEL1, OLED CS
* P0[7]/I2STX_CLK/SCK1/MAT2[1] J6-7 SCK1, OLED SCK
* P0[8]/I2STX_WS/MISO1/MAT2[2] J6-6 MISO1
* P0[9]/I2STX_SDA/MOSI1/MAT2[3] J6-5 MOSI1, OLED data in
* P0[10] J6-40 TXD2/SDA2
* P0[11] J6-41 RXD2/SCL2
* P0[15]/TXD1/SCK0/SCK J6-13 TXD1/SCK0
* P0[16]/RXD1/SSEL0/SSEL J6-14 RXD1/SSEL0
* P0[17]/CTS1/MISO0/MISO J6-12 MISO0
* P0[18]/DCD1/MOSI0/MOSI J6-11 MOSI0
* P0[19]/DSR1/SDA1 PAD17 N/A
* P0[20]/DTR1/SCL1 PAD18 I2C E2PROM SCL N/A
* P0[21]/RI1/MCIPWR/RD1 J6-23
* P0[22]/RTS1/TD1 J6-24 LED
* P0[23]/AD0[0]/I2SRX_CLK/CAP3[0] J6-15 AD0.0
* P0[24]/AD0[1]/I2SRX_WS/CAP3[1] J6-16 AD0.1
* P0[25]/AD0[2]/I2SRX_SDA/TXD3 J6-17 AD0.2
* P0[26]/AD0[3]/AOUT/RXD3 J6-18 AD0.3/AOUT / RGB LED
* P0[27]/SDA0/USB_SDA J6-25
* P0[28]/SCL0 J6-26
* P0[29]/USB_D+ J6-37 USB_D+
* P0[30]/USB_D- J6-36 USB_D-
*/
#define GPIO_UART3_TXD GPIO_UART3_TXD_1
#define GPIO_I2C1_SDA GPIO_I2C1_SDA_1
#define GPIO_UART3_RXD GPIO_UART3_RXD_1
#define GPIO_I2C1_SCL GPIO_I2C1_SCL_1
#define GPIO_SSP1_SCK GPIO_SSP1_SCK_1
#define GPIO_UART2_TXD GPIO_UART2_TXD_1
#define GPIO_UART2_RXD GPIO_UART2_RXD_1
#define GPIO_UART1_TXD GPIO_UART1_TXD_1
#define GPIO_SSP0_SCK GPIO_SSP0_SCK_1
#define GPIO_UART1_RXD GPIO_UART1_RXD_1
#define GPIO_SSP0_SSEL GPIO_SSP0_SSEL_1
#define GPIO_SSP0_MISO GPIO_SSP0_MISO_1
#define GPIO_SSP0_MOSI GPIO_SSP0_MOSI_1
/* P1[0]/ENET-TXD0 J6-34? TXD0 TX-(Ethernet PHY)
* P1[1]/ENET_TXD1 J6-35? TXD1 TX+(Ethernet PHY)
* P1[4]/ENET_TX_EN TXEN N/A
* P1[8]/ENET_CRS CRS_DV/MODE2 N/A
* P1[9]/ENET_RXD0 J6-32? RXD0/MODE0 RD-(Ethernet PHY)
* P1[10]/ENET_RXD1 J6-33? RXD1/MODE1 RD+(Ethernet PHY)
* P1[14]/ENET_RX_ER RXER/PHYAD0 N/A
* P1[15]/ENET_REF_CLK REFCLK N/A
* P1[16]/ENET_MDC MDC N/A
* P1[17]/ENET_MDIO MDIO N/A
* P1[18]/USB_UP_LED/PWM1[1]/CAP1[0] PAD1 N/A
* P1[19]/MC0A/USB_PPWR/N_CAP1.1 PAD2 N/A
* P1[20]/MCFB0/PWM1.2/SCK0 PAD3 N/A
* P1[21]/MCABORT/PWM1.3/SSEL0 PAD4 N/A
* P1[22]/MC0B/USB-PWRD/MAT1.0 PAD5 N/A
* P1[23]/MCFB1/PWM1.4/MISO0 PAD6 N/A
* P1[24]/MCFB2/PWM1.5/MOSI0 PAD7 N/A
* P1[25]/MC1A/MAT1.1 PAD8 N/A
* P1[26]/MC1B/PWM1.6/CAP0.0 PAD9 N/A
* P1[27]/CLKOUT/USB-OVRCR-N/CAP0.1 PAD10 N/A
* P1[28]/MC2A/PCAP1.0/MAT0.0 PAD11 N/A
* P1[29]/MC2B/PCAP1.1/MAT0.1 PAD12 N/A
* P1[30]/VBUS/AD0[4] J6-19 AD0.4
* P1[31]/SCK1/AD0[5] J6-20 AD0.5
*/
#define GPIO_ENET_MDC GPIO_ENET_MDC_1
#define GPIO_ENET_MDIO GPIO_ENET_MDIO_1
/* P2[0]/PWM1.1/TXD1 J6-42 PWM1.1 / RGB LED / RS422 RX
* P2[1]/PWM1.2/RXD1 J6-43 PWM1.2 / OLED voltage / RGB LED / RS422 RX
* P2[2]/PWM1.3/CTS1/TRACEDATA[3] J6-44 PWM1.3
* P2[3]/PWM1.4/DCD1/TRACEDATA[2] J6-45 PWM1.4
* P2[4]/PWM1.5/DSR1/TRACEDATA[1] J6-46 PWM1.5
* P2[5]/PWM1[6]/DTR1/TRACEDATA[0] J6-47 PWM1.6
* P2[6]/PCAP1[0]/RI1/TRACECLK J6-48
* P2[7]/RD2/RTS1 J6-49 OLED command/data
* P2[8]/TD2/TXD2 J6-50
* P2[9]/USB_CONNECT/RXD2 PAD19 USB Pullup N/A
* P2[10]/EINT0/NMI J6-51
* P2[11]/EINT1/I2STX_CLK J6-52
* P2[12]/EINT2/I2STX_WS J6-53
* P2[13]/EINT3/I2STX_SDA J6-27
*/
#define GPIO_PWM1p1 GPIO_PWM1p1_2
#define GPIO_PWM1p2 GPIO_PWM1p2_2
#define GPIO_PWM1p3 GPIO_PWM1p3_2
#define GPIO_PWM1p4 GPIO_PWM1p4_2
#define GPIO_PWM1p5 GPIO_PWM1p5_2
#define GPIO_PWM1p6 GPIO_PWM1p6_2
/* P3[25]/MAT0.0/PWM1.2 PAD13 N/A
* P3[26]/STCLK/MAT0.1/PWM1.3 PAD14 N/A
*
* P4[28]/RX-MCLK/MAT2.0/TXD3 PAD15 N/A
* P4[29]/TX-MCLK/MAT2.1/RXD3 PAD16 N/A
*/
/************************************************************************************
* Public Types
************************************************************************************/
#ifndef __ASSEMBLY__
/************************************************************************************
* Public Data
************************************************************************************/
#undef EXTERN
#if defined(__cplusplus)
#define EXTERN extern "C"
extern "C"
{
#else
#define EXTERN extern
#endif
/************************************************************************************
* Public Function Prototypes
************************************************************************************/
/************************************************************************************
* Name: lpc17_boardinitialize
*
* Description:
* All LPC17xx architectures must provide the following entry point. This entry point
* is called early in the initialization -- after all memory has been configured
* and mapped but before any devices have been initialized.
*
************************************************************************************/
void lpc17_boardinitialize(void);
/************************************************************************************
* Name: lpc17_led
*
* Description:
* Once the system has booted, these functions can be used to control LEDs 1, 2 & 3
*
************************************************************************************/
#ifdef CONFIG_ARCH_LEDS
void lpc17_led(int lednum, int state);
#endif
#undef EXTERN
#if defined(__cplusplus)
}
#endif
#endif /* __ASSEMBLY__ */
#endif /* __CONFIGS_MCB1700_INCLUDE_BOARD_H */

View File

@ -0,0 +1,50 @@
# CONFIG_MMCSD_HAVECARDDETECT is not set
# CONFIG_MMCSD_MMCSUPPORT is not set
# CONFIG_NSH_ARGCAT is not set
# CONFIG_NSH_CMDOPT_DF_H is not set
# CONFIG_NSH_CMDOPT_HEXDUMP is not set
# CONFIG_NSH_CMDPARMS is not set
# CONFIG_NSH_DISABLE_IFCONFIG is not set
# CONFIG_NSH_DISABLE_PS is not set
# CONFIG_SPI_EXCHANGE is not set
CONFIG_ARCH_BOARD_MCB1700=y
CONFIG_ARCH_BOARD="mcb1700"
CONFIG_ARCH_CHIP_LPC1768=y
CONFIG_ARCH_CHIP_LPC17XX=y
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH="arm"
CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT=y
CONFIG_BOARD_LOOPSPERMSEC=7982
CONFIG_DISABLE_POLL=y
CONFIG_EXAMPLES_NSH=y
CONFIG_FS_FAT=y
CONFIG_LPC17_SSP0=y
CONFIG_LPC17_UART0=y
CONFIG_MAX_TASKS=16
CONFIG_MAX_WDOGPARMS=2
CONFIG_MM_REGIONS=2
CONFIG_MMCSD_SPICLOCK=12500000
CONFIG_MMCSD=y
CONFIG_MTD=y
CONFIG_NFILE_DESCRIPTORS=8
CONFIG_NFILE_STREAMS=8
CONFIG_NSH_ARCHINIT=y
CONFIG_NSH_FILEIOSIZE=512
CONFIG_NSH_LINELEN=64
CONFIG_NSH_READLINE=y
CONFIG_PREALLOC_MQ_MSGS=4
CONFIG_PREALLOC_TIMERS=4
CONFIG_PREALLOC_WDOGS=4
CONFIG_RAM_SIZE=32768
CONFIG_RAM_START=0x10000000
CONFIG_RAW_BINARY=y
CONFIG_RR_INTERVAL=200
CONFIG_SDCLONE_DISABLE=y
CONFIG_SPI=y
CONFIG_START_DAY=18
CONFIG_START_MONTH=11
CONFIG_START_YEAR=2017
CONFIG_TASK_NAME_SIZE=0
CONFIG_UART0_SERIAL_CONSOLE=y
CONFIG_USER_ENTRYPOINT="nsh_main"
CONFIG_WDOG_INTRESERVE=0

View File

@ -0,0 +1,111 @@
############################################################################
# configs/mcb1700/scripts/Make.defs
#
# Copyright (C) 2017 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
include ${TOPDIR}/tools/Config.mk
include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs
ifeq ($(WINTOOL),y)
# Windows-native toolchains
DIRLINK = $(TOPDIR)/tools/copydir.sh
DIRUNLINK = $(TOPDIR)/tools/unlink.sh
MKDEP = $(TOPDIR)/tools/mkwindeps.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)/scripts/ld.script}"
else
# Linux/Cygwin-native toolchain
MKDEP = $(TOPDIR)/tools/mkdeps$(HOSTEXEEXT)
ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/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
ARCHCCVERSION = ${shell $(CC) -v 2>&1 | sed -n '/^gcc version/p' | sed -e 's/^gcc version \([0-9\.]\)/\1/g' -e 's/[-\ ].*//g' -e '1q'}
ARCHCCMAJOR = ${shell echo $(ARCHCCVERSION) | cut -d'.' -f1}
ifeq ($(CONFIG_DEBUG_SYMBOLS),y)
ARCHOPTIMIZATION = -g
endif
ifneq ($(CONFIG_DEBUG_NOOPT),y)
ARCHOPTIMIZATION += $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer
endif
ARCHCFLAGS = -fno-builtin
ARCHCXXFLAGS = -fno-builtin -fno-exceptions -fcheck-new
ARCHWARNINGS = -Wall -Wstrict-prototypes -Wshadow -Wundef
ARCHWARNINGSXX = -Wall -Wshadow -Wundef
ARCHDEFINES =
ARCHPICFLAGS = -fpic -msingle-pic-base -mpic-register=r10
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-pcrel.ld -no-check-sections
LDNXFLATFLAGS = -e main -s 2048
ASMEXT = .S
OBJEXT = .o
LIBEXT = .a
EXEEXT =
ifneq ($(CROSSDEV),arm-nuttx-elf-)
LDFLAGS += -nostartfiles -nodefaultlibs
endif
ifeq ($(CONFIG_DEBUG_SYMBOLS),y)
LDFLAGS += -g
endif
HOSTCC = gcc
HOSTINCLUDES = -I.
HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -Wundef -g -pipe
HOSTLDFLAGS =

View File

@ -0,0 +1,115 @@
/****************************************************************************
* configs/mcb1700/scripts/ld.script
*
* Copyright (C) 2017 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.
*
****************************************************************************/
/* The LPC1768 has 512Kb of FLASH beginning at address 0x0000:0000 and
* 64Kb of total SRAM: 32Kb of SRAM in the CPU block beginning at address
* 0x10000000 and 32Kb of AHB SRAM in two banks of 16Kb beginning at addresses
* 0x20070000 and 0x20080000. Here we assume that .data and .bss will all fit
* into the 32Kb CPU SRAM address range.
*/
MEMORY
{
flash (rx) : ORIGIN = 0x00000000, LENGTH = 512K
sram (rwx) : ORIGIN = 0x10000000, LENGTH = 32K
}
OUTPUT_ARCH(arm)
ENTRY(_stext)
SECTIONS
{
.text : {
_stext = ABSOLUTE(.);
*(.vectors)
*(.text .text.*)
*(.fixup)
*(.gnu.warning)
*(.rodata .rodata.*)
*(.gnu.linkonce.t.*)
*(.glue_7)
*(.glue_7t)
*(.got)
*(.gcc_except_table)
*(.gnu.linkonce.r.*)
_etext = ABSOLUTE(.);
} > flash
.init_section : {
_sinit = ABSOLUTE(.);
*(.init_array .init_array.*)
_einit = ABSOLUTE(.);
} > flash
.ARM.extab : {
*(.ARM.extab*)
} > flash
__exidx_start = ABSOLUTE(.);
.ARM.exidx : {
*(.ARM.exidx*)
} > flash
__exidx_end = ABSOLUTE(.);
_eronly = ABSOLUTE(.);
.data : {
_sdata = ABSOLUTE(.);
*(.data .data.*)
*(.gnu.linkonce.d.*)
CONSTRUCTORS
_edata = ABSOLUTE(.);
} > sram AT > flash
.bss : { /* BSS */
_sbss = ABSOLUTE(.);
*(.bss .bss.*)
*(.gnu.linkonce.b.*)
*(COMMON)
_ebss = ABSOLUTE(.);
} > sram
/* 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) }
.debug_abbrev 0 : { *(.debug_abbrev) }
.debug_info 0 : { *(.debug_info) }
.debug_line 0 : { *(.debug_line) }
.debug_pubnames 0 : { *(.debug_pubnames) }
.debug_aranges 0 : { *(.debug_aranges) }
}

2
configs/mcb1700/src/.gitignore vendored Normal file
View File

@ -0,0 +1,2 @@
/.depend
/Make.dep

View File

@ -0,0 +1,57 @@
############################################################################
# configs/mcb1700/src/Makefile
#
# Copyright (C) 2017 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
ASRCS =
CSRCS = lpc17_boot.c lpc17_bringup.c lpc17_leds.c lpc17_dac.c
ifeq ($(CONFIG_LIB_BOARDCTL),y)
CSRCS += lpc17_appinit.c
endif
ifeq ($(CONFIG_USBMSC),y)
CSRCS += lpc17_usbmsc.c
endif
ifeq ($(CONFIG_PWM),y)
CSRCS += lpc17_pwm.c
endif
ifeq ($(CONFIG_ADC),y)
CSRCS += lpc17_adc.c
endif
include $(TOPDIR)/configs/Board.mk

View File

@ -0,0 +1,112 @@
/************************************************************************************
* configs/mcb1700/src/lpc17_adc.c
*
* Based on configs/zkit-arm-176/src/up-adc
*
* Copyright (C) 2013 Zilogic Systems. All rights reserved.
* Author: Kannan <code@nuttx.org>
*
* Based on configs/lpc1720g-eval/src/lpc17_adc.c
*
* Copyright (C) 2012, 2014, 2016-2017 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 <errno.h>
#include <debug.h>
#include <nuttx/board.h>
#include <nuttx/analog/adc.h>
#include <arch/board/board.h>
#include "chip.h"
#include "up_arch.h"
#include "lpc17_adc.h"
#include "mcb1700.h"
#ifdef CONFIG_ADC
/************************************************************************************
* Public Functions
************************************************************************************/
/************************************************************************************
* Name: mcb1700_adc_setup
*
* Description:
* Initialize ADC and register the ADC driver.
*
************************************************************************************/
int mcb1700_adc_setup(void)
{
static bool initialized = false;
struct adc_dev_s *adc;
int ret;
/* Check if we have already initialized */
if (!initialized)
{
/* Call lpc17_adcinitialize() to get an instance of the ADC interface */
adc = lpc17_adcinitialize();
if (adc == NULL)
{
aerr("ERROR: Failed to get ADC interface\n");
return -ENODEV;
}
/* Register the ADC driver at "/dev/adc0" */
ret = adc_register("/dev/adc0", adc);
if (ret < 0)
{
aerr("ERROR: adc_register failed: %d\n", ret);
return ret;
}
/* Now we are initialized */
initialized = true;
}
return OK;
}
#endif /* CONFIG_ADC */

View File

@ -0,0 +1,94 @@
/****************************************************************************
* config/mcb1700/src/lpc17_appinit.c
*
* Copyright (C) 2017 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 <nuttx/board.h>
#include "mcb1700.h"
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
#ifndef OK
# define OK 0
#endif
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: board_app_initialize
*
* Description:
* Perform application specific initialization. This function is never
* called directly from application code, but only indirectly via the
* (non-standard) boardctl() interface using the command BOARDIOC_INIT.
*
* Input Parameters:
* arg - The boardctl() argument is passed to the board_app_initialize()
* implementation without modification. The argument has no
* meaning to NuttX; the meaning of the argument is a contract
* between the board-specific initalization logic and the
* matching application logic. The value cold be such things as a
* mode enumeration value, a set of DIP switch switch settings, a
* pointer to configuration data read from a file or serial FLASH,
* or whatever you would like to do with it. Every implementation
* should accept zero/NULL as a default configuration.
*
* Returned Value:
* Zero (OK) is returned on success; a negated errno value is returned on
* any failure to indicate the nature of the failure.
*
****************************************************************************/
int board_app_initialize(uintptr_t arg)
{
#ifdef CONFIG_BOARD_INITIALIZE
/* Board initialization already performed by board_initialize() */
return OK;
#else
/* Perform board-specific initialization */
return mcb1700_bringup();
#endif
}

View File

@ -0,0 +1,95 @@
/************************************************************************************
* configs/mcb1700/src/lpc17_boot.c
*
* Copyright (C) 2017 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 <nuttx/board.h>
#include <arch/board/board.h>
#include "up_arch.h"
#include "up_internal.h"
#include "mcb1700.h"
/************************************************************************************
* Public Functions
************************************************************************************/
/************************************************************************************
* Name: lpc17_boardinitialize
*
* Description:
* All LPC17xx 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 lpc17_boardinitialize(void)
{
#ifdef CONFIG_ARCH_LEDS
/* Configure on-board LEDs if LED support has been selected. */
board_autoled_initialize();
#endif
}
/****************************************************************************
* Name: board_initialize
*
* Description:
* If CONFIG_BOARD_INITIALIZE is selected, then an additional
* initialization call will be performed in the boot-up sequence to a
* function called board_initialize(). board_initialize() will be
* called immediately after up_initialize() is called and just before the
* initial application is started. This additional initialization phase
* may be used, for example, to initialize board-specific device drivers.
*
****************************************************************************/
#ifdef CONFIG_BOARD_INITIALIZE
void board_initialize(void)
{
/* Perform board-specific initialization */
(void)mcb1700_bringup();
}
#endif

View File

@ -0,0 +1,375 @@
/****************************************************************************
* config/mcb1700/src/lpc17_bringup.c
*
* Copyright (C) 2017 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 <sys/mount.h>
#include <stdio.h>
#include <unistd.h>
#include <syslog.h>
#include <errno.h>
#include <nuttx/board.h>
#include <nuttx/spi/spi.h>
#include <nuttx/mmcsd.h>
#include <nuttx/usb/usbhost.h>
#include "lpc17_ssp.h"
#include "lpc17_gpio.h"
#include "lpc17_usbhost.h"
#include "mcb1700.h"
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/* Configuration ************************************************************/
#define HAVE_MMCSD 1
#define HAVE_USBHOST 1
/* MMC/SD is on SSP port 1. There is only a single slot, slot 0 */
#ifdef CONFIG_NSH_ARCHINIT
# if !defined(CONFIG_NSH_MMCSDSPIPORTNO) || CONFIG_NSH_MMCSDSPIPORTNO != 1
# undef CONFIG_NSH_MMCSDSPIPORTNO
# define CONFIG_NSH_MMCSDSPIPORTNO 1
# endif
# if !defined(CONFIG_NSH_MMCSDSLOTNO) || CONFIG_NSH_MMCSDSLOTNO != 0
# undef CONFIG_NSH_MMCSDSLOTNO
# define CONFIG_NSH_MMCSDSLOTNO 0
# endif
# ifndef CONFIG_NSH_MMCSDMINOR
# define CONFIG_NSH_MMCSDMINOR 0
# endif
#else
# undef CONFIG_NSH_MMCSDSPIPORTNO
# define CONFIG_NSH_MMCSDSPIPORTNO 1
# undef CONFIG_NSH_MMCSDSLOTNO
# define CONFIG_NSH_MMCSDSLOTNO 0
# undef CONFIG_NSH_MMCSDMINOR
# define CONFIG_NSH_MMCSDMINOR 0
#endif
/* Can't support MMC/SD is SSP1 is not enabled */
#ifndef CONFIG_LPC17_SSP1
# undef HAVE_MMCSD
#endif
/* Can't support MMC/SD features if mountpoints are disabled */
#if defined(CONFIG_DISABLE_MOUNTPOINT)
# undef HAVE_MMCSD
#endif
/* USB Host */
#ifdef CONFIG_USBHOST
# ifndef CONFIG_LPC17_USBHOST
# error "CONFIG_LPC17_USBHOST is not selected"
# endif
#endif
#ifdef CONFIG_LPC17_USBHOST
# ifndef CONFIG_USBHOST
# warning "CONFIG_USBHOST is not selected"
# endif
#endif
#if !defined(CONFIG_USBHOST) || !defined(CONFIG_LPC17_USBHOST)
# undef HAVE_USBHOST
#endif
#ifdef HAVE_USBHOST
# ifndef CONFIG_MCB1700_USBHOST_PRIO
# define CONFIG_MCB1700_USBHOST_PRIO 50
# endif
# ifndef CONFIG_MCB1700_USBHOST_STACKSIZE
# define CONFIG_MCB1700_USBHOST_STACKSIZE 1024
# endif
#endif
/****************************************************************************
* Private Data
****************************************************************************/
#ifdef HAVE_USBHOST
static struct usbhost_connection_s *g_usbconn;
#endif
/****************************************************************************
* Private Functions
****************************************************************************/
/****************************************************************************
* Name: nsh_waiter
*
* Description:
* Wait for USB devices to be connected.
*
****************************************************************************/
#ifdef HAVE_USBHOST
static int nsh_waiter(int argc, char *argv[])
{
struct usbhost_hubport_s *hport;
syslog(LOG_INFO, "nsh_waiter: Running\n");
for (;;)
{
/* Wait for the device to change state */
DEBUGVERIFY(CONN_WAIT(g_usbconn, &hport));
syslog(LOG_INFO, "nsh_waiter: %s\n", hport->connected ? "connected" : "disconnected");
/* Did we just become connected? */
if (hport->connected)
{
/* Yes.. enumerate the newly connected device */
(void)CONN_ENUMERATE(g_usbconn, hport);
}
}
/* Keep the compiler from complaining */
return 0;
}
#endif
/****************************************************************************
* Name: nsh_sdinitialize
*
* Description:
* Initialize SPI-based microSD.
*
****************************************************************************/
#ifdef HAVE_MMCSD
static int nsh_sdinitialize(void)
{
FAR struct spi_dev_s *ssp;
int ret;
/* Enable power to the SD/MMC via a GPIO. LOW enables SD/MMC. */
lpc17_gpiowrite(MCB1700_MMC_PWR, false);
/* Get the SSP port. MMC/SD is on SSP port 1. */
ssp = lpc17_sspbus_initialize(CONFIG_NSH_MMCSDSPIPORTNO);
if (!ssp)
{
syslog(LOG_ERR, "ERROR: Failed to initialize SSP port %d\n",
CONFIG_NSH_MMCSDSPIPORTNO);
ret = -ENODEV;
goto errout;
}
syslog(LOG_INFO, "Successfully initialized SSP port %d\n",
CONFIG_NSH_MMCSDSPIPORTNO);
/* Bind the SSP port to the slot */
ret = mmcsd_spislotinitialize(CONFIG_NSH_MMCSDMINOR,
CONFIG_NSH_MMCSDSLOTNO, ssp);
if (ret < 0)
{
syslog(LOG_ERR,
"ERROR: Failed to bind SSP port %d to MMC/SD slot %d: %d\n",
CONFIG_NSH_MMCSDSPIPORTNO,
CONFIG_NSH_MMCSDSLOTNO, ret);
goto errout;
}
syslog(LOG_INFO, "Successfully bound SSP port %d to MMC/SD slot %d\n",
CONFIG_NSH_MMCSDSPIPORTNO,
CONFIG_NSH_MMCSDSLOTNO);
return OK;
/* Disable power to the SD/MMC via a GPIO. HIGH disables SD/MMC. */
errout:
lpc17_gpiowrite(MCB1700_MMC_PWR, true);
return ret;
}
#else
# define nsh_sdinitialize() (OK)
#endif
/****************************************************************************
* Name: nsh_usbhostinitialize
*
* Description:
* Initialize SPI-based microSD.
*
****************************************************************************/
#ifdef HAVE_USBHOST
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:
*/
syslog(LOG_INFO, "Register class drivers\n");
#ifdef CONFIG_USBHOST_HUB
/* Initialize USB hub support */
ret = usbhost_hub_initialize();
if (ret < 0)
{
syslog(LOG_ERR, "ERROR: usbhost_hub_initialize failed: %d\n", ret);
}
#endif
#ifdef CONFIG_USBHOST_MSC
/* Initialize mass storage support */
ret = usbhost_msc_initialize();
if (ret != OK)
{
syslog(LOG_ERR, "ERROR: Failed to register the mass storage class: %d\n", ret);
}
#endif
#ifdef CONFIG_USBHOST_CDCACM
/* Register the CDC/ACM serial class */
ret = usbhost_cdcacm_initialize();
if (ret != OK)
{
syslog(LOG_ERR, "ERROR: Failed to register the CDC/ACM serial class: %d\n", ret);
}
#endif
UNUSED(ret);
/* Then get an instance of the USB host interface */
syslog(LOG_INFO, "Initialize USB host\n");
g_usbconn = lpc17_usbhost_initialize(0);
if (g_usbconn)
{
/* Start a thread to handle device connection. */
syslog(LOG_ERR, "ERROR: Start nsh_waiter\n");
pid = task_create("usbhost", CONFIG_MCB1700_USBHOST_PRIO,
CONFIG_MCB1700_USBHOST_STACKSIZE,
(main_t)nsh_waiter, (FAR char * const *)NULL);
return pid < 0 ? -ENOEXEC : OK;
}
return -ENODEV;
}
#else
# define nsh_usbhostinitialize() (OK)
#endif
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: mcb1700_bringup
*
* Description:
* Perform architecture-specific initialization
*
* CONFIG_BOARD_INITIALIZE=y :
* Called from board_initialize().
*
* CONFIG_BOARD_INITIALIZE=y && CONFIG_LIB_BOARDCTL=y :
* Called from the NSH library
*
****************************************************************************/
int mcb1700_bringup(void)
{
int ret;
/* Initialize SPI-based microSD */
ret = nsh_sdinitialize();
if (ret < 0)
{
syslog(LOG_ERR, "ERROR: Failed to initialize SPI-based SD card: %d\n", ret);
}
/* Initialize USB host */
ret = nsh_usbhostinitialize();
if (ret < 0)
{
syslog(LOG_ERR, "ERROR: Failed to initialize USB host: %d\n", ret);
}
#ifdef CONFIG_CAN
/* Initialize CAN and register the CAN driver. */
ret = lpc1766stk_can_setup();
if (ret < 0)
{
syslog(LOG_ERR, "ERROR: lpc1766stk_can_setup failed: %d\n", ret);
}
#endif
#ifdef CONFIG_FS_PROCFS
/* Mount the procfs file system */
ret = mount(NULL, "/proc", "procfs", 0, NULL);
if (ret < 0)
{
syslog(LOG_ERR, "ERROR: Failed to mount procfs at /proc: %d\n", ret);
}
#endif
return ret;
}

View File

@ -0,0 +1,101 @@
/************************************************************************************
* configs/mcb1700/src/lpc17_dac.c
*
* Based on configs/zkit-arm-1769/src/lpc17_dac.c
*
* Copyright (C) 2013 Zilogic Systems. All rights reserved.
* Author: Kannan <code@nuttx.org>
*
* Based on configs/stm3220g-eval/src/stm32_dac.c
*
* Copyright (C) 2012, 2014, 2017 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 <errno.h>
#include <debug.h>
#include <nuttx/analog/dac.h>
#include <arch/board/board.h>
#include "up_arch.h"
#include "up_internal.h"
#include "lpc17_dac.h"
#ifdef CONFIG_DAC
/************************************************************************************
* Name: dac_devinit
*
* Description:
* All LPC17xx architectures must provide the following interface to work with
* examples/diag.
*
************************************************************************************/
int dac_devinit(void)
{
static bool initialized = false;
struct dac_dev_s *dac;
int ret;
if (!initialized)
{
/* Call lpc17_dacinitialize() to get an instance of the dac interface */
dac = lpc17_dacinitialize();
if (dac == NULL)
{
aerr("ERROR: Failed to get dac interface\n");
return -ENODEV;
}
ret = dac_register("/dev/dac0", dac);
if (ret < 0)
{
aerr("ERROR: dac_register failed: %d\n", ret);
return ret;
}
initialized = true;
}
return OK;
}
#endif /* CONFIG_DAC */

View File

@ -0,0 +1,200 @@
/****************************************************************************
* configs/mcb1700/src/lpc17_leds.c
*
* Copyright (C) 2017 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/board.h>
#include <arch/board/board.h>
#include "chip.h"
#include "up_arch.h"
#include "up_internal.h"
#include "lpc17_gpio.h"
#include "mcb1700.h"
#ifdef CONFIG_ARCH_LEDS
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/* Dump GPIO registers */
#ifdef CONFIG_DEBUG_LEDS_INFO
# define led_dumpgpio(m) lpc17_dumpgpio(MCB1700_LED3, m)
#else
# define led_dumpgpio(m)
#endif
/****************************************************************************
* Private Data
****************************************************************************/
/* LED definitions **********************************************************/
/* The MCB1700 has 4 LEDs along the bottom of the board. Blue or off.
* If CONFIG_ARCH_LEDS is defined, the LEDs will be controlled as follows
* for NuttX debug functionality (where NC means "No Change").
*
* During the boot phases. LED1 and LED2 will show boot status. LED3/4 Not
* used.
*
* LED1 LED2
* STARTED OFF OFF
* HEAPALLOCATE BLUE OFF
* IRQSENABLED OFF BLUE
* STACKCREATED OFF OFF
*
* After the system is booted, this logic will no longer use LEDs 1 & 2.
* They are available together with LED3 for use the application software
* using lpc17_led (prototyped below)
*/
static bool g_initialized;
static int g_nestcount;
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: board_autoled_initialize
****************************************************************************/
void board_autoled_initialize(void)
{
/* Configure all LED GPIO lines */
led_dumpgpio("board_autoled_initialize() Entry)");
lpc17_configgpio(MCB1700_LED1);
lpc17_configgpio(MCB1700_LED2);
lpc17_configgpio(MCB1700_LED3);
lpc17_configgpio(MCB1700_LED4);
led_dumpgpio("board_autoled_initialize() Exit");
}
/****************************************************************************
* Name: board_autoled_on
****************************************************************************/
void board_autoled_on(int led)
{
/* We will control LED1 and LED2 not yet completed the boot sequence. */
if (!g_initialized)
{
int led1 = 0;
int led2 = 0;
switch (led)
{
case LED_STACKCREATED:
g_initialized = true;
case LED_STARTED:
default:
break;
case LED_HEAPALLOCATE:
led1 = 1;
break;
case LED_IRQSENABLED:
led2 = 1;
}
lpc17_led(MCB1700_LED1,led1);
lpc17_led(MCB1700_LED2,led2);
}
/* We will always control the HB LED */
switch (led)
{
case LED_INIRQ:
case LED_SIGNAL:
case LED_ASSERTION:
case LED_PANIC:
lpc17_gpiowrite(MCB1700_HEARTBEAT, false);
g_nestcount++;
default:
break;
}
}
/****************************************************************************
* Name: board_autoled_off
****************************************************************************/
void board_autoled_off(int led)
{
/* In all states, OFF can only mean turning off the HB LED */
if (g_nestcount <= 1)
{
lpc17_led(MCB1700_HEARTBEAT, true);
g_nestcount = 0;
}
else
{
g_nestcount--;
}
}
/************************************************************************************
* Name: lpc17_led
*
* Description:
* Once the system has booted, these functions can be used to control the LEDs
*
************************************************************************************/
void lpc17_led(int lednum, int state)
{
lpc17_gpiowrite(lednum, state);
}
#endif /* CONFIG_ARCH_LEDS */

View File

@ -0,0 +1,151 @@
/************************************************************************************
* configs/mcb1700/lpc17_pwm.c
*
* Based on configs/lpcexpresso-lpc1768/lpc17_pwm.c
*
* Copyright (C) 2014-2017 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 <sys/types.h>
#include <errno.h>
#include <debug.h>
#include <nuttx/board.h>
#include <nuttx/drivers/pwm.h>
#include <arch/board/board.h>
#include "chip.h"
#include "up_arch.h"
#include "lpc17_pwm.h"
#include "lpc17_timer.h"
#include "mcb1700.h"
/************************************************************************************
* Pre-processor Definitions
************************************************************************************/
#ifdef CONFIG_PWM
FAR struct pwm_lowerhalf_s *lpc17_pwminitialize(int timer);
FAR struct pwm_lowerhalf_s *lpc17_mcpwminitialize(int timer);
FAR struct pwm_lowerhalf_s *lpc17_timerinitialize(int timer);
/************************************************************************************
* Public Functions
************************************************************************************/
/************************************************************************************
* Name: mcb1700_pwm_setup
*
* Description:
* Initialize PWM and register the PWM device.
*
************************************************************************************/
int mcb1700_pwm_setup(void)
{
static bool initialized = false;
struct pwm_lowerhalf_s *pwm;
struct pwm_lowerhalf_s *mcpwm;
struct pwm_lowerhalf_s *timer;
int ret;
/* Have we already initialized? */
if (!initialized)
{
/* Call lpc17_pwminitialize() to get an instance of the PWM interface */
pwm = lpc17_pwminitialize(0);
if (!pwm)
{
aerr("ERROR: Failed to get the LPC17XX PWM lower half\n");
return -ENODEV;
}
/* Register the PWM driver at "/dev/pwm0" */
ret = pwm_register("/dev/pwm0", pwm);
if (ret < 0)
{
aerr("ERROR: pwm_register failed: %d\n", ret);
return ret;
}
mcpwm = lpc17_mcpwminitialize(0);
if (!mcpwm)
{
aerr("ERROR: Failed to get the LPC17XX MOTOR PWM lower half\n");
return -ENODEV;
}
/* Register the MOTOR CONTROL PWM driver at "/dev/mcpwm0" */
ret = pwm_register("/dev/mcpwm0", mcpwm);
if (ret < 0)
{
aerr("ERROR: mcpwm_register failed: %d\n", ret);
return ret;
}
timer = lpc17_timerinitialize(0);
if (!timer)
{
aerr("ERROR: Failed to get the LPC17XX TIMER lower half\n");
return -ENODEV;
}
/* Register the PWM driver at "/dev/timer0" */
ret = pwm_register("/dev/timer0", timer);
if (ret < 0)
{
aerr("ERROR: timer_register failed: %d\n", ret);
return ret;
}
/* Now we are initialized */
initialized = true;
}
return OK;
}
#endif /* CONFIG_PWM */

View File

@ -0,0 +1,125 @@
/************************************************************************************
* configs/mcb1700/src/mcb1700.h
*
* Copyright (C) 2017 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_MCB1700_SRC_MCB1700_H
#define _CONFIGS_MCB1700_SRC_MCB1700_H
/************************************************************************************
* Included Files
************************************************************************************/
#include <nuttx/config.h>
#include <nuttx/compiler.h>
/************************************************************************************
* Pre-processor Definitions
************************************************************************************/
/* MCB1700 GPIO Pin Definitions *****************************************************/
#define MCB1700_LED1 (GPIO_OUTPUT | GPIO_PORT1 | GPIO_PIN18)
#define MCB1700_LED1_OFF MCB1700_LED1
#define MCB1700_LED1_ON (MCB1700_LED1 | GPIO_VALUE_ONE)
#define MCB1700_LED2 (GPIO_OUTPUT | GPIO_PORT1 | GPIO_PIN20)
#define MCB1700_LED2_OFF MCB1700_LED2
#define MCB1700_LED2_ON (MCB1700_LED2 | GPIO_VALUE_ONE)
#define MCB1700_LED3 (GPIO_OUTPUT | GPIO_PORT1 | GPIO_PIN21)
#define MCB1700_LED3_OFF MCB1700_LED3
#define MCB1700_LED3_ON (MCB1700_LED3 | GPIO_VALUE_ONE)
#define MCB1700_LED4 (GPIO_OUTPUT | GPIO_PORT1 | GPIO_PIN23)
#define MCB1700_LED4_OFF MCB1700_LED4
#define MCB1700_LED4_ON (MCB1700_LED 4| GPIO_VALUE_ONE)
#define MCB1700_HEARTBEAT MCB1700_LED4
#ifndef __ASSEMBLY__
/************************************************************************************
* Public Function Prototypes
************************************************************************************/
/****************************************************************************
* Name: mcb1700_bringup
*
* Description:
* Perform architecture-specific initialization
*
* CONFIG_BOARD_INITIALIZE=y :
* Called from board_initialize().
*
* CONFIG_BOARD_INITIALIZE=y && CONFIG_LIB_BOARDCTL=y :
* Called from the NSH library
*
****************************************************************************/
int mcb1700_bringup(void);
/************************************************************************************
* Name: mcb1700_sspdev_initialize
*
* Description:
* Called to configure SPI chip select GPIO pins for the NUCLEUS-2G board.
*
************************************************************************************/
void weak_function mcb1700_sspdev_initialize(void);
/************************************************************************************
* Name: mcb1700_pwm_setup
*
* Description:
* Initialize PWM and register the PWM device.
*
************************************************************************************/
#ifdef CONFIG_PWM
int mcb1700_pwm_setup(void);
#endif
/************************************************************************************
* Name: mcb1700_adc_setup
*
* Description:
* Initialize ADC and register the ADC driver.
*
************************************************************************************/
#ifdef CONFIG_ADC
int mcb1700_adc_setup(void);
#endif
#endif /* __ASSEMBLY__ */
#endif /* _CONFIGS_MCB1700_SRC_MCB1700_H */