summaryrefslogtreecommitdiff
path: root/nuttx
diff options
context:
space:
mode:
Diffstat (limited to 'nuttx')
-rw-r--r--nuttx/arch/pjrc-8051/include/types.h15
-rw-r--r--nuttx/arch/sh/include/m16c/types.h4
-rw-r--r--nuttx/arch/sh/include/sh1/types.h4
-rw-r--r--nuttx/arch/sh/include/types.h2
-rw-r--r--nuttx/arch/sim/include/types.h6
-rw-r--r--nuttx/arch/z16/include/types.h6
-rw-r--r--nuttx/arch/z80/include/ez80/types.h22
-rw-r--r--nuttx/arch/z80/include/z8/types.h8
-rw-r--r--nuttx/arch/z80/include/z80/types.h8
-rw-r--r--nuttx/drivers/can.c17
-rw-r--r--nuttx/drivers/mmcsd/mmcsd_spi.c10
-rwxr-xr-xnuttx/drivers/mtd/ftl.c7
-rw-r--r--nuttx/drivers/mtd/m25px.c2
-rw-r--r--nuttx/drivers/serial/serial.c11
-rw-r--r--nuttx/examples/ostest/barrier.c8
-rw-r--r--nuttx/examples/ostest/main.c13
-rw-r--r--nuttx/examples/ostest/mqueue.c4
-rw-r--r--nuttx/fs/fs_mmap.c6
-rw-r--r--nuttx/include/signal.h2
-rw-r--r--nuttx/include/sys/types.h9
-rw-r--r--nuttx/include/unistd.h2
-rw-r--r--nuttx/sched/mq_notify.c6
-rw-r--r--nuttx/sched/timer_settime.c8
-rw-r--r--nuttx/sched/usleep.c2
24 files changed, 124 insertions, 58 deletions
diff --git a/nuttx/arch/pjrc-8051/include/types.h b/nuttx/arch/pjrc-8051/include/types.h
index fad90f25d..f334b176f 100644
--- a/nuttx/arch/pjrc-8051/include/types.h
+++ b/nuttx/arch/pjrc-8051/include/types.h
@@ -1,7 +1,7 @@
/************************************************************
- * types.h
+ * arch/types.h
*
- * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2009 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -14,7 +14,7 @@
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
- * 3. Neither the name Gregory Nutt nor the names of its contributors may be
+ * 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.
*
@@ -58,9 +58,6 @@
*
* For SDCC, sizeof(int) is 16 and sizeof(long) is 32.
* long long and double are not supported.
- *
- * Generic pointers are 3 bytes in length with the
- * first byte holding data space intformation.
*/
typedef char sbyte;
@@ -72,6 +69,12 @@ typedef unsigned int uint16;
typedef long sint32;
typedef unsigned long uint32;
+/* For SDCC, a Generic pointer is 3 bytes in length with the
+ * first byte holding data space information.
+ */
+
+typedef unsigned long uintptr;
+
/* This is the size of the interrupt state save returned by
* irqsave()
*/
diff --git a/nuttx/arch/sh/include/m16c/types.h b/nuttx/arch/sh/include/m16c/types.h
index 4c3cad9bd..8037a4617 100644
--- a/nuttx/arch/sh/include/m16c/types.h
+++ b/nuttx/arch/sh/include/m16c/types.h
@@ -68,6 +68,10 @@ typedef unsigned long uint32;
typedef long long sint64;
typedef unsigned long long uint64;
+/* A pointer is 2 bytes */
+
+typedef unsigned int uintptr;
+
/* This is the size of the interrupt state save returned by
* irqsave()
*/
diff --git a/nuttx/arch/sh/include/sh1/types.h b/nuttx/arch/sh/include/sh1/types.h
index 1166fb40c..7b8876c93 100644
--- a/nuttx/arch/sh/include/sh1/types.h
+++ b/nuttx/arch/sh/include/sh1/types.h
@@ -67,6 +67,10 @@ typedef unsigned int uint32;
typedef long long sint64;
typedef unsigned long long uint64;
+/* A pointer is 4 bytes */
+
+typedef unsigned int uintptr;
+
/* This is the size of the interrupt state save returned by
* irqsave()
*/
diff --git a/nuttx/arch/sh/include/types.h b/nuttx/arch/sh/include/types.h
index 593d88306..e50a71c00 100644
--- a/nuttx/arch/sh/include/types.h
+++ b/nuttx/arch/sh/include/types.h
@@ -14,7 +14,7 @@
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
- * 3. Neither the name Gregory Nutt nor the names of its contributors may be
+ * 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.
*
diff --git a/nuttx/arch/sim/include/types.h b/nuttx/arch/sim/include/types.h
index 1c7636886..9648b12ae 100644
--- a/nuttx/arch/sim/include/types.h
+++ b/nuttx/arch/sim/include/types.h
@@ -1,7 +1,7 @@
/************************************************************
* types.h
*
- * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2009 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -67,6 +67,10 @@ typedef unsigned int uint32;
typedef long long sint64;
typedef unsigned long long uint64;
+/* A pointer is 4 bytes */
+
+typedef unsigned int uintptr;
+
/* This is the size of the interrupt state save returned by
* irqsave()
*/
diff --git a/nuttx/arch/z16/include/types.h b/nuttx/arch/z16/include/types.h
index 890779849..1de8149b6 100644
--- a/nuttx/arch/z16/include/types.h
+++ b/nuttx/arch/z16/include/types.h
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/types.h
*
- * Copyright (C) 2008 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2008-2009 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -65,6 +65,10 @@ typedef unsigned short uint16;
typedef int sint32;
typedef unsigned int uint32;
+/* A pointer is 4 bytes */
+
+typedef unsigned int uintptr;
+
/* This is the size of the interrupt state save returned by
* irqsave()
*/
diff --git a/nuttx/arch/z80/include/ez80/types.h b/nuttx/arch/z80/include/ez80/types.h
index f8de240c4..52c95ac6b 100644
--- a/nuttx/arch/z80/include/ez80/types.h
+++ b/nuttx/arch/z80/include/ez80/types.h
@@ -2,7 +2,7 @@
* arch/z80/include/ez80/types.h
* include/arch/chip/types.h
*
- * Copyright (C) 2008 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2008-2009 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -15,7 +15,7 @@
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
- * 3. Neither the name Gregory Nutt nor the names of its contributors may be
+ * 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.
*
@@ -62,11 +62,6 @@
* long - 32-bits
* char - 8-bits
* float - 32-bits
- *
- * Pointers:
- *
- * Z80 mode - 16 bits
- * ADL mode - 24 bits
*/
typedef char sbyte;
@@ -80,6 +75,19 @@ typedef unsigned int uint24;
typedef long sint32;
typedef unsigned long uint32;
+/* A pointer is 2 or 3 bytes, depending upon if the ez80 is in z80
+ * compatibility mode or not
+ *
+ * Z80 mode - 16 bits
+ * ADL mode - 24 bits
+ */
+
+#ifdef CONFIG_EZ80_Z80MODE
+typedef unsigned short uintptr;
+#else
+typedef unsigned int uintptr;
+#endif
+
/* This is the size of the interrupt state save returned by irqsave().
* It holds the AF regiser pair + a zero pad byte
*/
diff --git a/nuttx/arch/z80/include/z8/types.h b/nuttx/arch/z80/include/z8/types.h
index 5cf8f1341..79f2682f6 100644
--- a/nuttx/arch/z80/include/z8/types.h
+++ b/nuttx/arch/z80/include/z8/types.h
@@ -2,7 +2,7 @@
* arch/z80/include/z8/types.h
* include/arch/chip/types.h
*
- * Copyright (C) 2008 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2008-2009 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -15,7 +15,7 @@
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
- * 3. Neither the name Gregory Nutt nor the names of its contributors may be
+ * 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.
*
@@ -80,6 +80,10 @@ typedef unsigned int uint16;
typedef long sint32;
typedef unsigned long uint32;
+/* A pointer is 2 bytes */
+
+typedef unsigned int uintptr;
+
/* This is the size of the interrupt state save returned by irqsave() */
typedef ubyte irqstate_t;
diff --git a/nuttx/arch/z80/include/z80/types.h b/nuttx/arch/z80/include/z80/types.h
index 97efa0761..d482725bc 100644
--- a/nuttx/arch/z80/include/z80/types.h
+++ b/nuttx/arch/z80/include/z80/types.h
@@ -2,7 +2,7 @@
* arch/z80/include/z80/types.h
* include/arch/chip/types.h
*
- * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2009 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -15,7 +15,7 @@
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
- * 3. Neither the name Gregory Nutt nor the names of its contributors may be
+ * 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.
*
@@ -73,6 +73,10 @@ typedef unsigned int uint16;
typedef long sint32;
typedef unsigned long uint32;
+/* A pointer is 2 bytes */
+
+typedef unsigned int uintptr;
+
/* This is the size of the interrupt state save returned by irqsave() */
typedef uint16 irqstate_t;
diff --git a/nuttx/drivers/can.c b/nuttx/drivers/can.c
index 509210a8f..834765183 100644
--- a/nuttx/drivers/can.c
+++ b/nuttx/drivers/can.c
@@ -61,6 +61,9 @@
* Definitions
****************************************************************************/
+#define HALF_SECOND_MSEC 500
+#define HALF_SECOND_USEC 500000L
+
/****************************************************************************
* Private Type Definitions
****************************************************************************/
@@ -214,9 +217,9 @@ static int can_close(FAR struct file *filep)
while (dev->cd_xmit.cf_head != dev->cd_xmit.cf_tail)
{
#ifndef CONFIG_DISABLE_SIGNALS
- usleep(500*1000);
+ usleep(HALF_SECOND_USEC);
#else
- up_mdelay(500);
+ up_mdelay(HALF_SECOND_MSEC);
#endif
}
@@ -225,9 +228,9 @@ static int can_close(FAR struct file *filep)
while (!dev_txempty(dev))
{
#ifndef CONFIG_DISABLE_SIGNALS
- usleep(500*1000);
+ usleep(HALF_SECOND_USEC);
#else
- up_mdelay(500);
+ up_mdelay(HALF_SECOND_MSEC);
#endif
}
@@ -554,11 +557,13 @@ static int can_ioctl(FAR struct file *filep, int cmd, unsigned long arg)
switch (cmd)
{
/* CANIOCTL_RTR: Send the remote transmission request and wait for the response.
- * Argument is a reference to struct canioctl_rtr_s
+ * Argument is a reference to struct canioctl_rtr_s (casting to uintptr first
+ * eliminates complaints on some architectures where the sizeof long is different
+ * from the size of a pointer).
*/
case CANIOCTL_RTR:
- ret = can_rtrread(dev, (struct canioctl_rtr_s*)arg);
+ ret = can_rtrread(dev, (struct canioctl_rtr_s*)((uintptr)arg));
break;
/* Not a "built-in" ioctl command.. perhaps it is unique to this device driver */
diff --git a/nuttx/drivers/mmcsd/mmcsd_spi.c b/nuttx/drivers/mmcsd/mmcsd_spi.c
index 412969922..896d8515f 100644
--- a/nuttx/drivers/mmcsd/mmcsd_spi.c
+++ b/nuttx/drivers/mmcsd/mmcsd_spi.c
@@ -564,13 +564,13 @@ static void mmcsd_setblklen(FAR struct mmcsd_slot_s *slot, uint32 length)
static uint32 mmcsd_nsac(FAR struct mmcsd_slot_s *slot, ubyte *csd, uint32 frequency)
{
- /* NSAC is 8-bits width and is in units of 100 clock cycles. Therefore, the
+ /* NSAC is 8-bits wide and is in units of 100 clock cycles. Therefore, the
* maximum value is 25.5K clock cycles.
*/
- uint32 nsac = MMCSD_CSD_NSAC(csd) * (100*1000); /* 1,000 * NSAC */
- uint32 fhkz = (frequency + 500) / 1000; /* frequency / 1,000 */
- return (nsac + (fhkz >> 1)) / fhkz; /* 1,000,000 * NSAC / frequency */
+ uint32 nsac = MMCSD_CSD_NSAC(csd) * ((uint32)100*1000); /* 1,000 * NSAC */
+ uint32 fhkz = (frequency + 500) / 1000; /* frequency / 1,000 */
+ return (nsac + (fhkz >> 1)) / fhkz; /* 1,000,000 * NSAC / frequency */
}
/****************************************************************************
@@ -1699,7 +1699,7 @@ static int mmcsd_mediainitialize(FAR struct mmcsd_slot_s *slot)
* of 1024 or 2048.
*/
- if (!IS_SDV2(slot->type) && slot->nsectors <= 4096*12)
+ if (!IS_SDV2(slot->type) && slot->nsectors <= ((uint32)4096*12))
{
/* Don't set the block len on high capacity cards (ver1.x or ver2.x) */
diff --git a/nuttx/drivers/mtd/ftl.c b/nuttx/drivers/mtd/ftl.c
index 08fa94203..43c4b3aed 100755
--- a/nuttx/drivers/mtd/ftl.c
+++ b/nuttx/drivers/mtd/ftl.c
@@ -473,9 +473,12 @@ int ftl_initialize(int minor, ubyte *buffer, FAR struct mtd_dev_s *mtd)
dev->mtd = mtd;
- /* Get the device geometry */
+ /* Get the device geometry. (casting to uintptr first eliminates
+ * complaints on some architectures where the sizeof long is different
+ * from the size of a pointer).
+ */
- ret = MTD_IOCTL(mtd, MTDIOC_GEOMETRY, (unsigned long)&dev->geo);
+ ret = MTD_IOCTL(mtd, MTDIOC_GEOMETRY, (unsigned long)((uintptr)&dev->geo));
if (ret < 0)
{
fdbg("MTD ioctl(MTDIOC_GEOMETRY) failed: %d\n", ret);
diff --git a/nuttx/drivers/mtd/m25px.c b/nuttx/drivers/mtd/m25px.c
index bdb0341a0..e42f05cc9 100644
--- a/nuttx/drivers/mtd/m25px.c
+++ b/nuttx/drivers/mtd/m25px.c
@@ -577,7 +577,7 @@ static int m25p_ioctl(FAR struct mtd_dev_s *dev, int cmd, unsigned long arg)
{
case MTDIOC_GEOMETRY:
{
- FAR struct mtd_geometry_s *geo = (FAR struct mtd_geometry_s *)arg;
+ FAR struct mtd_geometry_s *geo = (FAR struct mtd_geometry_s *)((uintptr)arg);
if (geo)
{
/* Populate the geometry structure with information need to know
diff --git a/nuttx/drivers/serial/serial.c b/nuttx/drivers/serial/serial.c
index df942a050..5675f1791 100644
--- a/nuttx/drivers/serial/serial.c
+++ b/nuttx/drivers/serial/serial.c
@@ -65,6 +65,9 @@
#define uart_putc(ch) up_putc(ch)
+#define HALF_SECOND_MSEC 500
+#define HALF_SECOND_USEC 500000L
+
/************************************************************************************
* Private Types
************************************************************************************/
@@ -543,9 +546,9 @@ static int uart_close(FAR struct file *filep)
while (dev->xmit.head != dev->xmit.tail)
{
#ifndef CONFIG_DISABLE_SIGNALS
- usleep(500*1000);
+ usleep(HALF_SECOND_USEC);
#else
- up_mdelay(500);
+ up_mdelay(HALF_SECOND_MSEC);
#endif
}
@@ -554,9 +557,9 @@ static int uart_close(FAR struct file *filep)
while (!uart_txempty(dev))
{
#ifndef CONFIG_DISABLE_SIGNALS
- usleep(500*1000);
+ usleep(HALF_SECOND_USEC);
#else
- up_mdelay(500);
+ up_mdelay(HALF_SECOND_MSEC);
#endif
}
diff --git a/nuttx/examples/ostest/barrier.c b/nuttx/examples/ostest/barrier.c
index 6b33ac0e3..56c0b75b1 100644
--- a/nuttx/examples/ostest/barrier.c
+++ b/nuttx/examples/ostest/barrier.c
@@ -1,7 +1,7 @@
/****************************************************************************
* examples/ostest/barrier.c
*
- * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2009 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -48,6 +48,8 @@
* Definitions
****************************************************************************/
+#define HALF_SECOND 500000L
+
/****************************************************************************
* Private Data
****************************************************************************/
@@ -69,7 +71,7 @@ static void *barrier_func(void *parameter)
printf("barrier_func: Thread %d started\n", id);
#ifndef CONFIG_DISABLE_SIGNALS
- usleep(500*1000);
+ usleep(HALF_SECOND);
#endif
/* Wait at the barrier until all threads are synchronized. */
@@ -96,7 +98,7 @@ static void *barrier_func(void *parameter)
}
#ifndef CONFIG_DISABLE_SIGNALS
- usleep(500*1000);
+ usleep(HALF_SECOND);
#endif
printf("barrier_func: Thread %d done\n", id);
return NULL;
diff --git a/nuttx/examples/ostest/main.c b/nuttx/examples/ostest/main.c
index 261f7974b..22a45dcfc 100644
--- a/nuttx/examples/ostest/main.c
+++ b/nuttx/examples/ostest/main.c
@@ -1,5 +1,5 @@
/****************************************************************************
- * ostest/main.c
+ * examples/ostest/main.c
*
* Copyright (C) 2007-2009 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
@@ -51,8 +51,9 @@
* Definitions
****************************************************************************/
-#define PRIORITY 100
-#define NARGS 4
+#define PRIORITY 100
+#define NARGS 4
+#define HALF_SECOND_USEC 500000L
/****************************************************************************
* Private Data
@@ -133,7 +134,7 @@ static void check_test_memory_usage(void)
{
/* Wait a little bit to let any threads terminate */
- usleep(500*1000);
+ usleep(HALF_SECOND_USEC);
/* Get the current memory usage */
@@ -224,7 +225,7 @@ static int user_main(int argc, char *argv[])
/* Sample the memory usage now */
#ifndef CONFIG_DISABLE_SIGNALS
- usleep(500*1000);
+ usleep(HALF_SECOND_USEC);
#ifdef CONFIG_CAN_PASS_STRUCTS
g_mmbefore = mallinfo();
@@ -405,7 +406,7 @@ static int user_main(int argc, char *argv[])
*/
#ifndef CONFIG_DISABLE_SIGNALS
- usleep(500*1000);
+ usleep(HALF_SECOND_USEC);
#ifdef CONFIG_CAN_PASS_STRUCTS
g_mmafter = mallinfo();
diff --git a/nuttx/examples/ostest/mqueue.c b/nuttx/examples/ostest/mqueue.c
index 8c96d9cf4..e68cfc012 100644
--- a/nuttx/examples/ostest/mqueue.c
+++ b/nuttx/examples/ostest/mqueue.c
@@ -73,6 +73,8 @@
# define TEST_RECEIVE_NMSGS (10)
#endif
+#define HALF_SECOND_USEC_USEC 500000L
+
/**************************************************************************
* Private Types
**************************************************************************/
@@ -370,7 +372,7 @@ void mqueue_test(void)
/* Wait a bit to see if the thread exits on its own */
- usleep(500*1000);
+ usleep(HALF_SECOND_USEC_USEC);
#endif
/* Then cancel the thread and see if it did */
diff --git a/nuttx/fs/fs_mmap.c b/nuttx/fs/fs_mmap.c
index 309d48942..0fa0b56e1 100644
--- a/nuttx/fs/fs_mmap.c
+++ b/nuttx/fs/fs_mmap.c
@@ -146,10 +146,12 @@ FAR void *mmap(FAR void *start, size_t length, int prot, int flags,
* only option supported
*
* Perform the ioctl to get the base address of the file in 'mapped'
- * in memory.
+ * in memory. (casting to uintptr first eliminates complaints on some
+ * architectures where the sizeof long is different from the size of
+ * a pointer).
*/
- ret = ioctl(fd, FIOC_MMAP, (unsigned long)&addr);
+ ret = ioctl(fd, FIOC_MMAP, (unsigned long)((uintptr)&addr));
if (ret < 0)
{
fdbg("ioctl(FIOC_MMAP) failed: %d\n", errno);
diff --git a/nuttx/include/signal.h b/nuttx/include/signal.h
index 9357c4d7d..baa1e2ad3 100644
--- a/nuttx/include/signal.h
+++ b/nuttx/include/signal.h
@@ -59,7 +59,7 @@
#define ALL_SIGNAL_SET ((sigset_t)0xffffffff)
#define MIN_SIGNO 0
#define MAX_SIGNO 31
-#define GOOD_SIGNO(s) (((s)>=MIN_SIGNO)&&((s)<=MAX_SIGNO))
+#define GOOD_SIGNO(s) ((((unsigned)(s))<=MAX_SIGNO))
#define SIGNO2SET(s) ((sigset_t)1 << (s))
/* All signals are "real time" signals */
diff --git a/nuttx/include/sys/types.h b/nuttx/include/sys/types.h
index 0c0204255..91544bf0c 100644
--- a/nuttx/include/sys/types.h
+++ b/nuttx/include/sys/types.h
@@ -135,6 +135,15 @@ typedef int STATUS;
typedef unsigned int socklen_t;
typedef uint16 sa_family_t;
+/* The type useconds_t shall be an unsigned integer type capable of storing
+ * values at least in the range [0, 1000000]. The type suseconds_t shall be
+ * a signed integer type capable of storing values at least in the range
+ * [-1, 1000000].
+ */
+
+typedef uint32 useconds_t;
+typedef sint32 suseconds_t;
+
/* Task entry point */
typedef int (*main_t)(int argc, char *argv[]);
diff --git a/nuttx/include/unistd.h b/nuttx/include/unistd.h
index 3d05dcb99..0db1acbb0 100644
--- a/nuttx/include/unistd.h
+++ b/nuttx/include/unistd.h
@@ -132,7 +132,7 @@ EXTERN int optopt; /* unrecognized option character */
EXTERN pid_t getpid(void);
EXTERN void _exit(int status) noreturn_function;
EXTERN unsigned int sleep(unsigned int seconds);
-EXTERN void usleep(unsigned long usec);
+EXTERN void usleep(useconds_t usec);
/* File descriptor operations */
diff --git a/nuttx/sched/mq_notify.c b/nuttx/sched/mq_notify.c
index 60d5bc1a8..b01a2d7c7 100644
--- a/nuttx/sched/mq_notify.c
+++ b/nuttx/sched/mq_notify.c
@@ -1,7 +1,7 @@
/************************************************************
- * mq_notify.c
+ * sched/mq_notify.c
*
- * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2009 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -14,7 +14,7 @@
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
- * 3. Neither the name Gregory Nutt nor the names of its contributors may be
+ * 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.
*
diff --git a/nuttx/sched/timer_settime.c b/nuttx/sched/timer_settime.c
index 25dfc32c4..1551ff3a7 100644
--- a/nuttx/sched/timer_settime.c
+++ b/nuttx/sched/timer_settime.c
@@ -200,7 +200,11 @@ static void timer_timeout(int argc, uint32 itimer)
timer_restart(u.timer, itimer);
}
#else
- FAR struct posix_timer_s *timer = (FAR struct posix_timer_s *)itimer;
+ /* (casting to uintptr first eliminates complaints on some architectures
+ * where the sizeof uint32 is different from the size of a pointer).
+ */
+
+ FAR struct posix_timer_s *timer = (FAR struct posix_timer_s *)((uintptr)itimer);
/* Send the specified signal to the specified task. Increment the reference
* count on the timer first so that will not be deleted until after the
@@ -379,7 +383,7 @@ int timer_settime(timer_t timerid, int flags, FAR const struct itimerspec *value
if (delay > 0)
{
timer->pt_last = delay;
- ret = wd_start(timer->pt_wdog, timer->pt_delay, (wdentry_t)timer_timeout, 1, (uint32)timer);
+ ret = wd_start(timer->pt_wdog, timer->pt_delay, (wdentry_t)timer_timeout, 1, (uint32)((uintptr)timer));
}
irqrestore(state);
diff --git a/nuttx/sched/usleep.c b/nuttx/sched/usleep.c
index d92dcc2bf..2751628eb 100644
--- a/nuttx/sched/usleep.c
+++ b/nuttx/sched/usleep.c
@@ -82,7 +82,7 @@
*
****************************************************************************/
-void usleep(unsigned long usec)
+void usleep(useconds_t usec)
{
sigset_t set;
struct timespec ts;