summaryrefslogtreecommitdiff
path: root/nuttx
diff options
context:
space:
mode:
Diffstat (limited to 'nuttx')
-rw-r--r--nuttx/arch/sim/src/up_createstack.c2
-rw-r--r--nuttx/arch/sim/src/up_reprioritizertr.c11
-rw-r--r--nuttx/binfmt/symtab_findbyvalue.c1
-rw-r--r--nuttx/binfmt/symtab_findorderedbyvalue.c1
-rw-r--r--nuttx/drivers/can.c4
-rw-r--r--nuttx/drivers/mmcsd/mmcsd_sdio.c6
-rwxr-xr-xnuttx/drivers/mtd/ftl.c6
-rw-r--r--nuttx/drivers/mtd/m25px.c2
-rw-r--r--nuttx/fs/fat/fs_configfat.c12
-rw-r--r--nuttx/include/errno.h4
-rw-r--r--nuttx/include/pthread.h2
-rwxr-xr-xnuttx/include/stdint.h1
-rw-r--r--nuttx/include/sys/types.h14
-rw-r--r--nuttx/sched/mq_sndinternal.c2
-rw-r--r--nuttx/sched/pthread_condattrinit.c2
15 files changed, 44 insertions, 26 deletions
diff --git a/nuttx/arch/sim/src/up_createstack.c b/nuttx/arch/sim/src/up_createstack.c
index 76f13f1e7..03426ade2 100644
--- a/nuttx/arch/sim/src/up_createstack.c
+++ b/nuttx/arch/sim/src/up_createstack.c
@@ -96,7 +96,7 @@ int up_create_stack(_TCB *tcb, size_t stack_size)
/* Allocate the memory for the stack */
- uint32 *stack_alloc_ptr = (uint32_t*)kmalloc(adj_stack_size);
+ uint32_t *stack_alloc_ptr = (uint32_t*)kmalloc(adj_stack_size);
if (stack_alloc_ptr)
{
/* This is the address of the last word in the allocation */
diff --git a/nuttx/arch/sim/src/up_reprioritizertr.c b/nuttx/arch/sim/src/up_reprioritizertr.c
index a11bada6d..a7ffb137d 100644
--- a/nuttx/arch/sim/src/up_reprioritizertr.c
+++ b/nuttx/arch/sim/src/up_reprioritizertr.c
@@ -90,9 +90,14 @@ void up_reprioritize_rtr(_TCB *tcb, uint8_t priority)
/* Verify that the caller is sane */
if (tcb->task_state < FIRST_READY_TO_RUN_STATE ||
- tcb->task_state > LAST_READY_TO_RUN_STATE ||
- priority < SCHED_PRIORITY_MIN ||
- priority > SCHED_PRIORITY_MAX)
+ tcb->task_state > LAST_READY_TO_RUN_STATE
+#if SCHED_PRIORITY_MIN > UINT8_MIN
+ || priority < SCHED_PRIORITY_MIN
+#endif
+#if SCHED_PRIORITY_MAX < UINT8_MAX
+ || priority > SCHED_PRIORITY_MAX
+#endif
+ )
{
PANIC(OSERR_BADREPRIORITIZESTATE);
}
diff --git a/nuttx/binfmt/symtab_findbyvalue.c b/nuttx/binfmt/symtab_findbyvalue.c
index 269fd8bb2..80df74668 100644
--- a/nuttx/binfmt/symtab_findbyvalue.c
+++ b/nuttx/binfmt/symtab_findbyvalue.c
@@ -39,6 +39,7 @@
#include <nuttx/config.h>
+#include <stddef.h>
#include <debug.h>
#include <assert.h>
#include <errno.h>
diff --git a/nuttx/binfmt/symtab_findorderedbyvalue.c b/nuttx/binfmt/symtab_findorderedbyvalue.c
index aae3f780b..a995595da 100644
--- a/nuttx/binfmt/symtab_findorderedbyvalue.c
+++ b/nuttx/binfmt/symtab_findorderedbyvalue.c
@@ -39,6 +39,7 @@
#include <nuttx/config.h>
+#include <stddef.h>
#include <debug.h>
#include <assert.h>
#include <errno.h>
diff --git a/nuttx/drivers/can.c b/nuttx/drivers/can.c
index 47525257d..3be0248dc 100644
--- a/nuttx/drivers/can.c
+++ b/nuttx/drivers/can.c
@@ -559,13 +559,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 (casting to uintptr first
+ * Argument is a reference to struct canioctl_rtr_s (casting to uintptr_t 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*)((uintptr)arg));
+ ret = can_rtrread(dev, (struct canioctl_rtr_s*)((uintptr_t)arg));
break;
/* Not a "built-in" ioctl command.. perhaps it is unique to this device driver */
diff --git a/nuttx/drivers/mmcsd/mmcsd_sdio.c b/nuttx/drivers/mmcsd/mmcsd_sdio.c
index 7eea71983..9d04c683b 100644
--- a/nuttx/drivers/mmcsd/mmcsd_sdio.c
+++ b/nuttx/drivers/mmcsd/mmcsd_sdio.c
@@ -218,7 +218,9 @@ static int mmcsd_ioctl(FAR struct inode *inode, int cmd,
static void mmcsd_mediachange(FAR void *arg);
static int mmcsd_widebus(FAR struct mmcsd_state_s *priv);
+#ifdef CONFIG_MMCSD_MMCSUPPORT
static int mmcsd_mmcinitialize(FAR struct mmcsd_state_s *priv);
+#endif
static int mmcsd_sdinitialize(FAR struct mmcsd_state_s *priv);
static int mmcsd_cardidentify(FAR struct mmcsd_state_s *priv);
static int mmcsd_probe(FAR struct mmcsd_state_s *priv);
@@ -2120,9 +2122,9 @@ static int mmcsd_widebus(FAR struct mmcsd_state_s *priv)
*
****************************************************************************/
+#ifdef CONFIG_MMCSD_MMCSUPPORT
static int mmcsd_mmcinitialize(FAR struct mmcsd_state_s *priv)
{
-#ifdef CONFIG_MMCSD_MMCSUPPORT
uint32_t cid[4];
uint32_t csd[4];
int ret;
@@ -2201,9 +2203,9 @@ static int mmcsd_mmcinitialize(FAR struct mmcsd_state_s *priv)
SDIO_CLOCK(priv->dev, CLOCK_MMC_TRANSFER);
up_udelay( MMCSD_CLK_DELAY);
-#endif
return OK;
}
+#endif
/****************************************************************************
* Name: mmcsd_sdinitialize
diff --git a/nuttx/drivers/mtd/ftl.c b/nuttx/drivers/mtd/ftl.c
index 1e9ab5ebd..11ed83f63 100755
--- a/nuttx/drivers/mtd/ftl.c
+++ b/nuttx/drivers/mtd/ftl.c
@@ -475,12 +475,12 @@ int ftl_initialize(int minor, uint8_t *buffer, FAR struct mtd_dev_s *mtd)
dev->mtd = mtd;
- /* Get the device geometry. (casting to uintptr first eliminates
+ /* Get the device geometry. (casting to uintptr_t 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)((uintptr)&dev->geo));
+ ret = MTD_IOCTL(mtd, MTDIOC_GEOMETRY, (unsigned long)((uintptr_t)&dev->geo));
if (ret < 0)
{
fdbg("MTD ioctl(MTDIOC_GEOMETRY) failed: %d\n", ret);
@@ -503,7 +503,7 @@ int ftl_initialize(int minor, uint8_t *buffer, FAR struct mtd_dev_s *mtd)
/* Get the number of R/W blocks per erase block */
dev->blkper = dev->geo.erasesize / dev->geo.blocksize;
- DEBUGASSERT(dev->blkper * dev->geo.blocksize = dev->geo.erasesize);
+ DEBUGASSERT(dev->blkper * dev->geo.blocksize == dev->geo.erasesize);
/* Configure read-ahead/write buffering */
diff --git a/nuttx/drivers/mtd/m25px.c b/nuttx/drivers/mtd/m25px.c
index 0899376d6..509b8302a 100644
--- a/nuttx/drivers/mtd/m25px.c
+++ b/nuttx/drivers/mtd/m25px.c
@@ -579,7 +579,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 *)((uintptr)arg);
+ FAR struct mtd_geometry_s *geo = (FAR struct mtd_geometry_s *)((uintptr_t)arg);
if (geo)
{
/* Populate the geometry structure with information need to know
diff --git a/nuttx/fs/fat/fs_configfat.c b/nuttx/fs/fat/fs_configfat.c
index 17a3e528d..9ec7573a7 100644
--- a/nuttx/fs/fat/fs_configfat.c
+++ b/nuttx/fs/fat/fs_configfat.c
@@ -137,8 +137,8 @@ mkfatfs_nfatsect12(FAR struct fat_format_s *fmt, FAR struct fat_var_s *var,
uint32_t navailsects)
{
#ifdef CONFIG_HAVE_LONG_LONG
- uint64 denom;
- uint64 numer;
+ uint64_t denom;
+ uint64_t numer;
#else
uint32_t denom;
uint32_t numer;
@@ -214,8 +214,8 @@ mkfatfs_nfatsect16(FAR struct fat_format_s *fmt, FAR struct fat_var_s *var,
uint32_t navailsects)
{
#ifdef CONFIG_HAVE_LONG_LONG
- uint64 denom;
- uint64 numer;
+ uint64_t denom;
+ uint64_t numer;
#else
uint32_t denom;
uint32_t numer;
@@ -280,8 +280,8 @@ mkfatfs_nfatsect32(FAR struct fat_format_s *fmt, FAR struct fat_var_s *var,
uint32_t navailsects)
{
#ifdef CONFIG_HAVE_LONG_LONG
- uint64 denom;
- uint64 numer;
+ uint64_t denom;
+ uint64_t numer;
#else
uint32_t denom;
uint32_t numer;
diff --git a/nuttx/include/errno.h b/nuttx/include/errno.h
index 945f83957..8c1654b0f 100644
--- a/nuttx/include/errno.h
+++ b/nuttx/include/errno.h
@@ -40,6 +40,8 @@
* Included Files
************************************************************************/
+#include <nuttx/compiler.h>
+
/************************************************************************
* Definitions
************************************************************************/
@@ -317,7 +319,7 @@ extern "C" {
/* Return a pointer to the thread specifid errno */
-extern FAR int *get_errno_ptr(void);
+EXTERN FAR int *get_errno_ptr(void);
#undef EXTERN
#if defined(__cplusplus)
diff --git a/nuttx/include/pthread.h b/nuttx/include/pthread.h
index c3342b369..c0cf9b75e 100644
--- a/nuttx/include/pthread.h
+++ b/nuttx/include/pthread.h
@@ -163,7 +163,7 @@ struct pthread_attr_s
size_t stacksize; /* Size of the stack allocated for the pthead */
int16_t priority; /* Priority of the pthread */
uint8_t policy; /* Pthread scheduler policy */
- uint8_t nheritsched; /* Inherit parent prio/policy? */
+ uint8_t inheritsched; /* Inherit parent prio/policy? */
};
typedef struct pthread_attr_s pthread_attr_t;
diff --git a/nuttx/include/stdint.h b/nuttx/include/stdint.h
index eece03496..3bd1d9f47 100755
--- a/nuttx/include/stdint.h
+++ b/nuttx/include/stdint.h
@@ -43,6 +43,7 @@
#include <nuttx/config.h>
#include <nuttx/compiler.h>
+#include <arch/types.h>
#include <limits.h>
/****************************************************************************
diff --git a/nuttx/include/sys/types.h b/nuttx/include/sys/types.h
index 286cc3fe9..205beefff 100644
--- a/nuttx/include/sys/types.h
+++ b/nuttx/include/sys/types.h
@@ -43,16 +43,22 @@
#include <nuttx/config.h>
#include <nuttx/compiler.h>
-#include <stdint.h>
+#ifndef __ASSEMBLY__
+# include <stdint.h>
+#endif
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
-/* Alternative alues for type bool (for historic reasons) */
+/* Alternative values for type bool (for historic reasons) */
-#define TRUE 1
-#define FALSE 0
+#ifndef TRUE
+# define TRUE 1
+#endif
+#ifndef FALSE
+# define FALSE 0
+#endif
/* NULL is usually defined in stddef.h (which includes this file) */
diff --git a/nuttx/sched/mq_sndinternal.c b/nuttx/sched/mq_sndinternal.c
index 6184ced7d..64eee136d 100644
--- a/nuttx/sched/mq_sndinternal.c
+++ b/nuttx/sched/mq_sndinternal.c
@@ -40,7 +40,7 @@
#include <nuttx/config.h>
#include <sys/types.h>
-#include <sigint.h>
+#include <stdint.h>
#include <fcntl.h>
#include <mqueue.h>
#include <string.h>
diff --git a/nuttx/sched/pthread_condattrinit.c b/nuttx/sched/pthread_condattrinit.c
index 1e3746654..30e3f71ac 100644
--- a/nuttx/sched/pthread_condattrinit.c
+++ b/nuttx/sched/pthread_condattrinit.c
@@ -37,7 +37,7 @@
* Included Files
****************************************************************************/
-#include <config/nuttx.h>
+#include <nuttx/config.h>
#include <pthread.h>
#include <debug.h>