PIC32 NSH configuration now builds without errors

git-svn-id: https://nuttx.svn.sourceforge.net/svnroot/nuttx/trunk@4220 7fd9a85b-ad96-42d3-883c-3090e2eb8679
This commit is contained in:
patacongo 2011-12-23 00:58:00 +00:00
parent 5464c1d5ed
commit f1ee90fa13
5 changed files with 51 additions and 49 deletions

View File

@ -2,7 +2,7 @@
* arch/mips/src/pic32/pic32mx-lowinit.c * arch/mips/src/pic32/pic32mx-lowinit.c
* *
* Copyright (C) 2011 Gregory Nutt. All rights reserved. * Copyright (C) 2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr> * Author: Gregory Nutt <gnutt@nuttx.org>
* *
* Redistribution and use in source and binary forms, with or without * Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions * modification, are permitted provided that the following conditions

View File

@ -2,7 +2,7 @@
* arch/mips/src/pic32mx/pic32mx-serial.c * arch/mips/src/pic32mx/pic32mx-serial.c
* *
* Copyright (C) 2011 Gregory Nutt. All rights reserved. * Copyright (C) 2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr> * Author: Gregory Nutt <gnutt@nuttx.org>
* *
* Redistribution and use in source and binary forms, with or without * Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions * modification, are permitted provided that the following conditions
@ -160,8 +160,8 @@ struct up_dev_s
static inline uint32_t up_serialin(struct up_dev_s *priv, int offset); static inline uint32_t up_serialin(struct up_dev_s *priv, int offset);
static inline void up_serialout(struct up_dev_s *priv, int offset, uint32_t value); static inline void up_serialout(struct up_dev_s *priv, int offset, uint32_t value);
static void up_restoreuartint(struct up_dev_s *priv, uint8_t im); static void up_restoreuartint(struct uart_dev_s *dev, uint8_t im);
static void up_disableuartint(struct up_dev_s *priv, uint8_t *im); static void up_disableuartint(struct uart_dev_s *dev, uint8_t *im);
/* Serial driver methods */ /* Serial driver methods */
@ -215,32 +215,32 @@ static char g_uart2txbuffer[CONFIG_UART2_TXBUFSIZE];
#ifdef CONFIG_PIC32MX_UART1 #ifdef CONFIG_PIC32MX_UART1
static struct up_dev_s g_uart1priv = static struct up_dev_s g_uart1priv =
{ {
.uartbase = PIC32MX_UART1_K1BASE, .uartbase = PIC32MX_UART1_K1BASE,
.baud = CONFIG_UART1_BAUD, .baud = CONFIG_UART1_BAUD,
.irq = PIC32MX_IRQ_U1, .irq = PIC32MX_IRQ_U1,
.irqe = PIC32MX_IRQSRC_U1E, .irqe = PIC32MX_IRQSRC_U1E,
.irqrx = PIC32MX_IRQSRC_U1RX, .irqrx = PIC32MX_IRQSRC_U1RX,
.irqtx = PIC32MX_IRQSRC_U1TX, .irqtx = PIC32MX_IRQSRC_U1TX,
.irqprio = CONFIG_PIC32MX_UART1PRIO, .irqprio = CONFIG_PIC32MX_UART1PRIO,
.parity = CONFIG_UART1_PARITY, .parity = CONFIG_UART1_PARITY,
.bits = CONFIG_UART1_BITS, .bits = CONFIG_UART1_BITS,
.stopbits2 = CONFIG_UART1_2STOP, .stopbits2 = CONFIG_UART1_2STOP,
}; };
static uart_dev_t g_uart1port = static uart_dev_t g_uart1port =
{ {
.recv = .recv =
{ {
.size = CONFIG_UART1_RXBUFSIZE, .size = CONFIG_UART1_RXBUFSIZE,
.buffer = g_uart1rxbuffer, .buffer = g_uart1rxbuffer,
}, },
.xmit = .xmit =
{ {
.size = CONFIG_UART1_TXBUFSIZE, .size = CONFIG_UART1_TXBUFSIZE,
.buffer = g_uart1txbuffer, .buffer = g_uart1txbuffer,
}, },
.ops = &g_uart_ops, .ops = &g_uart_ops,
.priv = &g_uart1priv, .priv = &g_uart1priv,
}; };
#endif #endif
@ -249,32 +249,32 @@ static uart_dev_t g_uart1port =
#ifdef CONFIG_PIC32MX_UART2 #ifdef CONFIG_PIC32MX_UART2
static struct up_dev_s g_uart2priv = static struct up_dev_s g_uart2priv =
{ {
.uartbase = PIC32MX_UART2_K1BASE, .uartbase = PIC32MX_UART2_K1BASE,
.baud = CONFIG_UART2_BAUD, .baud = CONFIG_UART2_BAUD,
.irq = PIC32MX_IRQ_U2, .irq = PIC32MX_IRQ_U2,
.irqe = PIC32MX_IRQSRC_U2E, .irqe = PIC32MX_IRQSRC_U2E,
.irqrx = PIC32MX_IRQSRC_U2RX, .irqrx = PIC32MX_IRQSRC_U2RX,
.irqtx = PIC32MX_IRQSRC_U2TX, .irqtx = PIC32MX_IRQSRC_U2TX,
.irqprio = CONFIG_PIC32MX_UART2PRIO, .irqprio = CONFIG_PIC32MX_UART2PRIO,
.parity = CONFIG_UART2_PARITY, .parity = CONFIG_UART2_PARITY,
.bits = CONFIG_UART2_BITS, .bits = CONFIG_UART2_BITS,
.stopbits2 = CONFIG_UART2_2STOP, .stopbits2 = CONFIG_UART2_2STOP,
}; };
static uart_dev_t g_uart2port = static uart_dev_t g_uart2port =
{ {
.recv = .recv =
{ {
.size = CONFIG_UART2_RXBUFSIZE, .size = CONFIG_UART2_RXBUFSIZE,
.buffer = g_uart2rxbuffer, .buffer = g_uart2rxbuffer,
}, },
.xmit = .xmit =
{ {
.size = CONFIG_UART2_TXBUFSIZE, .size = CONFIG_UART2_TXBUFSIZE,
.buffer = g_uart2txbuffer, .buffer = g_uart2txbuffer,
}, },
.ops = &g_uart_ops, .ops = &g_uart_ops,
.priv = &g_uart2priv, .priv = &g_uart2priv,
}; };
#endif #endif
@ -320,8 +320,9 @@ static void up_restoreuartint(struct uart_dev_s *dev, uint8_t im)
* Name: up_disableuartint * Name: up_disableuartint
****************************************************************************/ ****************************************************************************/
static void up_disableuartint(sstruct uart_dev_s *dev, uint8_t *im) static void up_disableuartint(struct uart_dev_s *dev, uint8_t *im)
{ {
struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
irqstate_t flags; irqstate_t flags;
flags = irqsave(); flags = irqsave();
@ -761,12 +762,12 @@ static bool up_txempty(struct uart_dev_s *dev)
void up_earlyserialinit(void) void up_earlyserialinit(void)
{ {
/* Disable interrupts from all UARTS. The console is enabled in /* Disable interrupts from all UARTS. The console is enabled in
* pic32mx_consoleinit() * pic32mx_consoleinit().
*/ */
up_disableuartint(TTYS0_DEV, NULL); up_disableuartint(&TTYS0_DEV, NULL);
#ifdef TTYS1_DEV #ifdef TTYS1_DEV
up_disableuartint(TTYS1_DEV, NULL); up_disableuartint(&TTYS1_DEV, NULL);
#endif #endif
/* Configuration whichever one is the console */ /* Configuration whichever one is the console */
@ -814,7 +815,7 @@ int up_putc(int ch)
{ {
#ifdef HAVE_SERIAL_CONSOLE #ifdef HAVE_SERIAL_CONSOLE
struct uart_dev_s *dev = (struct uart_dev_s *)&CONSOLE_DEV; struct uart_dev_s *dev = (struct uart_dev_s *)&CONSOLE_DEV;
uint32_t imr; uint8_t imr;
up_disableuartint(dev, &imr); up_disableuartint(dev, &imr);

View File

@ -328,7 +328,7 @@ CONFIG_DEBUG=n
CONFIG_DEBUG_VERBOSE=n CONFIG_DEBUG_VERBOSE=n
CONFIG_DEBUG_SYMBOLS=n CONFIG_DEBUG_SYMBOLS=n
CONFIG_DEBUG_SCHED=n CONFIG_DEBUG_SCHED=n
CONFIG_HAVE_CXX=y CONFIG_HAVE_CXX=n
CONFIG_MM_REGIONS=1 CONFIG_MM_REGIONS=1
CONFIG_ARCH_LOWPUTC=y CONFIG_ARCH_LOWPUTC=y
CONFIG_RR_INTERVAL=0 CONFIG_RR_INTERVAL=0

View File

@ -3,7 +3,7 @@
* Driver for SPI-based M25P1 (128Kbit), M25P64 (64Mbit), and M25P128 (128Mbit) FLASH * Driver for SPI-based M25P1 (128Kbit), M25P64 (64Mbit), and M25P128 (128Mbit) FLASH
* *
* Copyright (C) 2009-2011 Gregory Nutt. All rights reserved. * Copyright (C) 2009-2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr> * Author: Gregory Nutt <gnutt@nuttx.org>
* *
* Redistribution and use in source and binary forms, with or without * Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions * modification, are permitted provided that the following conditions
@ -44,6 +44,7 @@
#include <stdint.h> #include <stdint.h>
#include <stdbool.h> #include <stdbool.h>
#include <stdlib.h> #include <stdlib.h>
#include <unistd.h>
#include <errno.h> #include <errno.h>
#include <debug.h> #include <debug.h>

View File

@ -2,7 +2,7 @@
* fs/fat/fs_fat32.h * fs/fat/fs_fat32.h
* *
* Copyright (C) 2007-2009, 2011 Gregory Nutt. All rights reserved. * Copyright (C) 2007-2009, 2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr> * Author: Gregory Nutt <gnutt@nuttx.org>
* *
* Redistribution and use in source and binary forms, with or without * Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions * modification, are permitted provided that the following conditions
@ -845,7 +845,7 @@ EXTERN void fat_semgive(struct fat_mountpt_s *fs);
/* Get the current time for FAT creation and write times */ /* Get the current time for FAT creation and write times */
EXTERN uint32_t fat_systime2fattime(void); EXTERN uint32_t fat_systime2fattime(void);
EXTERN time_t fat_fattime2systime(uint16_t time, uint16_t date); EXTERN time_t fat_fattime2systime(uint16_t fattime, uint16_t fatdate);
/* Handle hardware interactions for mounting */ /* Handle hardware interactions for mounting */