summaryrefslogtreecommitdiff
path: root/nuttx
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-12-23 00:58:00 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-12-23 00:58:00 +0000
commit617ec57ee062782a59650a5c5cf8cba44c53adc7 (patch)
tree9663e36a6f697ca1389310e5495796f8d3f78f55 /nuttx
parentbdb6f93e9da4768ba60375f8ff89d0ed124e19bd (diff)
downloadpx4-nuttx-617ec57ee062782a59650a5c5cf8cba44c53adc7.tar.gz
px4-nuttx-617ec57ee062782a59650a5c5cf8cba44c53adc7.tar.bz2
px4-nuttx-617ec57ee062782a59650a5c5cf8cba44c53adc7.zip
PIC32 NSH configuration now builds without errors
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@4220 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx')
-rw-r--r--nuttx/arch/mips/src/pic32mx/pic32mx-lowinit.c2
-rw-r--r--nuttx/arch/mips/src/pic32mx/pic32mx-serial.c89
-rw-r--r--nuttx/configs/sure-pic32mx/nsh/defconfig2
-rw-r--r--nuttx/drivers/mtd/m25px.c3
-rw-r--r--nuttx/fs/fat/fs_fat32.h4
5 files changed, 51 insertions, 49 deletions
diff --git a/nuttx/arch/mips/src/pic32mx/pic32mx-lowinit.c b/nuttx/arch/mips/src/pic32mx/pic32mx-lowinit.c
index ad2b8bf1f..44fcaaa2a 100644
--- a/nuttx/arch/mips/src/pic32mx/pic32mx-lowinit.c
+++ b/nuttx/arch/mips/src/pic32mx/pic32mx-lowinit.c
@@ -2,7 +2,7 @@
* arch/mips/src/pic32/pic32mx-lowinit.c
*
* 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
* modification, are permitted provided that the following conditions
diff --git a/nuttx/arch/mips/src/pic32mx/pic32mx-serial.c b/nuttx/arch/mips/src/pic32mx/pic32mx-serial.c
index 9644e09f8..eace41bcb 100644
--- a/nuttx/arch/mips/src/pic32mx/pic32mx-serial.c
+++ b/nuttx/arch/mips/src/pic32mx/pic32mx-serial.c
@@ -2,7 +2,7 @@
* arch/mips/src/pic32mx/pic32mx-serial.c
*
* 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
* 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 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_disableuartint(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 uart_dev_s *dev, uint8_t *im);
/* Serial driver methods */
@@ -215,32 +215,32 @@ static char g_uart2txbuffer[CONFIG_UART2_TXBUFSIZE];
#ifdef CONFIG_PIC32MX_UART1
static struct up_dev_s g_uart1priv =
{
- .uartbase = PIC32MX_UART1_K1BASE,
- .baud = CONFIG_UART1_BAUD,
- .irq = PIC32MX_IRQ_U1,
- .irqe = PIC32MX_IRQSRC_U1E,
- .irqrx = PIC32MX_IRQSRC_U1RX,
- .irqtx = PIC32MX_IRQSRC_U1TX,
- .irqprio = CONFIG_PIC32MX_UART1PRIO,
- .parity = CONFIG_UART1_PARITY,
- .bits = CONFIG_UART1_BITS,
- .stopbits2 = CONFIG_UART1_2STOP,
+ .uartbase = PIC32MX_UART1_K1BASE,
+ .baud = CONFIG_UART1_BAUD,
+ .irq = PIC32MX_IRQ_U1,
+ .irqe = PIC32MX_IRQSRC_U1E,
+ .irqrx = PIC32MX_IRQSRC_U1RX,
+ .irqtx = PIC32MX_IRQSRC_U1TX,
+ .irqprio = CONFIG_PIC32MX_UART1PRIO,
+ .parity = CONFIG_UART1_PARITY,
+ .bits = CONFIG_UART1_BITS,
+ .stopbits2 = CONFIG_UART1_2STOP,
};
static uart_dev_t g_uart1port =
{
- .recv =
+ .recv =
{
- .size = CONFIG_UART1_RXBUFSIZE,
- .buffer = g_uart1rxbuffer,
+ .size = CONFIG_UART1_RXBUFSIZE,
+ .buffer = g_uart1rxbuffer,
},
- .xmit =
+ .xmit =
{
- .size = CONFIG_UART1_TXBUFSIZE,
- .buffer = g_uart1txbuffer,
+ .size = CONFIG_UART1_TXBUFSIZE,
+ .buffer = g_uart1txbuffer,
},
- .ops = &g_uart_ops,
- .priv = &g_uart1priv,
+ .ops = &g_uart_ops,
+ .priv = &g_uart1priv,
};
#endif
@@ -249,32 +249,32 @@ static uart_dev_t g_uart1port =
#ifdef CONFIG_PIC32MX_UART2
static struct up_dev_s g_uart2priv =
{
- .uartbase = PIC32MX_UART2_K1BASE,
- .baud = CONFIG_UART2_BAUD,
- .irq = PIC32MX_IRQ_U2,
- .irqe = PIC32MX_IRQSRC_U2E,
- .irqrx = PIC32MX_IRQSRC_U2RX,
- .irqtx = PIC32MX_IRQSRC_U2TX,
- .irqprio = CONFIG_PIC32MX_UART2PRIO,
- .parity = CONFIG_UART2_PARITY,
- .bits = CONFIG_UART2_BITS,
- .stopbits2 = CONFIG_UART2_2STOP,
+ .uartbase = PIC32MX_UART2_K1BASE,
+ .baud = CONFIG_UART2_BAUD,
+ .irq = PIC32MX_IRQ_U2,
+ .irqe = PIC32MX_IRQSRC_U2E,
+ .irqrx = PIC32MX_IRQSRC_U2RX,
+ .irqtx = PIC32MX_IRQSRC_U2TX,
+ .irqprio = CONFIG_PIC32MX_UART2PRIO,
+ .parity = CONFIG_UART2_PARITY,
+ .bits = CONFIG_UART2_BITS,
+ .stopbits2 = CONFIG_UART2_2STOP,
};
static uart_dev_t g_uart2port =
{
- .recv =
+ .recv =
{
- .size = CONFIG_UART2_RXBUFSIZE,
- .buffer = g_uart2rxbuffer,
+ .size = CONFIG_UART2_RXBUFSIZE,
+ .buffer = g_uart2rxbuffer,
},
- .xmit =
+ .xmit =
{
- .size = CONFIG_UART2_TXBUFSIZE,
- .buffer = g_uart2txbuffer,
+ .size = CONFIG_UART2_TXBUFSIZE,
+ .buffer = g_uart2txbuffer,
},
- .ops = &g_uart_ops,
- .priv = &g_uart2priv,
+ .ops = &g_uart_ops,
+ .priv = &g_uart2priv,
};
#endif
@@ -320,8 +320,9 @@ static void up_restoreuartint(struct uart_dev_s *dev, uint8_t im)
* 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;
flags = irqsave();
@@ -761,12 +762,12 @@ static bool up_txempty(struct uart_dev_s *dev)
void up_earlyserialinit(void)
{
/* 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
- up_disableuartint(TTYS1_DEV, NULL);
+ up_disableuartint(&TTYS1_DEV, NULL);
#endif
/* Configuration whichever one is the console */
@@ -814,7 +815,7 @@ int up_putc(int ch)
{
#ifdef HAVE_SERIAL_CONSOLE
struct uart_dev_s *dev = (struct uart_dev_s *)&CONSOLE_DEV;
- uint32_t imr;
+ uint8_t imr;
up_disableuartint(dev, &imr);
diff --git a/nuttx/configs/sure-pic32mx/nsh/defconfig b/nuttx/configs/sure-pic32mx/nsh/defconfig
index 74b56dda8..70d4017cf 100644
--- a/nuttx/configs/sure-pic32mx/nsh/defconfig
+++ b/nuttx/configs/sure-pic32mx/nsh/defconfig
@@ -328,7 +328,7 @@ CONFIG_DEBUG=n
CONFIG_DEBUG_VERBOSE=n
CONFIG_DEBUG_SYMBOLS=n
CONFIG_DEBUG_SCHED=n
-CONFIG_HAVE_CXX=y
+CONFIG_HAVE_CXX=n
CONFIG_MM_REGIONS=1
CONFIG_ARCH_LOWPUTC=y
CONFIG_RR_INTERVAL=0
diff --git a/nuttx/drivers/mtd/m25px.c b/nuttx/drivers/mtd/m25px.c
index 6fc613d7c..3c4229b95 100644
--- a/nuttx/drivers/mtd/m25px.c
+++ b/nuttx/drivers/mtd/m25px.c
@@ -3,7 +3,7 @@
* Driver for SPI-based M25P1 (128Kbit), M25P64 (64Mbit), and M25P128 (128Mbit) FLASH
*
* 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
* modification, are permitted provided that the following conditions
@@ -44,6 +44,7 @@
#include <stdint.h>
#include <stdbool.h>
#include <stdlib.h>
+#include <unistd.h>
#include <errno.h>
#include <debug.h>
diff --git a/nuttx/fs/fat/fs_fat32.h b/nuttx/fs/fat/fs_fat32.h
index 536e8fd7e..dfdc6bef2 100644
--- a/nuttx/fs/fat/fs_fat32.h
+++ b/nuttx/fs/fat/fs_fat32.h
@@ -2,7 +2,7 @@
* fs/fat/fs_fat32.h
*
* 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
* 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 */
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 */