aboutsummaryrefslogtreecommitdiff
path: root/nuttx/include
diff options
context:
space:
mode:
Diffstat (limited to 'nuttx/include')
-rw-r--r--nuttx/include/cxx/cmath62
-rw-r--r--nuttx/include/cxx/cstdbool9
-rw-r--r--nuttx/include/cxx/cstdio12
-rw-r--r--nuttx/include/cxx/cstdlib1
-rw-r--r--nuttx/include/debug.h25
-rw-r--r--nuttx/include/elf32.h352
-rw-r--r--nuttx/include/net/if.h9
-rw-r--r--nuttx/include/nuttx/arch.h290
-rw-r--r--nuttx/include/nuttx/binfmt/binfmt.h (renamed from nuttx/include/nuttx/binfmt.h)175
-rw-r--r--nuttx/include/nuttx/binfmt/elf.h340
-rw-r--r--nuttx/include/nuttx/binfmt/nxflat.h (renamed from nuttx/include/nuttx/nxflat.h)85
-rw-r--r--nuttx/include/nuttx/binfmt/symtab.h (renamed from nuttx/include/nuttx/symtab.h)10
-rw-r--r--nuttx/include/nuttx/compiler.h25
-rw-r--r--nuttx/include/nuttx/float.h225
-rw-r--r--nuttx/include/nuttx/fs/fs.h17
-rw-r--r--nuttx/include/nuttx/i2c.h31
-rw-r--r--nuttx/include/nuttx/input/keypad.h54
-rw-r--r--nuttx/include/nuttx/input/max11802.h175
-rw-r--r--nuttx/include/nuttx/lcd/ug-2864ambag01.h245
-rw-r--r--nuttx/include/nuttx/lcd/ug-9664hswag01.h15
-rw-r--r--nuttx/include/nuttx/math.h270
-rw-r--r--nuttx/include/nuttx/mtd.h3
-rw-r--r--nuttx/include/nuttx/net/ioctl.h6
-rw-r--r--nuttx/include/nuttx/net/uip/uip-arch.h4
-rw-r--r--nuttx/include/nuttx/power/pm.h6
-rw-r--r--nuttx/include/nuttx/sched.h38
-rw-r--r--nuttx/include/nuttx/usb/cdcacm.h2
-rw-r--r--nuttx/include/nuttx/usb/usbdev_trace.h4
-rw-r--r--nuttx/include/nuttx/vt100.h4
-rw-r--r--nuttx/include/nuttx/wqueue.h24
-rw-r--r--nuttx/include/stdbool.h35
-rw-r--r--nuttx/include/stdio.h7
-rw-r--r--nuttx/include/termios.h30
-rw-r--r--nuttx/include/unistd.h1
34 files changed, 2405 insertions, 186 deletions
diff --git a/nuttx/include/cxx/cmath b/nuttx/include/cxx/cmath
index 7cb3a2109..b30d5548b 100644
--- a/nuttx/include/cxx/cmath
+++ b/nuttx/include/cxx/cmath
@@ -40,6 +40,9 @@
// Included Files
//***************************************************************************
+#include <nuttx/config.h>
+#include <nuttx/compiler.h>
+
#include <math.h>
//***************************************************************************
@@ -48,6 +51,34 @@
namespace std
{
+#if CONFIG_HAVE_FLOAT
+ using ::acosf;
+ using ::asinf;
+ using ::atanf;
+ using ::atan2f;
+ using ::ceilf;
+ using ::cosf;
+ using ::coshf;
+ using ::expf;
+ using ::fabsf;
+ using ::floorf;
+ using ::fmodf;
+ using ::frexpf;
+ using ::ldexpf;
+ using ::logf;
+ using ::log10f;
+ using ::log2f;
+ using ::modff;
+ using ::roundf;
+ using ::powf;
+ using ::sinf;
+ using ::sinhf;
+ using ::sqrtf;
+ using ::tanf;
+ using ::tanhf;
+#endif
+
+#if CONFIG_HAVE_DOUBLE
using ::acos;
using ::asin;
using ::atan;
@@ -63,13 +94,44 @@ namespace std
using ::ldexp;
using ::log;
using ::log10;
+ using ::log2;
using ::modf;
+ using ::round;
using ::pow;
using ::sin;
using ::sinh;
using ::sqrt;
using ::tan;
using ::tanh;
+#endif
+
+#ifdef CONFIG_HAVE_LONG_DOUBLE
+ using ::acosl;
+ using ::asinl;
+ using ::atanl;
+ using ::atan2l;
+ using ::ceill;
+ using ::cosl;
+ using ::coshl;
+ using ::expl;
+ using ::fabsl;
+ using ::floorl;
+ using ::fmodl;
+ using ::frexpl;
+ using ::ldexpl;
+ using ::logl;
+ using ::log10l;
+ using ::log2l;
+ using ::modfl;
+ using ::roundl;
+ using ::powl;
+ using ::sinl;
+ using ::sinhl;
+ using ::sqrtl;
+ using ::tanl;
+ using ::tanhl;
+#endif
+
}
#endif // __INCLUDE_CXX_CMATH
diff --git a/nuttx/include/cxx/cstdbool b/nuttx/include/cxx/cstdbool
index d2f0639d2..192fde490 100644
--- a/nuttx/include/cxx/cstdbool
+++ b/nuttx/include/cxx/cstdbool
@@ -46,4 +46,13 @@
// Namespace
//***************************************************************************
+//***************************************************************************
+// Namespace
+//***************************************************************************
+
+namespace std
+{
+ using ::_Bool8;
+}
+
#endif // __INCLUDE_CXX_CSTDBOOL
diff --git a/nuttx/include/cxx/cstdio b/nuttx/include/cxx/cstdio
index 900d429cb..6a9620e1a 100644
--- a/nuttx/include/cxx/cstdio
+++ b/nuttx/include/cxx/cstdio
@@ -52,6 +52,8 @@ namespace std
using ::FILE;
using ::fpos_t;
using ::size_t;
+
+ using ::clearerr;
using ::fclose;
using ::fflush;
using ::feof;
@@ -69,16 +71,24 @@ namespace std
using ::ftell;
using ::fwrite;
using ::gets;
+ using ::ungetc;
+
using ::printf;
using ::puts;
using ::rename;
using ::sprintf;
+ using ::asprintf;
using ::snprintf;
- using ::ungetc;
+ using ::sscanf;
+ using ::perror;
+
using ::vprintf;
using ::vfprintf;
using ::vsprintf;
+ using ::avsprintf;
using ::vsnprintf;
+ using ::vsscanf;
+
using ::fdopen;
using ::statfs;
}
diff --git a/nuttx/include/cxx/cstdlib b/nuttx/include/cxx/cstdlib
index 522f3fdb1..1bf8ed9da 100644
--- a/nuttx/include/cxx/cstdlib
+++ b/nuttx/include/cxx/cstdlib
@@ -70,6 +70,7 @@ namespace std
#endif
using ::strtol;
+ using ::strtoul;
using ::strtod;
using ::malloc;
diff --git a/nuttx/include/debug.h b/nuttx/include/debug.h
index 1f8c7d7ca..aa5efd432 100644
--- a/nuttx/include/debug.h
+++ b/nuttx/include/debug.h
@@ -571,12 +571,9 @@
* Public Function Prototypes
****************************************************************************/
-#undef EXTERN
#if defined(__cplusplus)
-#define EXTERN extern "C"
-extern "C" {
-#else
-#define EXTERN extern
+extern "C"
+{
#endif
/* These low-level debug APIs are provided by the NuttX library. If the
@@ -585,21 +582,20 @@ extern "C" {
* or the other of the following.
*/
-EXTERN int lib_rawprintf(FAR const char *format, ...);
+int lib_rawprintf(FAR const char *format, ...);
#ifdef CONFIG_ARCH_LOWPUTC
-EXTERN int lib_lowprintf(FAR const char *format, ...);
+int lib_lowprintf(FAR const char *format, ...);
#endif
/* Dump a buffer of data */
-EXTERN void lib_dumpbuffer(FAR const char *msg, FAR const uint8_t *buffer,
- unsigned int buflen);
+void lib_dumpbuffer(FAR const char *msg, FAR const uint8_t *buffer, unsigned int buflen);
/* Enable or disable debug output */
#ifdef CONFIG_DEBUG_ENABLE
-EXTERN void dbg_enable(bool enable);
+void dbg_enable(bool enable);
#endif
/* If the cross-compiler's pre-processor does not support variable length
@@ -608,23 +604,22 @@ EXTERN void dbg_enable(bool enable);
#ifndef CONFIG_CPP_HAVE_VARARGS
#ifdef CONFIG_DEBUG
-EXTERN int dbg(const char *format, ...);
+int dbg(const char *format, ...);
# ifdef CONFIG_ARCH_LOWPUTC
-EXTERN int lldbg(const char *format, ...);
+int lldbg(const char *format, ...);
# endif
# ifdef CONFIG_DEBUG_VERBOSE
-EXTERN int vdbg(const char *format, ...);
+int vdbg(const char *format, ...);
# ifdef CONFIG_ARCH_LOWPUTC
-EXTERN int llvdbg(const char *format, ...);
+int llvdbg(const char *format, ...);
# endif
#endif
#endif /* CONFIG_DEBUG */
#endif /* CONFIG_CPP_HAVE_VARARGS */
-#undef EXTERN
#if defined(__cplusplus)
}
#endif
diff --git a/nuttx/include/elf32.h b/nuttx/include/elf32.h
new file mode 100644
index 000000000..e16ae0091
--- /dev/null
+++ b/nuttx/include/elf32.h
@@ -0,0 +1,352 @@
+/****************************************************************************
+ * include/elf32.h
+ *
+ * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Reference: System V Application Binary Interface, Edition 4.1, March 18,
+ * 1997, The Santa Cruz Operation, Inc.
+ *
+ * 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 __INCLUDE_ELF32_H
+#define __INCLUDE_ELF32_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdint.h>
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/* Values for Elf32_Ehdr::e_type */
+
+#define ET_NONE 0 /* No file type */
+#define ET_REL 1 /* Relocatable file */
+#define ET_EXEC 2 /* Executable file */
+#define ET_DYN 3 /* Shared object file */
+#define ET_CORE 4 /* Core file */
+#define ET_LOPROC 0xff00 /* Processor-specific */
+#define ET_HIPROC 0xffff /* Processor-specific */
+
+/* Values for Elf32_Ehdr::e_machine (most of this were not included in the
+ * original SCO document but have been gleaned from elsewhere).
+ */
+
+#define EM_NONE 0 /* No machine */
+#define EM_M32 1 /* AT&T WE 32100 */
+#define EM_SPARC 2 /* SPARC */
+#define EM_386 3 /* Intel 80386 */
+#define EM_68K 4 /* Motorola 68000 */
+#define EM_88K 5 /* Motorola 88000 */
+#define EM_486 6 /* Intel 486+ */
+#define EM_860 7 /* Intel 80860 */
+#define EM_MIPS 8 /* MIPS R3000 Big-Endian */
+#define EM_MIPS_RS4_BE 10 /* MIPS R4000 Big-Endian */
+#define EM_PARISC 15 /* HPPA */
+#define EM_SPARC32PLUS 18 /* Sun's "v8plus" */
+#define EM_PPC 20 /* PowerPC */
+#define EM_PPC64 21 /* PowerPC64 */
+#define EM_ARM 40 /* ARM */
+#define EM_SH 42 /* SuperH */
+#define EM_SPARCV9 43 /* SPARC v9 64-bit */
+#define EM_IA_64 50 /* HP/Intel IA-64 */
+#define EM_X86_64 62 /* AMD x86-64 */
+#define EM_S390 22 /* IBM S/390 */
+#define EM_CRIS 76 /* Axis Communications 32-bit embedded processor */
+#define EM_V850 87 /* NEC v850 */
+#define EM_M32R 88 /* Renesas M32R */
+#define EM_H8_300 46
+#define EM_ALPHA 0x9026
+#define EM_CYGNUS_V850 0x9080
+#define EM_CYGNUS_M32R 0x9041
+#define EM_S390_OLD 0xa390
+#define EM_FRV 0x5441
+
+/* Values for Elf32_Ehdr::e_version */
+
+#define EV_NONE 0 /* Invalid version */
+#define EV_CURRENT 1 /* The current version */
+
+/* Ehe ELF identifier */
+
+#define EI_MAG0 0 /* File identification */
+#define EI_MAG1 1 /* " " " " */
+#define EI_MAG2 2 /* " " " " */
+#define EI_MAG3 3 /* " " " " */
+#define EI_CLASS 4 /* File class */
+#define EI_DATA 5 /* Data encoding */
+#define EI_VERSION 6 /* File version */
+#define EI_PAD 7 /* Start of padding bytes */
+#define EI_NIDENT 16 /* Size of eident[] */
+
+#define EI_MAGIC_SIZE 4
+#define EI_MAGIC {0x7f, 'E', 'L', 'F'}
+
+/* Values for EI_CLASS */
+
+#define ELFCLASSNONE 0 /* Invalid class */
+#define ELFCLASS32 1 /* 32-bit objects */
+#define ELFCLASS64 2 /* 64-bit objects */
+
+/* Values for EI_DATA */
+
+#define ELFDATANONE 0 /* Invalid data encoding */
+#define ELFDATA2LSB 1 /* Least significant byte occupying the lowest address */
+#define ELFDATA2MSB 2 /* Most significant byte occupying the lowest address */
+
+/* Figure 4-7: Special Section Indexes */
+
+#define SHN_UNDEF 0
+#define SHN_LORESERVE 0xff00
+#define SHN_LOPROC 0xff00
+#define SHN_HIPROC 0xff1f
+#define SHN_ABS 0xfff1
+#define SHN_COMMON 0xfff2
+#define SHN_HIRESERVE 0xffff
+
+/* Figure 4-9: Section Types, sh_type */
+
+#define SHT_NULL 0
+#define SHT_PROGBITS 1
+#define SHT_SYMTAB 2
+#define SHT_STRTAB 3
+#define SHT_RELA 4
+#define SHT_HASH 5
+#define SHT_DYNAMIC 6
+#define SHT_NOTE 7
+#define SHT_NOBITS 8
+#define SHT_REL 9
+#define SHT_SHLIB 10
+#define SHT_DYNSYM 11
+#define SHT_LOPROC 0x70000000
+#define SHT_HIPROC 0x7fffffff
+#define SHT_LOUSER 0x80000000
+#define SHT_HIUSER 0xffffffff
+
+/* Figure 4-11: Section Attribute Flags, sh_flags */
+
+#define SHF_WRITE 1
+#define SHF_ALLOC 2
+#define SHF_EXECINSTR 4
+#define SHF_MASKPROC 0xf0000000
+
+/* Definitions for Elf32_Sym::st_info */
+
+#define ELF32_ST_BIND(i) ((i) >> 4)
+#define ELF32_ST_TYPE(i) ((i) & 0xf)
+#define ELF32_ST_INFO(b,t) (((b) << 4) | ((t) & 0xf))
+
+/* Figure 4-16: Symbol Binding, ELF32_ST_BIND */
+
+#define STB_LOCAL 0
+#define STB_GLOBAL 1
+#define STB_WEAK 2
+#define STB_LOPROC 13
+#define STB_HIPROC 15
+
+/* Figure 4-17: Symbol Types, ELF32_ST_TYPE */
+
+#define STT_NOTYPE 0
+#define STT_OBJECT 1
+#define STT_FUNC 2
+#define STT_SECTION 3
+#define STT_FILE 4
+#define STT_LOPROC 13
+#define STT_HIPROC 15
+
+/* Definitions for Elf32_Rel*::r_info */
+
+#define ELF32_R_SYM(i) ((i) >> 8)
+#define ELF32_R_TYPE(i) ((i) & 0xff)
+#define ELF32_R_INFO(s,t) (((s)<< 8) | ((t) & 0xff))
+
+/* Figure 5-2: Segment Types, p_type */
+
+#define PT_NULL 0
+#define PT_LOAD 1
+#define PT_DYNAMIC 2
+#define PT_INTERP 3
+#define PT_NOTE 4
+#define PT_SHLIB 5
+#define PT_PHDR 6
+#define PT_LOPROC 0x70000000
+#define PT_HIPROC 0x7fffffff
+
+/* Figure 5-3: Segment Flag Bits, p_flags */
+
+#define PF_X 1 /* Execute */
+#define PF_W 2 /* Write */
+#define PF_R 4 /* Read */
+#define PF_MASKPROC 0xf0000000 /* Unspecified */
+
+/* Figure 5-10: Dynamic Array Tags, d_tag */
+
+#define DT_NULL 0 /* d_un=ignored */
+#define DT_NEEDED 1 /* d_un=d_val */
+#define DT_PLTRELSZ 2 /* d_un=d_val */
+#define DT_PLTGOT 3 /* d_un=d_ptr */
+#define DT_HASH 4 /* d_un=d_ptr */
+#define DT_STRTAB 5 /* d_un=d_ptr */
+#define DT_SYMTAB 6 /* d_un=d_ptr */
+#define DT_RELA 7 /* d_un=d_ptr */
+#define DT_RELASZ 8 /* d_un=d_val */
+#define DT_RELAENT 9 /* d_un=d_val */
+#define DT_STRSZ 10 /* d_un=d_val */
+#define DT_SYMENT 11 /* d_un=d_val */
+#define DT_INIT 12 /* d_un=d_ptr */
+#define DT_FINI 13 /* d_un=d_ptr */
+#define DT_SONAME 14 /* d_un=d_val */
+#define DT_RPATH 15 /* d_un=d_val */
+#define DT_SYMBOLIC 16 /* d_un=ignored */
+#define DT_REL 17 /* d_un=d_ptr */
+#define DT_RELSZ 18 /* d_un=d_val */
+#define DT_RELENT 19 /* d_un=d_val */
+#define DT_PLTREL 20 /* d_un=d_val */
+#define DT_DEBUG 21 /* d_un=d_ptr */
+#define DT_TEXTREL 22 /* d_un=ignored */
+#define DT_JMPREL 23 /* d_un=d_ptr */
+#define DT_BINDNOW 24 /* d_un=ignored */
+#define DT_LOPROC 0x70000000 /* d_un=unspecified */
+#define DT_HIPROC 0x7fffffff /* d_un= unspecified */
+
+/****************************************************************************
+ * Public Type Definitions
+ ****************************************************************************/
+
+/* Figure 4.2: 32-Bit Data Types */
+
+typedef uint32_t Elf32_Addr; /* Unsigned program address */
+typedef uint16_t Elf32_Half; /* Unsigned medium integer */
+typedef uint32_t Elf32_Off; /* Unsigned file offset */
+typedef int32_t Elf32_Sword; /* Signed large integer */
+typedef uint32_t Elf32_Word; /* Unsigned large integer */
+
+/* Figure 4-3: ELF Header */
+
+typedef struct
+{
+ unsigned char e_ident[EI_NIDENT];
+ Elf32_Half e_type;
+ Elf32_Half e_machine;
+ Elf32_Word e_version;
+ Elf32_Addr e_entry;
+ Elf32_Off e_phoff;
+ Elf32_Off e_shoff;
+ Elf32_Word e_flags;
+ Elf32_Half e_ehsize;
+ Elf32_Half e_phentsize;
+ Elf32_Half e_phnum;
+ Elf32_Half e_shentsize;
+ Elf32_Half e_shnum;
+ Elf32_Half e_shstrndx;
+} Elf32_Ehdr;
+
+/* Figure 4-8: Section Header */
+
+typedef struct
+{
+ Elf32_Word sh_name;
+ Elf32_Word sh_type;
+ Elf32_Word sh_flags;
+ Elf32_Addr sh_addr;
+ Elf32_Off sh_offset;
+ Elf32_Word sh_size;
+ Elf32_Word sh_link;
+ Elf32_Word sh_info;
+ Elf32_Word sh_addralign;
+ Elf32_Word sh_entsize;
+} Elf32_Shdr;
+
+/* Figure 4-15: Symbol Table Entry */
+
+typedef struct
+{
+ Elf32_Word st_name;
+ Elf32_Addr st_value;
+ Elf32_Word st_size;
+ unsigned char st_info;
+ unsigned char st_other;
+ Elf32_Half st_shndx;
+} Elf32_Sym;
+
+/* Figure 4-19: Relocation Entries */
+
+typedef struct
+{
+ Elf32_Addr r_offset;
+ Elf32_Word r_info;
+} Elf32_Rel;
+
+typedef struct
+{
+ Elf32_Addr r_offset;
+ Elf32_Word r_info;
+ Elf32_Sword r_addend;
+} Elf32_Rela;
+
+/* Figure 5-1: Program Header */
+
+typedef struct
+{
+ Elf32_Word p_type;
+ Elf32_Off p_offset;
+ Elf32_Addr p_vaddr;
+ Elf32_Addr p_paddr;
+ Elf32_Word p_filesz;
+ Elf32_Word p_memsz;
+ Elf32_Word p_flags;
+ Elf32_Word p_align;
+} Elf32_Phdr;
+
+/* Figure 5-9: Dynamic Structure */
+
+typedef struct
+{
+ Elf32_Sword d_tag;
+ union
+ {
+ Elf32_Word d_val;
+ Elf32_Addr d_ptr;
+ } d_un;
+} Elf32_Dyn;
+
+//extern Elf32_Dyn _DYNAMIC[] ;
+
+#endif /* __INCLUDE_ELF32_H */
diff --git a/nuttx/include/net/if.h b/nuttx/include/net/if.h
index e64b58563..1ff8ebc38 100644
--- a/nuttx/include/net/if.h
+++ b/nuttx/include/net/if.h
@@ -52,6 +52,10 @@
#define IF_NAMESIZE 6 /* Newer naming standard */
#define IFHWADDRLEN 6
+#define IFF_RUNNING (1 << 0)
+#define IF_FLAG_IFUP (1 << 0)
+#define IF_FLAG_IFDOWN (2 << 0)
+
/*******************************************************************************************
* Public Type Definitions
*******************************************************************************************/
@@ -72,6 +76,7 @@ struct lifreq
struct sockaddr lifru_hwaddr; /* MAC address */
int lifru_count; /* Number of devices */
int lifru_mtu; /* MTU size */
+ uint8_t lifru_flags; /* Interface flags */
} lifr_ifru;
};
@@ -82,6 +87,7 @@ struct lifreq
#define lifr_hwaddr lifr_ifru.lifru_hwaddr /* MAC address */
#define lifr_mtu lifr_ifru.lifru_mtu /* MTU */
#define lifr_count lifr_ifru.lifru_count /* Number of devices */
+#define lifr_flags lifr_ifru.lifru_flags /* interface flags */
/* This is the older I/F request that should only be used with IPv4. However, since
* NuttX only supports IPv4 or 6 (not both), we can force the older structure to
@@ -101,6 +107,7 @@ struct ifreq
struct sockaddr ifru_hwaddr; /* MAC address */
int ifru_count; /* Number of devices */
int ifru_mtu; /* MTU size */
+ uint8_t ifru_flags; /* Interface flags */
} ifr_ifru;
};
@@ -111,6 +118,7 @@ struct ifreq
#define ifr_hwaddr ifr_ifru.ifru_hwaddr /* MAC address */
#define ifr_mtu ifr_ifru.ifru_mtu /* MTU */
#define ifr_count ifr_ifru.ifru_count /* Number of devices */
+#define ifr_flags ifr_ifru.ifru_flags /* interface flags */
#else /* CONFIG_NET_IPv6 */
@@ -123,6 +131,7 @@ struct ifreq
#define ifr_hwaddr lifr_ifru.lifru_hwaddr /* MAC address */
#define ifr_mtu lifr_ifru.lifru_mtu /* MTU */
#define ifr_count lifr_ifru.lifru_count /* Number of devices */
+#define ifr_flags lifr_ifru.lifru_flags /* interface flags */
#endif /* CONFIG_NET_IPv6 */
diff --git a/nuttx/include/nuttx/arch.h b/nuttx/include/nuttx/arch.h
index bf6be1ce0..8b4b10ade 100644
--- a/nuttx/include/nuttx/arch.h
+++ b/nuttx/include/nuttx/arch.h
@@ -46,6 +46,7 @@
#include <stdint.h>
#include <stdbool.h>
#include <sched.h>
+
#include <arch/arch.h>
/****************************************************************************
@@ -67,10 +68,8 @@ typedef CODE void (*sig_deliver_t)(FAR _TCB *tcb);
****************************************************************************/
#ifdef __cplusplus
-#define EXTERN extern "C"
-extern "C" {
-#else
-#define EXTERN extern
+extern "C"
+{
#endif
/****************************************************************************
@@ -98,7 +97,7 @@ extern "C" {
*
****************************************************************************/
-EXTERN void up_initialize(void);
+void up_initialize(void);
/****************************************************************************
* Name: up_idle
@@ -114,7 +113,7 @@ EXTERN void up_initialize(void);
*
****************************************************************************/
-EXTERN void up_idle(void);
+void up_idle(void);
/****************************************************************************
* Name: up_initial_state
@@ -130,7 +129,7 @@ EXTERN void up_idle(void);
*
****************************************************************************/
-EXTERN void up_initial_state(FAR _TCB *tcb);
+void up_initial_state(FAR _TCB *tcb);
/****************************************************************************
* Name: up_create_stack
@@ -155,7 +154,7 @@ EXTERN void up_initial_state(FAR _TCB *tcb);
****************************************************************************/
#ifndef CONFIG_CUSTOM_STACK
-EXTERN int up_create_stack(FAR _TCB *tcb, size_t stack_size);
+int up_create_stack(FAR _TCB *tcb, size_t stack_size);
#endif
/****************************************************************************
@@ -180,7 +179,7 @@ EXTERN int up_create_stack(FAR _TCB *tcb, size_t stack_size);
****************************************************************************/
#ifndef CONFIG_CUSTOM_STACK
-EXTERN int up_use_stack(FAR _TCB *tcb, FAR void *stack, size_t stack_size);
+int up_use_stack(FAR _TCB *tcb, FAR void *stack, size_t stack_size);
#endif
/****************************************************************************
@@ -193,7 +192,7 @@ EXTERN int up_use_stack(FAR _TCB *tcb, FAR void *stack, size_t stack_size);
****************************************************************************/
#ifndef CONFIG_CUSTOM_STACK
-EXTERN void up_release_stack(FAR _TCB *dtcb);
+void up_release_stack(FAR _TCB *dtcb);
#endif
/****************************************************************************
@@ -216,7 +215,7 @@ EXTERN void up_release_stack(FAR _TCB *dtcb);
*
****************************************************************************/
-EXTERN void up_unblock_task(FAR _TCB *tcb);
+void up_unblock_task(FAR _TCB *tcb);
/****************************************************************************
* Name: up_block_task
@@ -242,7 +241,7 @@ EXTERN void up_unblock_task(FAR _TCB *tcb);
*
****************************************************************************/
-EXTERN void up_block_task(FAR _TCB *tcb, tstate_t task_state);
+void up_block_task(FAR _TCB *tcb, tstate_t task_state);
/****************************************************************************
* Name: up_release_pending
@@ -261,7 +260,7 @@ EXTERN void up_block_task(FAR _TCB *tcb, tstate_t task_state);
*
****************************************************************************/
-EXTERN void up_release_pending(void);
+void up_release_pending(void);
/****************************************************************************
* Name: up_reprioritize_rtr
@@ -287,7 +286,7 @@ EXTERN void up_release_pending(void);
*
****************************************************************************/
-EXTERN void up_reprioritize_rtr(FAR _TCB *tcb, uint8_t priority);
+void up_reprioritize_rtr(FAR _TCB *tcb, uint8_t priority);
/****************************************************************************
* Name: _exit
@@ -349,7 +348,7 @@ EXTERN void up_reprioritize_rtr(FAR _TCB *tcb, uint8_t priority);
****************************************************************************/
#ifndef CONFIG_DISABLE_SIGNALS
-EXTERN void up_schedule_sigaction(FAR _TCB *tcb, sig_deliver_t sigdeliver);
+void up_schedule_sigaction(FAR _TCB *tcb, sig_deliver_t sigdeliver);
#endif
/****************************************************************************
@@ -363,7 +362,7 @@ EXTERN void up_schedule_sigaction(FAR _TCB *tcb, sig_deliver_t sigdeliver);
****************************************************************************/
#ifndef CONFIG_HEAP_BASE
-EXTERN void up_allocate_heap(FAR void **heap_start, size_t *heap_size);
+void up_allocate_heap(FAR void **heap_start, size_t *heap_size);
#endif
/****************************************************************************
@@ -383,6 +382,214 @@ EXTERN void up_allocate_heap(FAR void **heap_start, size_t *heap_size);
#endif
/****************************************************************************
+ * Address Environment Interfaces
+ *
+ * Low-level interfaces used in binfmt/ to instantiate tasks with address
+ * environments. These interfaces all operate on type task_addrenv_t which
+ * is an abstract representation of a task's address environment and must be
+ * defined in arch/arch.h if CONFIG_ADDRENV is defined.
+ *
+ * up_addrenv_create - Create an address environment
+ * up_addrenv_vaddr - Returns the virtual base address of the address
+ * environment
+ * up_addrenv_select - Instantiate an address environment
+ * up_addrenv_restore - Restore an address environment
+ * up_addrenv_destroy - Destroy an address environment.
+ * up_addrenv_assign - Assign an address environment to a TCB
+ *
+ * Higher-level interfaces used by the tasking logic. These interfaces are
+ * used by the functions in sched/ and all operate on the TCB which as been
+ * assigned an address environment by up_addrenv_assign().
+ *
+ * up_addrenv_share - Clone the address environment assigned to one TCB
+ * to another. This operation is done when a pthread
+ * is created that share's the same address
+ * environment.
+ * up_addrenv_release - Release the TCBs reference to an address
+ * environment when a task/thread exits.
+ *
+ ****************************************************************************/
+/****************************************************************************
+ * Name: up_addrenv_create
+ *
+ * Description:
+ * This function is called from the binary loader logic when a new
+ * task is created in order to instantiate an address environment for the
+ * task. up_addrenv_create is essentially the allocator of the physical
+ * memory for the new task.
+ *
+ * Input Parameters:
+ * envsize - The size (in bytes) of the address environment needed by the
+ * task.
+ * addrenv - The location to return the representation of the task address
+ * environment.
+ *
+ * Returned Value:
+ * Zero (OK) on success; a negated errno value on failure.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_ADDRENV
+int up_addrenv_create(size_t envsize, FAR task_addrenv_t *addrenv);
+#endif
+
+/****************************************************************************
+ * Name: up_addrenv_vaddr
+ *
+ * Description:
+ * Return the virtual address associated with the newly create address
+ * environment. This function is used by the binary loaders in order
+ * get an address that can be used to initialize the new task.
+ *
+ * Input Parameters:
+ * addrenv - The representation of the task address environment previously
+ * returned by up_addrenv_create.
+ * vaddr - The location to return the virtual address.
+ *
+ * Returned Value:
+ * Zero (OK) on success; a negated errno value on failure.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_ADDRENV
+int up_addrenv_vaddr(FAR task_addrenv_t addrenv, FAR void **vaddr);
+#endif
+
+/****************************************************************************
+ * Name: up_addrenv_select
+ *
+ * Description:
+ * After an address environment has been established for a task (via
+ * up_addrenv_create(). This function may be called to to instantiate
+ * that address environment in the virtual address space. this might be
+ * necessary, for example, to load the code for the task from a file or
+ * to access address environment private data.
+ *
+ * Input Parameters:
+ * addrenv - The representation of the task address environment previously
+ * returned by up_addrenv_create.
+ * oldenv
+ * The address environment that was in place before up_addrenv_select().
+ * This may be used with up_addrenv_restore() to restore the original
+ * address environment that was in place before up_addrenv_select() was
+ * called. Note that this may be a task agnostic, hardware
+ * representation that is different from task_addrenv_t.
+ *
+ * Returned Value:
+ * Zero (OK) on success; a negated errno value on failure.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_ADDRENV
+int up_addrenv_select(task_addrenv_t addrenv, hw_addrenv_t *oldenv);
+#endif
+
+/****************************************************************************
+ * Name: up_addrenv_restore
+ *
+ * Description:
+ * After an address environment has been temporarilty instantiated by
+ * up_addrenv_select, this function may be called to to restore the
+ * original address environment.
+ *
+ * Input Parameters:
+ * oldenv - The hardware representation of the address environment
+ * previously returned by up_addrenv_select.
+ *
+ * Returned Value:
+ * Zero (OK) on success; a negated errno value on failure.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_ADDRENV
+int up_addrenv_restore(hw_addrenv_t oldenv);
+#endif
+
+/****************************************************************************
+ * Name: up_addrenv_destroy
+ *
+ * Description:
+ * Called from the binary loader loader during error handling to destroy
+ * the address environment previously created by up_addrenv_create().
+ *
+ * Input Parameters:
+ * addrenv - The representation of the task address environment previously
+ * returned by up_addrenv_create.
+ *
+ * Returned Value:
+ * Zero (OK) on success; a negated errno value on failure.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_ADDRENV
+int up_addrenv_destroy(task_addrenv_t addrenv);
+#endif
+
+/****************************************************************************
+ * Name: up_addrenv_assign
+ *
+ * Description:
+ * Assign an address environment to a TCB.
+ *
+ * Input Parameters:
+ * addrenv - The representation of the task address environment previously
+ * returned by up_addrenv_create.
+ * tcb - The TCB of the task to receive the address environment.
+ *
+ * Returned Value:
+ * Zero (OK) on success; a negated errno value on failure.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_ADDRENV
+int up_addrenv_assign(task_addrenv_t addrenv, FAR _TCB *tcb);
+#endif
+
+/****************************************************************************
+ * Name: up_addrenv_share
+ *
+ * Description:
+ * This function is called from the core scheduler logic when a thread
+ * is created that needs to share the address ennvironment of its parent
+ * task. In this case, the parent's address environment needs to be
+ * "cloned" for the child.
+ *
+ * Input Parameters:
+ * ptcb - The TCB of the parent task that has the address environment.
+ * ctcb - The TCB of the child thread needing the address environment.
+ *
+ * Returned Value:
+ * Zero (OK) on success; a negated errno value on failure.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_ADDRENV
+int up_addrenv_share(FAR const _TCB *ptcb, FAR _TCB *ctcb);
+#endif
+
+/****************************************************************************
+ * Name: up_addrenv_release
+ *
+ * Description:
+ * This function is called when a task or thread exits in order to release
+ * its reference to an address environment. When there are no further
+ * references to an address environment, that address environment should
+ * be destroyed.
+ *
+ * Input Parameters:
+ * tcb - The TCB of the task or thread whose the address environment will
+ * be released.
+ *
+ * Returned Value:
+ * Zero (OK) on success; a negated errno value on failure.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_ADDRENV
+int up_addrenv_release(FAR _TCB *tcb);
+#endif
+
+/****************************************************************************
* Name: up_interrupt_context
*
* Description:
@@ -391,7 +598,7 @@ EXTERN void up_allocate_heap(FAR void **heap_start, size_t *heap_size);
*
****************************************************************************/
-EXTERN bool up_interrupt_context(void);
+bool up_interrupt_context(void);
/****************************************************************************
* Name: up_enable_irq
@@ -413,7 +620,7 @@ EXTERN bool up_interrupt_context(void);
****************************************************************************/
#ifndef CONFIG_ARCH_NOINTC
-EXTERN void up_enable_irq(int irq);
+void up_enable_irq(int irq);
#endif
/****************************************************************************
@@ -431,7 +638,7 @@ EXTERN void up_enable_irq(int irq);
****************************************************************************/
#ifndef CONFIG_ARCH_NOINTC
-EXTERN void up_disable_irq(int irq);
+void up_disable_irq(int irq);
#endif
/****************************************************************************
@@ -446,7 +653,7 @@ EXTERN void up_disable_irq(int irq);
****************************************************************************/
#ifdef CONFIG_ARCH_IRQPRIO
-EXTERN int up_prioritize_irq(int irq, int priority);
+int up_prioritize_irq(int irq, int priority);
#endif
/****************************************************************************
@@ -483,7 +690,7 @@ EXTERN int up_prioritize_irq(int irq, int priority);
****************************************************************************/
#ifdef CONFIG_ARCH_ROMGETC
-EXTERN char up_romgetc(FAR const char *ptr);
+char up_romgetc(FAR const char *ptr);
#else
# define up_romgetc(ptr) (*ptr)
#endif
@@ -497,8 +704,8 @@ EXTERN char up_romgetc(FAR const char *ptr);
*
***************************************************************************/
-EXTERN void up_mdelay(unsigned int milliseconds);
-EXTERN void up_udelay(useconds_t microseconds);
+void up_mdelay(unsigned int milliseconds);
+void up_udelay(useconds_t microseconds);
/****************************************************************************
* Name: up_cxxinitialize
@@ -517,7 +724,7 @@ EXTERN void up_udelay(useconds_t microseconds);
***************************************************************************/
#if defined(CONFIG_HAVE_CXX) && defined(CONFIG_HAVE_CXXINITIALIZE)
-EXTERN void up_cxxinitialize(void);
+void up_cxxinitialize(void);
#endif
/****************************************************************************
@@ -537,7 +744,7 @@ EXTERN void up_cxxinitialize(void);
*
****************************************************************************/
-EXTERN void sched_process_timer(void);
+void sched_process_timer(void);
/****************************************************************************
* Name: irq_dispatch
@@ -549,7 +756,7 @@ EXTERN void sched_process_timer(void);
*
***************************************************************************/
-EXTERN void irq_dispatch(int irq, FAR void *context);
+void irq_dispatch(int irq, FAR void *context);
/****************************************************************************
* Board-specific button interfaces exported by the board-specific logic
@@ -571,7 +778,7 @@ EXTERN void irq_dispatch(int irq, FAR void *context);
****************************************************************************/
#ifdef CONFIG_ARCH_BUTTONS
-EXTERN void up_buttoninit(void);
+void up_buttoninit(void);
#endif
/****************************************************************************
@@ -592,7 +799,7 @@ EXTERN void up_buttoninit(void);
****************************************************************************/
#ifdef CONFIG_ARCH_BUTTONS
-EXTERN uint8_t up_buttons(void);
+uint8_t up_buttons(void);
#endif
/****************************************************************************
@@ -613,7 +820,29 @@ EXTERN uint8_t up_buttons(void);
****************************************************************************/
#ifdef CONFIG_ARCH_IRQBUTTONS
-EXTERN xcpt_t up_irqbutton(int id, xcpt_t irqhandler);
+xcpt_t up_irqbutton(int id, xcpt_t irqhandler);
+#endif
+
+/************************************************************************************
+ * Relay control functions
+ *
+ * Description:
+ * Non-standard functions for relay control.
+ *
+ ************************************************************************************/
+
+#ifdef CONFIG_ARCH_RELAYS
+void up_relaysinit(void);
+void relays_setstat(int relays, bool stat);
+bool relays_getstat(int relays);
+void relays_setstats(uint32_t relays_stat);
+uint32_t relays_getstats(void);
+void relays_onoff(int relays, uint32_t mdelay);
+void relays_onoffs(uint32_t relays_stat, uint32_t mdelay);
+void relays_resetmode(int relays);
+void relays_powermode(int relays);
+void relays_resetmodes(uint32_t relays_stat);
+void relays_powermodes(uint32_t relays_stat);
#endif
/****************************************************************************
@@ -628,9 +857,8 @@ EXTERN xcpt_t up_irqbutton(int id, xcpt_t irqhandler);
*
****************************************************************************/
-EXTERN int up_putc(int ch);
+int up_putc(int ch);
-#undef EXTERN
#ifdef __cplusplus
}
#endif
diff --git a/nuttx/include/nuttx/binfmt.h b/nuttx/include/nuttx/binfmt/binfmt.h
index 70beda393..6df5190d2 100644
--- a/nuttx/include/nuttx/binfmt.h
+++ b/nuttx/include/nuttx/binfmt/binfmt.h
@@ -1,7 +1,7 @@
/****************************************************************************
- * include/nuttx/binfmt.h
+ * include/nuttx/binfmt/binfmt.h
*
- * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2009, 2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -33,34 +33,58 @@
*
****************************************************************************/
-#ifndef __INCLUDE_NUTTX_BINFMT_H
-#define __INCLUDE_NUTTX_BINFMT_H
+#ifndef __INCLUDE_NUTTX_BINFMT_BINFMT_H
+#define __INCLUDE_NUTTX_BINFMT_BINFMT_H
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
+
#include <sys/types.h>
#include <nxflat.h>
+
+#include <nuttx/arch.h>
#include <nuttx/sched.h>
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
+#define BINFMT_NALLOC 3
+
/****************************************************************************
* Public Types
****************************************************************************/
+/* EXEPATH_HANDLE is an opaque handle used to traverse the absolute paths
+ * assigned to the PATH environment variable.
+ */
+
+#if !defined(CONFIG_BINFMT_DISABLE) && defined(CONFIG_BINFMT_EXEPATH)
+typedef FAR void *EXEPATH_HANDLE;
+#endif
+
+/* The type of one C++ constructor or destructor */
+
+typedef FAR void (*binfmt_ctor_t)(void);
+typedef FAR void (*binfmt_dtor_t)(void);
-/* This describes the file to be loaded */
+/* This describes the file to be loaded.
+ *
+ * NOTE 1: The 'filename' must be the full, absolute path to the file to be
+ * executed unless CONFIG_BINFMT_EXEPATH is defined. In that case,
+ * 'filename' may be a relative path; a set of candidate absolute paths
+ * will be generated using the PATH environment variable and load_module()
+ * will attempt to load each file that is found at those absolute paths.
+ */
struct symtab_s;
struct binary_s
{
/* Information provided to the loader to load and bind a module */
- FAR const char *filename; /* Full path to the binary to be loaded */
+ FAR const char *filename; /* Full path to the binary to be loaded (See NOTE 1 above) */
FAR const char **argv; /* Argument list */
FAR const struct symtab_s *exports; /* Table of exported symbols */
int nexports; /* The number of symbols in exports[] */
@@ -70,9 +94,29 @@ struct binary_s
*/
main_t entrypt; /* Entry point into a program module */
- FAR void *ispace; /* Memory-mapped, I-space (.text) address */
- FAR struct dspace_s *dspace; /* Address of the allocated .data/.bss space */
- size_t isize; /* Size of the I-space region (needed for munmap) */
+ FAR void *mapped; /* Memory-mapped, address space */
+ FAR void *alloc[BINFMT_NALLOC]; /* Allocated address spaces */
+
+ /* Constructors/destructors */
+
+#ifdef CONFIG_BINFMT_CONSTRUCTORS
+ FAR binfmt_ctor_t *ctors; /* Pointer to a list of constructors */
+ FAR binfmt_dtor_t *dtors; /* Pointer to a list of destructors */
+ uint16_t nctors; /* Number of constructors in the list */
+ uint16_t ndtors; /* Number of destructors in the list */
+#endif
+
+ /* Address environment.
+ *
+ * addrenv - This is the handle created by up_addrenv_create() that can be
+ * used to manage the tasks address space.
+ */
+
+#ifdef CONFIG_ADDRENV
+ task_addrenv_t addrenv; /* Task address environment */
+#endif
+
+ size_t mapsize; /* Size of the mapped address region (needed for munmap) */
size_t stacksize; /* Size of the stack in bytes (unallocated) */
};
@@ -88,12 +132,9 @@ struct binfmt_s
* Public Data
****************************************************************************/
-#undef EXTERN
#if defined(__cplusplus)
-#define EXTERN extern "C"
-extern "C" {
-#else
-#define EXTERN extern
+extern "C"
+{
#endif
/****************************************************************************
@@ -113,7 +154,7 @@ extern "C" {
*
****************************************************************************/
-EXTERN int register_binfmt(FAR struct binfmt_s *binfmt);
+int register_binfmt(FAR struct binfmt_s *binfmt);
/****************************************************************************
* Name: unregister_binfmt
@@ -128,7 +169,7 @@ EXTERN int register_binfmt(FAR struct binfmt_s *binfmt);
*
****************************************************************************/
-EXTERN int unregister_binfmt(FAR struct binfmt_s *binfmt);
+int unregister_binfmt(FAR struct binfmt_s *binfmt);
/****************************************************************************
* Name: load_module
@@ -144,14 +185,19 @@ EXTERN int unregister_binfmt(FAR struct binfmt_s *binfmt);
*
****************************************************************************/
-EXTERN int load_module(FAR struct binary_s *bin);
+int load_module(FAR struct binary_s *bin);
/****************************************************************************
* Name: unload_module
*
* Description:
* Unload a (non-executing) module from memory. If the module has
- * been started (via exec_module), calling this will be fatal.
+ * been started (via exec_module) and has not exited, calling this will
+ * be fatal.
+ *
+ * However, this function must be called after the module exist. How
+ * this is done is up to your logic. Perhaps you register it to be
+ * called by on_exit()?
*
* Returned Value:
* This is a NuttX internal function so it follows the convention that
@@ -160,7 +206,7 @@ EXTERN int load_module(FAR struct binary_s *bin);
*
****************************************************************************/
-EXTERN int unload_module(FAR const struct binary_s *bin);
+int unload_module(FAR const struct binary_s *bin);
/****************************************************************************
* Name: exec_module
@@ -175,7 +221,7 @@ EXTERN int unload_module(FAR const struct binary_s *bin);
*
****************************************************************************/
-EXTERN int exec_module(FAR const struct binary_s *bin, int priority);
+int exec_module(FAR const struct binary_s *bin, int priority);
/****************************************************************************
* Name: exec
@@ -197,13 +243,96 @@ EXTERN int exec_module(FAR const struct binary_s *bin, int priority);
*
****************************************************************************/
-EXTERN int exec(FAR const char *filename, FAR const char **argv,
- FAR const struct symtab_s *exports, int nexports);
+int exec(FAR const char *filename, FAR const char **argv,
+ FAR const struct symtab_s *exports, int nexports);
+
+/****************************************************************************
+ * Name: exepath_init
+ *
+ * Description:
+ * Initialize for the traversal of each value in the PATH variable. The
+ * usage is sequence is as follows:
+ *
+ * 1) Call exepath_init() to initialize for the traversal. exepath_init()
+ * will return an opaque handle that can then be provided to
+ * exepath_next() and exepath_release().
+ * 2) Call exepath_next() repeatedly to examine every file that lies
+ * in the directories of the PATH variable
+ * 3) Call exepath_release() to free resources set aside by exepath_init().
+ *
+ * Input Parameters:
+ * None
+ *
+ * Returned Value:
+ * On success, exepath_init() return a non-NULL, opaque handle that may
+ * subsequently be used in calls to exepath_next() and exepath_release().
+ * On error, a NULL handle value will be returned. The most likely cause
+ * of an error would be that the there is no value associated with the
+ * PATH variable.
+ *
+ ****************************************************************************/
+
+#if !defined(CONFIG_BINFMT_DISABLE) && defined(CONFIG_BINFMT_EXEPATH)
+EXEPATH_HANDLE exepath_init(void);
+#endif
+
+/****************************************************************************
+ * Name: exepath_next
+ *
+ * Description:
+ * Traverse all possible values in the PATH variable in attempt to find
+ * the full path to an executable file when only a relative path is
+ * provided.
+ *
+ * Input Parameters:
+ * handle - The handle value returned by exepath_init
+ * relpath - The relative path to the file to be found.
+ *
+ * Returned Value:
+ * On success, a non-NULL pointer to a null-terminated string is provided.
+ * This is the full path to a file that exists in the file system. This
+ * function will verify that the file exists (but will not verify that it
+ * is marked executable).
+ *
+ * NOTE: The string pointer return in the success case points to allocated
+ * memory. This memory must be freed by the called by calling kfree().
+ *
+ * NULL is returned if no path is found to any file with the provided
+ * 'relpath' from any absolute path in the PATH variable. In this case,
+ * there is no point in calling exepath_next() further; exepath_release()
+ * must be called to release resources set aside by expath_init().
+ *
+ ****************************************************************************/
+
+#if !defined(CONFIG_BINFMT_DISABLE) && defined(CONFIG_BINFMT_EXEPATH)
+FAR char *exepath_next(EXEPATH_HANDLE handle, FAR const char *relpath);
+#endif
+
+/****************************************************************************
+ * Name: exepath_release
+ *
+ * Description:
+ * Release all resources set aside by exepath_init() when the handle value
+ * was created. The handle value is invalid on return from this function.
+ * Attempts to all exepath_next() or exepath_release() with such a 'stale'
+ * handle will result in undefined (i.e., not good) behavior.
+ *
+ * Input Parameters:
+ * handle - The handle value returned by exepath_init
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+#if !defined(CONFIG_BINFMT_DISABLE) && defined(CONFIG_BINFMT_EXEPATH)
+void exepath_release(EXEPATH_HANDLE handle);
+#endif
#undef EXTERN
#if defined(__cplusplus)
}
#endif
-#endif /* __INCLUDE_NUTTX_BINFMT_H */
+#endif /* __INCLUDE_NUTTX_BINFMT_BINFMT_H */
diff --git a/nuttx/include/nuttx/binfmt/elf.h b/nuttx/include/nuttx/binfmt/elf.h
new file mode 100644
index 000000000..6b6851934
--- /dev/null
+++ b/nuttx/include/nuttx/binfmt/elf.h
@@ -0,0 +1,340 @@
+/****************************************************************************
+ * include/nuttx/binfmt/elf.h
+ *
+ * Copyright (C) 2012 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 __INCLUDE_NUTTX_BINFMT_ELF_H
+#define __INCLUDE_NUTTX_BINFMT_ELF_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+
+#include <stdint.h>
+#include <stdbool.h>
+#include <elf32.h>
+
+#include <nuttx/binfmt/binfmt.h>
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+/* Configuration ************************************************************/
+
+#ifndef CONFIG_ELF_ALIGN_LOG2
+# define CONFIG_ELF_ALIGN_LOG2 2
+#endif
+
+#ifndef CONFIG_ELF_STACKSIZE
+# define CONFIG_ELF_STACKSIZE 2048
+#endif
+
+#ifndef CONFIG_ELF_BUFFERSIZE
+# define CONFIG_ELF_BUFFERSIZE 128
+#endif
+
+#ifndef CONFIG_ELF_BUFFERINCR
+# define CONFIG_ELF_BUFFERINCR 32
+#endif
+
+/* Allocation array size and indices */
+
+#define LIBELF_ELF_ALLOC 0
+#ifdef CONFIG_BINFMT_CONSTRUCTORS
+# define LIBELF_CTORS_ALLOC 1
+# define LIBELF_CTPRS_ALLOC 2
+# define LIBELF_NALLOC 3
+#else
+# define LIBELF_NALLOC 1
+#endif
+
+/****************************************************************************
+ * Public Types
+ ****************************************************************************/
+
+/* This struct provides a desciption of the currently loaded instantiation
+ * of an ELF binary.
+ */
+
+struct elf_loadinfo_s
+{
+ /* elfalloc is the base address of the memory that is allocated to hold the
+ * ELF program image.
+ *
+ * If CONFIG_ADDRENV=n, elfalloc will be allocated using kmalloc() (or
+ * kzalloc()). If CONFIG_ADDRENV-y, then elfalloc will be allocated using
+ * up_addrenv_create(). In either case, there will be a unique instance
+ * of elfalloc (and stack) for each instance of a process.
+ *
+ * The alloc[] array in struct binary_s will hold memory that persists after
+ * the ELF module has been loaded.
+ */
+
+ uintptr_t elfalloc; /* Memory allocated when ELF file was loaded */
+ size_t elfsize; /* Size of the ELF memory allocation */
+ off_t filelen; /* Length of the entire ELF file */
+ Elf32_Ehdr ehdr; /* Buffered ELF file header */
+ FAR Elf32_Shdr *shdr; /* Buffered ELF section headers */
+ uint8_t *iobuffer; /* File I/O buffer */
+
+ /* Constructors and destructors */
+
+#ifdef CONFIG_BINFMT_CONSTRUCTORS
+ FAR void *ctoralloc; /* Memory allocated for ctors */
+ FAR void *dtoralloc; /* Memory allocated dtors */
+ FAR binfmt_ctor_t *ctors; /* Pointer to a list of constructors */
+ FAR binfmt_dtor_t *dtors; /* Pointer to a list of destructors */
+ uint16_t nctors; /* Number of constructors */
+ uint16_t ndtors; /* Number of destructors */
+#endif
+
+ /* Address environment.
+ *
+ * addrenv - This is the handle created by up_addrenv_create() that can be
+ * used to manage the tasks address space.
+ * oldenv - This is a value returned by up_addrenv_select() that must be
+ * used to restore the current hardware address environment.
+ */
+
+#ifdef CONFIG_ADDRENV
+ task_addrenv_t addrenv; /* Task address environment */
+ hw_addrenv_t oldenv; /* Saved hardware address environment */
+#endif
+
+ uint16_t symtabidx; /* Symbol table section index */
+ uint16_t strtabidx; /* String table section index */
+ uint16_t buflen; /* size of iobuffer[] */
+ int filfd; /* Descriptor for the file being loaded */
+};
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+#undef EXTERN
+#if defined(__cplusplus)
+#define EXTERN extern "C"
+extern "C" {
+#else
+#define EXTERN extern
+#endif
+
+/****************************************************************************
+ * These are APIs exported by libelf (but are used only by the binfmt logic):
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: elf_init
+ *
+ * Description:
+ * This function is called to configure the library to process an ELF
+ * program binary.
+ *
+ * Returned Value:
+ * 0 (OK) is returned on success and a negated errno is returned on
+ * failure.
+ *
+ ****************************************************************************/
+
+EXTERN int elf_init(FAR const char *filename,
+ FAR struct elf_loadinfo_s *loadinfo);
+
+/****************************************************************************
+ * Name: elf_uninit
+ *
+ * Description:
+ * Releases any resources committed by elf_init(). This essentially
+ * undoes the actions of elf_init.
+ *
+ * Returned Value:
+ * 0 (OK) is returned on success and a negated errno is returned on
+ * failure.
+ *
+ ****************************************************************************/
+
+EXTERN int elf_uninit(FAR struct elf_loadinfo_s *loadinfo);
+
+/****************************************************************************
+ * Name: elf_load
+ *
+ * Description:
+ * Loads the binary into memory, allocating memory, performing relocations
+ * and inializing the data and bss segments.
+ *
+ * Returned Value:
+ * 0 (OK) is returned on success and a negated errno is returned on
+ * failure.
+ *
+ ****************************************************************************/
+
+EXTERN int elf_load(FAR struct elf_loadinfo_s *loadinfo);
+
+/****************************************************************************
+ * Name: elf_bind
+ *
+ * Description:
+ * Bind the imported symbol names in the loaded module described by
+ * 'loadinfo' using the exported symbol values provided by 'symtab'.
+ *
+ * Returned Value:
+ * 0 (OK) is returned on success and a negated errno is returned on
+ * failure.
+ *
+ ****************************************************************************/
+
+struct symtab_s;
+EXTERN int elf_bind(FAR struct elf_loadinfo_s *loadinfo,
+ FAR const struct symtab_s *exports, int nexports);
+
+/****************************************************************************
+ * Name: elf_unload
+ *
+ * Description:
+ * This function unloads the object from memory. This essentially undoes
+ * the actions of elf_load. It is called only under certain error
+ * conditions after the the module has been loaded but not yet started.
+ *
+ * Returned Value:
+ * 0 (OK) is returned on success and a negated errno is returned on
+ * failure.
+ *
+ ****************************************************************************/
+
+EXTERN int elf_unload(struct elf_loadinfo_s *loadinfo);
+
+/****************************************************************************
+ * These are APIs used outside of binfmt by NuttX:
+ ****************************************************************************/
+/****************************************************************************
+ * Name: elf_initialize
+ *
+ * Description:
+ * ELF support is built unconditionally. However, it order to
+ * use this binary format, this function must be called during system
+ * format in order to register the ELF binary format.
+ *
+ * Returned Value:
+ * This is a NuttX internal function so it follows the convention that
+ * 0 (OK) is returned on success and a negated errno is returned on
+ * failure.
+ *
+ ****************************************************************************/
+
+EXTERN int elf_initialize(void);
+
+/****************************************************************************
+ * Name: elf_uninitialize
+ *
+ * Description:
+ * Unregister the ELF binary loader
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+EXTERN void elf_uninitialize(void);
+
+/****************************************************************************
+ * These are APIs must be provided by architecture-specific logic:
+ ****************************************************************************/
+/****************************************************************************
+ * Name: arch_checkarch
+ *
+ * Description:
+ * Given the ELF header in 'hdr', verify that the ELF file is appropriate
+ * for the current, configured architecture. Every architecture that uses
+ * the ELF loader must provide this function.
+ *
+ * Input Parameters:
+ * hdr - The ELF header read from the ELF file.
+ *
+ * Returned Value:
+ * True if the architecture supports this ELF file.
+ *
+ ****************************************************************************/
+
+EXTERN bool arch_checkarch(FAR const Elf32_Ehdr *hdr);
+
+/****************************************************************************
+ * Name: arch_relocate and arch_relocateadd
+ *
+ * Description:
+ * Perform on architecture-specific ELF relocation. Every architecture
+ * that uses the ELF loader must provide this function.
+ *
+ * Input Parameters:
+ * rel - The relocation type
+ * sym - The ELF symbol structure containing the fully resolved value.
+ * addr - The address that requires the relocation.
+ *
+ * Returned Value:
+ * Zero (OK) if the relocation was successful. Otherwise, a negated errno
+ * value indicating the cause of the relocation failure.
+ *
+ ****************************************************************************/
+
+EXTERN int arch_relocate(FAR const Elf32_Rel *rel, FAR const Elf32_Sym *sym,
+ uintptr_t addr);
+EXTERN int arch_relocateadd(FAR const Elf32_Rela *rel,
+ FAR const Elf32_Sym *sym, uintptr_t addr);
+
+/****************************************************************************
+ * Name: arch_flushicache
+ *
+ * Description:
+ * Flush the instruction cache.
+ *
+ * Input Parameters:
+ * addr - Start address to flush
+ * len - Number of bytes to flush
+ *
+ * Returned Value:
+ * True if the architecture supports this ELF file.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_ELF_ICACHE
+EXTERN bool arch_flushicache(FAR void *addr, size_t len);
+#endif
+
+#undef EXTERN
+#if defined(__cplusplus)
+}
+#endif
+
+#endif /* __INCLUDE_NUTTX_BINFMT_ELF_H */
diff --git a/nuttx/include/nuttx/nxflat.h b/nuttx/include/nuttx/binfmt/nxflat.h
index b6501522e..db396771b 100644
--- a/nuttx/include/nuttx/nxflat.h
+++ b/nuttx/include/nuttx/binfmt/nxflat.h
@@ -1,7 +1,7 @@
/****************************************************************************
- * include/nuttx/nxflat.h
+ * include/nuttx/binfmt/nxflat.h
*
- * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2009, 2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -33,8 +33,8 @@
*
****************************************************************************/
-#ifndef __INCLUDE_NUTTX_NXFLAT_H
-#define __INCLUDE_NUTTX_NXFLAT_H
+#ifndef __INCLUDE_NUTTX_BINFMT_NXFLAT_H
+#define __INCLUDE_NUTTX_BINFMT_NXFLAT_H
/****************************************************************************
* Included Files
@@ -44,7 +44,9 @@
#include <stdint.h>
#include <nxflat.h>
+
#include <nuttx/sched.h>
+#include <nuttx/arch.h>
/****************************************************************************
* Pre-processor Definitions
@@ -61,17 +63,24 @@
struct nxflat_loadinfo_s
{
/* Instruction Space (ISpace): This region contains the nxflat file header
- * plus everything from the text section. Ideally, will have only one mmap'ed
- * text section instance in the system for each module.
+ * plus everything from the text section.
+ *
+ * The ISpace region is allocated using mmap() and, thus, can be shared by
+ * multiple tasks. Ideally, will have only one mmap'ed text section
+ * instance in the system for each module.
*/
- uint32_t ispace; /* Address where hdr/text is loaded */
+ uintptr_t ispace; /* Address where hdr/text is loaded */
uint32_t entryoffs; /* Offset from ispace to entry point */
uint32_t isize; /* Size of ispace. */
- /* Data Space (DSpace): This region contains all information that in referenced
- * as data (other than the stack which is separately allocated). There will be
- * a unique instance of DSpace (and stack) for each instance of a process.
+ /* Data Space (DSpace): This region contains all information that is
+ * referenced as data (other than the stack which is separately allocated).
+ *
+ * If CONFIG_ADDRENV=n, DSpace will be allocated using kmalloc() (or
+ * kzalloc()). If CONFIG_ADDRENV-y, then DSpace will be allocated using
+ * up_addrenv_create(). In either case, there will be a unique instance
+ * of DSpace (and stack) for each instance of a process.
*/
struct dspace_s *dspace; /* Allocated D-Space (data/bss/etc) */
@@ -85,6 +94,19 @@ struct nxflat_loadinfo_s
uint32_t relocstart; /* Start of array of struct flat_reloc */
uint16_t reloccount; /* Number of elements in reloc array */
+ /* Address environment.
+ *
+ * addrenv - This is the handle created by up_addrenv_create() that can be
+ * used to manage the tasks address space.
+ * oldenv - This is a value returned by up_addrenv_select() that must be
+ * used to restore the current hardware address environment.
+ */
+
+#ifdef CONFIG_ADDRENV
+ task_addrenv_t addrenv; /* Task address environment */
+ hw_addrenv_t oldenv; /* Saved hardware address environment */
+#endif
+
/* File descriptors */
int filfd; /* Descriptor for the file being loaded */
@@ -110,22 +132,22 @@ extern "C" {
* These are APIs exported by libnxflat (and may be used outside of NuttX):
****************************************************************************/
-/***********************************************************************
+/****************************************************************************
* Name: nxflat_verifyheader
*
* Description:
- * Given the header from a possible NXFLAT executable, verify that it
- * is an NXFLAT executable.
+ * Given the header from a possible NXFLAT executable, verify that it is
+ * an NXFLAT executable.
*
* Returned Value:
* 0 (OK) is returned on success and a negated errno is returned on
* failure.
*
- ***********************************************************************/
+ ****************************************************************************/
EXTERN int nxflat_verifyheader(const struct nxflat_hdr_s *header);
-/***********************************************************************
+/****************************************************************************
* Name: nxflat_init
*
* Description:
@@ -136,12 +158,12 @@ EXTERN int nxflat_verifyheader(const struct nxflat_hdr_s *header);
* 0 (OK) is returned on success and a negated errno is returned on
* failure.
*
- ***********************************************************************/
+ ****************************************************************************/
EXTERN int nxflat_init(const char *filename,
struct nxflat_loadinfo_s *loadinfo);
-/***********************************************************************
+/****************************************************************************
* Name: nxflat_uninit
*
* Description:
@@ -152,11 +174,11 @@ EXTERN int nxflat_init(const char *filename,
* 0 (OK) is returned on success and a negated errno is returned on
* failure.
*
- ***********************************************************************/
+ ****************************************************************************/
EXTERN int nxflat_uninit(struct nxflat_loadinfo_s *loadinfo);
-/***********************************************************************
+/****************************************************************************
* Name: nxflat_load
*
* Description:
@@ -170,11 +192,11 @@ EXTERN int nxflat_uninit(struct nxflat_loadinfo_s *loadinfo);
* 0 (OK) is returned on success and a negated errno is returned on
* failure.
*
- ***********************************************************************/
+ ****************************************************************************/
EXTERN int nxflat_load(struct nxflat_loadinfo_s *loadinfo);
-/***********************************************************************
+/****************************************************************************
* Name: nxflat_read
*
* Description:
@@ -184,12 +206,12 @@ EXTERN int nxflat_load(struct nxflat_loadinfo_s *loadinfo);
* 0 (OK) is returned on success and a negated errno is returned on
* failure.
*
- ***********************************************************************/
+ ****************************************************************************/
EXTERN int nxflat_read(struct nxflat_loadinfo_s *loadinfo, char *buffer,
int readsize, int offset);
-/***********************************************************************
+/****************************************************************************
* Name: nxflat_bind
*
* Description:
@@ -202,31 +224,32 @@ EXTERN int nxflat_read(struct nxflat_loadinfo_s *loadinfo, char *buffer,
* 0 (OK) is returned on success and a negated errno is returned on
* failure.
*
- ***********************************************************************/
+ ****************************************************************************/
struct symtab_s;
EXTERN int nxflat_bind(FAR struct nxflat_loadinfo_s *loadinfo,
FAR const struct symtab_s *exports, int nexports);
-/***********************************************************************
+/****************************************************************************
* Name: nxflat_unload
*
* Description:
- * This function unloads the object from memory. This essentially
- * undoes the actions of nxflat_load.
+ * This function unloads the object from memory. This essentially undoes
+ * the actions of nxflat_load. It is called only under certain error
+ * conditions after the the module has been loaded but not yet started.
*
* Returned Value:
* 0 (OK) is returned on success and a negated errno is returned on
* failure.
*
- ***********************************************************************/
+ ****************************************************************************/
EXTERN int nxflat_unload(struct nxflat_loadinfo_s *loadinfo);
/****************************************************************************
* These are APIs used internally only by NuttX:
****************************************************************************/
-/***********************************************************************
+/****************************************************************************
* Name: nxflat_initialize
*
* Description:
@@ -239,7 +262,7 @@ EXTERN int nxflat_unload(struct nxflat_loadinfo_s *loadinfo);
* 0 (OK) is returned on success and a negated errno is returned on
* failure.
*
- ***********************************************************************/
+ ****************************************************************************/
EXTERN int nxflat_initialize(void);
@@ -261,4 +284,4 @@ EXTERN void nxflat_uninitialize(void);
}
#endif
-#endif /* __INCLUDE_NUTTX_NXFLAT_H */
+#endif /* __INCLUDE_NUTTX_BINFMT_NXFLAT_H */
diff --git a/nuttx/include/nuttx/symtab.h b/nuttx/include/nuttx/binfmt/symtab.h
index b302ab20a..346c6099f 100644
--- a/nuttx/include/nuttx/symtab.h
+++ b/nuttx/include/nuttx/binfmt/symtab.h
@@ -1,5 +1,5 @@
/****************************************************************************
- * include/nuttx/symtab.h
+ * include/nuttx/binfmt/symtab.h
*
* Copyright (C) 2009 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
@@ -33,8 +33,8 @@
*
****************************************************************************/
-#ifndef __INCLUDE_NUTTX_SYMTAB_H
-#define __INCLUDE_NUTTX_SYMTAB_H
+#ifndef __INCLUDE_NUTTX_BINFMT_SYMTAB_H
+#define __INCLUDE_NUTTX_BINFMT_SYMTAB_H
/****************************************************************************
* Included Files
@@ -54,7 +54,7 @@
* is a fixed size array of struct symtab_s. The information is intentionally
* minimal and supports only:
*
- * 1. Function points as sym_values. Of other kinds of values need to be
+ * 1. Function pointers as sym_values. Of other kinds of values need to be
* supported, then typing information would also need to be included in
* the structure.
*
@@ -159,5 +159,5 @@ symtab_findorderedbyvalue(FAR const struct symtab_s *symtab,
}
#endif
-#endif /* __INCLUDE_NUTTX_SYMTAB_H */
+#endif /* __INCLUDE_NUTTX_BINFMT_SYMTAB_H */
diff --git a/nuttx/include/nuttx/compiler.h b/nuttx/include/nuttx/compiler.h
index d74fcbea0..6ad51ad0f 100644
--- a/nuttx/include/nuttx/compiler.h
+++ b/nuttx/include/nuttx/compiler.h
@@ -87,11 +87,16 @@
# define packed_struct __attribute__ ((packed))
-/* GCC does not support the reentrant or naked attributes */
+/* GCC does not support the reentrant attribute */
# define reentrant_function
-# define naked_function
+/* The naked attribute informs GCC that the programmer will take care of
+ * the function prolog and epilog.
+ */
+
+# define naked_function __attribute__ ((naked,no_instrument_function))
+
/* The inline_function attribute informs GCC that the function should always
* be inlined, regardless of the level of optimization. The noinline_function
* indicates that the function should never be inlined.
@@ -191,8 +196,10 @@
/* GCC supports both types double and long long */
-# define CONFIG_HAVE_DOUBLE 1
# define CONFIG_HAVE_LONG_LONG 1
+# define CONFIG_HAVE_FLOAT 1
+# define CONFIG_HAVE_DOUBLE 1
+# define CONFIG_HAVE_LONG_DOUBLE 1
/* Structures and unions can be assigned and passed as values */
@@ -255,7 +262,7 @@
* external RAM.
*/
-#if defined(__z80) || defined(__gbz80)
+#if defined(__SDCC_z80) || defined(__SDCC_z180) || defined(__SDCC_gbz80)
# define FAR
# define NEAR
# define CODE
@@ -295,7 +302,9 @@
/* SDCC does not support type long long or type double */
# undef CONFIG_HAVE_LONG_LONG
+# define CONFIG_HAVE_FLOAT 1
# undef CONFIG_HAVE_DOUBLE
+# undef CONFIG_HAVE_LONG_DOUBLE
/* Structures and unions cannot be passed as values or used
* in assignments.
@@ -398,8 +407,10 @@
* simply do not support long long or double.
*/
-# undef CONFIG_HAVE_DOUBLE
# undef CONFIG_HAVE_LONG_LONG
+# define CONFIG_HAVE_FLOAT 1
+# undef CONFIG_HAVE_DOUBLE
+# undef CONFIG_HAVE_LONG_DOUBLE
/* Structures and unions can be assigned and passed as values */
@@ -433,9 +444,11 @@
# undef CONFIG_LONG_IS_NOT_INT
# undef CONFIG_PTR_IS_NOT_INT
# undef CONFIG_HAVE_INLINE
-# define inline
+# define inline 1
# undef CONFIG_HAVE_LONG_LONG
+# define CONFIG_HAVE_FLOAT 1
# undef CONFIG_HAVE_DOUBLE
+# undef CONFIG_HAVE_LONG_DOUBLE
# undef CONFIG_CAN_PASS_STRUCTS
#endif
diff --git a/nuttx/include/nuttx/float.h b/nuttx/include/nuttx/float.h
new file mode 100644
index 000000000..a8e4aa28b
--- /dev/null
+++ b/nuttx/include/nuttx/float.h
@@ -0,0 +1,225 @@
+/****************************************************************************
+ * include/nuttx/float.h
+ *
+ * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Reference: http://pubs.opengroup.org/onlinepubs/009695399/basedefs/float.h.html
+ *
+ * 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 __INCLUDE_NUTTX_FLOAT_H
+#define __INCLUDE_NUTTX_FLOAT_H
+
+/* TODO: These values could vary with architectures toolchains. This
+ * logic should be move at least to the include/arch directory.
+ */
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#include <nuttx/compiler.h>
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/* Radix of exponent representation, b. */
+
+#define FLT_RADIX 2
+
+/* Number of base-FLT_RADIX digits in the floating-point significand, p. */
+
+#define FLT_MANT_DIG 24
+
+#if CONFIG_HAVE_DOUBLE
+# define DBL_MANT_DIG 53
+#else
+# define DBL_MANT_DIG FLT_MANT_DIG
+#endif
+
+#ifdef CONFIG_HAVE_LONG_DOUBLE
+# define LDBL_MANT_DIG DBL_MANT_DIG /* FIX ME */
+#else
+# define LDBL_MANT_DIG DBL_MANT_DIG
+#endif
+
+/* Number of decimal digits, n, such that any floating-point number in the
+ * widest supported floating type with pmax radix b digits can be rounded
+ * to a floating-point number with n decimal digits and back again without
+ * change to the value.
+ */
+
+#define DECIMAL_DIG 10
+
+/* Number of decimal digits, q, such that any floating-point number with q
+ * decimal digits can be rounded into a floating-point number with p radix
+ * b digits and back again without change to the q decimal digits.
+ */
+
+#define FLT_DIG 6
+
+#if CONFIG_HAVE_DOUBLE
+# define DBL_DIG 15 /* 10 */
+#else
+# define DBL_DIG FLT_DIG
+#endif
+
+#ifdef CONFIG_HAVE_LONG_DOUBLE
+# define LDBL_DIG DBL_DIG /* FIX ME */
+#else
+# define LDBL_DIG DBL_DIG
+#endif
+
+/* Minimum negative integer such that FLT_RADIX raised to that power minus
+ * 1 is a normalized floating-point number, emin.
+ */
+
+#define FLT_MIN_EXP (-125)
+
+#if CONFIG_HAVE_DOUBLE
+# define DBL_MIN_EXP (-1021)
+#else
+# define DBL_MIN_EXP FLT_MIN_EXP
+#endif
+
+#ifdef CONFIG_HAVE_LONG_DOUBLE
+# define LDBL_MIN_EXP DBL_MIN_EXP /* FIX ME */
+#else
+# define LDBL_MIN_EXP DBL_MIN_EXP
+#endif
+
+/* inimum negative integer such that 10 raised to that power is in the range
+ * of normalized floating-point numbers.
+ */
+
+#define FLT_MIN_10_EXP (-37)
+
+#if CONFIG_HAVE_DOUBLE
+# define DBL_MIN_10_EXP (-307) /* -37 */
+#else
+# define DBL_MIN_10_EXP FLT_MIN_10_EXP
+#endif
+
+#ifdef CONFIG_HAVE_LONG_DOUBLE
+# define LDBL_MIN_10_EXP DBL_MIN_10_EXP /* FIX ME */
+#else
+# define LDBL_MIN_10_EXP DBL_MIN_10_EXP
+#endif
+
+/* Maximum integer such that FLT_RADIX raised to that power minus 1 is a
+ * representable finite floating-point number, emax.
+ */
+
+#define FLT_MAX_EXP 128
+
+#if CONFIG_HAVE_DOUBLE
+# define DBL_MAX_EXP 1024
+#else
+# define DBL_MAX_EXP FLT_MAX_EXP
+#endif
+
+#ifdef CONFIG_HAVE_LONG_DOUBLE
+# define LDBL_MAX_EXP DBL_MAX_EXP /* FIX ME */
+#else
+# define LDBL_MAX_EXP DBL_MAX_EXP
+#endif
+
+/* Maximum integer such that 10 raised to that power is in the range of
+ * representable finite floating-point numbers.
+ */
+
+#define FLT_MAX_10_EXP 38 /* 37 */
+
+#if CONFIG_HAVE_DOUBLE
+# define DBL_MAX_10_EXP 308 /* 37 */
+#else
+# define DBL_MAX_10_EXP FLT_MAX_10_EXP
+#endif
+
+#ifdef CONFIG_HAVE_LONG_DOUBLE
+# define LDBL_MAX_10_EXP DBL_MAX_10_EXP /* FIX ME */
+#else
+# define LDBL_MAX_10_EXP DBL_MAX_10_EXP
+#endif
+
+/* Maximum representable finite floating-point number. */
+
+#define FLT_MAX 3.40282347e+38F /* 1E+37 */
+
+#if CONFIG_HAVE_DOUBLE
+# define DBL_MAX 1.7976931348623157e+308 /* 1E+37 */
+#else
+# define DBL_MAX FLT_MAX
+#endif
+
+#ifdef CONFIG_HAVE_LONG_DOUBLE
+# define LDBL_MAX DBL_MAX /* FIX ME */
+#else
+# define LDBL_MAX DBL_MAX
+#endif
+
+/* The difference between 1 and the least value greater than 1 that is
+ * representable in the given floating-point type, b1-p.
+ */
+
+#define FLT_EPSILON 1.1920929e-07F /* 1E-5 */
+
+#if CONFIG_HAVE_DOUBLE
+# define DBL_EPSILON 2.2204460492503131e-16 /* 1E-9 */
+#else
+# define DBL_EPSILON FLT_EPSILON
+#endif
+
+#ifdef CONFIG_HAVE_LONG_DOUBLE
+# define LDBL_EPSILON DBL_EPSILON /* FIX ME */
+#else
+# define LDBL_EPSILON DBL_EPSILON
+#endif
+
+/* Minimum normalized positive floating-point number, bemin -1. */
+
+#define FLT_MIN 1.17549435e-38F /* 1E-37 */
+
+#if CONFIG_HAVE_DOUBLE
+#define DBL_MIN 2.2250738585072014e-308 /* 1E-37 */
+#else
+# define DBL_MIN FLT_MIN
+#endif
+
+#ifdef CONFIG_HAVE_LONG_DOUBLE
+# define LDBL_MIN DBL_MIN /* FIX ME */
+#else
+# define LDBL_MIN DBL_MIN
+#endif
+
+#endif /* __INCLUDE_NUTTX_FLOAT_H */
diff --git a/nuttx/include/nuttx/fs/fs.h b/nuttx/include/nuttx/fs/fs.h
index 81f81622f..1759310bc 100644
--- a/nuttx/include/nuttx/fs/fs.h
+++ b/nuttx/include/nuttx/fs/fs.h
@@ -51,6 +51,10 @@
/****************************************************************************
* Definitions
****************************************************************************/
+/* Stream flags for the fs_flags field of in struct file_struct */
+
+#define __FS_FLAG_EOF (1 << 0) /* EOF detected by a read operation */
+#define __FS_FLAG_ERROR (1 << 1) /* Error detected by any operation */
/****************************************************************************
* Type Definitions
@@ -172,7 +176,7 @@ struct mountpt_operations
int (*statfs)(FAR struct inode *mountpt, FAR struct statfs *buf);
- /* Operations on pathes */
+ /* Operations on paths */
int (*unlink)(FAR struct inode *mountpt, FAR const char *relpath);
int (*mkdir)(FAR struct inode *mountpt, FAR const char *relpath, mode_t mode);
@@ -270,11 +274,6 @@ struct filelist
struct file_struct
{
int fs_filedes; /* File descriptor associated with stream */
- uint16_t fs_oflags; /* Open mode flags */
-#if CONFIG_NUNGET_CHARS > 0
- uint8_t fs_nungotten; /* The number of characters buffered for ungetc */
- unsigned char fs_ungotten[CONFIG_NUNGET_CHARS];
-#endif
#if CONFIG_STDIO_BUFFER_SIZE > 0
sem_t fs_sem; /* For thread safety */
pid_t fs_holder; /* Holder of sem */
@@ -284,6 +283,12 @@ struct file_struct
FAR unsigned char *fs_bufpos; /* Current position in buffer */
FAR unsigned char *fs_bufread; /* Pointer to 1 past last buffered read char. */
#endif
+ uint16_t fs_oflags; /* Open mode flags */
+ uint8_t fs_flags; /* Stream flags */
+#if CONFIG_NUNGET_CHARS > 0
+ uint8_t fs_nungotten; /* The number of characters buffered for ungetc */
+ unsigned char fs_ungotten[CONFIG_NUNGET_CHARS];
+#endif
};
struct streamlist
diff --git a/nuttx/include/nuttx/i2c.h b/nuttx/include/nuttx/i2c.h
index ef3d9a388..23356ecd3 100644
--- a/nuttx/include/nuttx/i2c.h
+++ b/nuttx/include/nuttx/i2c.h
@@ -1,7 +1,7 @@
/****************************************************************************
* include/nuttx/i2c.h
*
- * Copyright(C) 2009-2011 Gregory Nutt. All rights reserved.
+ * Copyright(C) 2009-2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -47,6 +47,16 @@
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
+/* If a dynamic timeout is selected, then a non-negative, non-zero micro-
+ * seconds per byte vale must be provided as well.
+ */
+
+#ifdef CONFIG_STM32_I2C_DYNTIMEO
+# if CONFIG_STM32_I2C_DYNTIMEO_USECPERBYTE < 1
+# warning "Ignoring CONFIG_STM32_I2C_DYNTIMEO because of CONFIG_STM32_I2C_DYNTIMEO_USECPERBYTE"
+# undef CONFIG_STM32_I2C_DYNTIMEO
+# endif
+#endif
/* I2C address calculation. Convert 7- and 10-bit address to 8-bit and
* 16-bit read/write address
@@ -323,24 +333,19 @@ EXTERN FAR struct i2c_dev_s *up_i2cinitialize(int port);
*
****************************************************************************/
-EXTERN int up_i2cuninitialize(FAR struct i2c_dev_s * dev);
+EXTERN int up_i2cuninitialize(FAR struct i2c_dev_s *dev);
-/****************************************************************************
+/************************************************************************************
* Name: up_i2creset
*
* Description:
- * Reset the port and the associated I2C bus. Useful when the bus or an
- * attached slave has become wedged or unresponsive.
+ * Reset an I2C bus
*
- * Input Parameter:
- * Device structure as returned by the up_i2cinitalize()
- *
- * Returned Value:
- * OK on success, ERROR if the bus cannot be unwedged.
- *
- ****************************************************************************/
+ ************************************************************************************/
-EXTERN int up_i2creset(FAR struct i2c_dev_s * dev);
+#ifdef CONFIG_I2C_RESET
+EXTERN int up_i2creset(FAR struct i2c_dev_s *dev);
+#endif
#undef EXTERN
#if defined(__cplusplus)
diff --git a/nuttx/include/nuttx/input/keypad.h b/nuttx/include/nuttx/input/keypad.h
new file mode 100644
index 000000000..574b421c1
--- /dev/null
+++ b/nuttx/include/nuttx/input/keypad.h
@@ -0,0 +1,54 @@
+/************************************************************************************
+ * include/nuttx/input/keypad.h
+ *
+ * Copyright (C) 2012 Denis Carikli.
+ * Author: Denis Carikli <GNUtoo@no-log.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 __INCLUDE_NUTTX_INPUT_KEYPAD_H
+#define __INCLUDE_NUTTX_INPUT_KEYPAD_H
+
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+int keypad_kbdinit(void);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __INCLUDE_NUTTX_INPUT_KEYPAD_H */
+
diff --git a/nuttx/include/nuttx/input/max11802.h b/nuttx/include/nuttx/input/max11802.h
new file mode 100644
index 000000000..3d03bdd11
--- /dev/null
+++ b/nuttx/include/nuttx/input/max11802.h
@@ -0,0 +1,175 @@
+/****************************************************************************
+ * include/nuttx/input/max11802.h
+ *
+ * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Authors: Gregory Nutt <gnutt@nuttx.org>
+ * Petteri Aimonen <jpa@nx.mail.kapsi.fi>
+ *
+ * References:
+ * "Low-Power, Ultra-Small Resistive Touch-Screen Controllers
+ * with I2C/SPI Interface" Maxim IC, Rev 3, 10/2010
+ *
+ * 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 __INCLUDE_NUTTX_INPUT_MAX11802_H
+#define __INCLUDE_NUTTX_INPUT_MAX11802_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#include <nuttx/spi.h>
+#include <stdbool.h>
+#include <nuttx/irq.h>
+
+#if defined(CONFIG_INPUT) && defined(CONFIG_INPUT_MAX11802)
+
+/****************************************************************************
+ * Pre-Processor Definitions
+ ****************************************************************************/
+/* Configuration ************************************************************/
+/* SPI Frequency. Default: 100KHz */
+
+#ifndef CONFIG_MAX11802_FREQUENCY
+# define CONFIG_MAX11802_FREQUENCY 100000
+#endif
+
+/* Maximum number of threads than can be waiting for POLL events */
+
+#ifndef CONFIG_MAX11802_NPOLLWAITERS
+# define CONFIG_MAX11802_NPOLLWAITERS 2
+#endif
+
+#ifndef CONFIG_MAX11802_SPIMODE
+# define CONFIG_MAX11802_SPIMODE SPIDEV_MODE0
+#endif
+
+/* Thresholds */
+
+#ifndef CONFIG_MAX11802_THRESHX
+# define CONFIG_MAX11802_THRESHX 12
+#endif
+
+#ifndef CONFIG_MAX11802_THRESHY
+# define CONFIG_MAX11802_THRESHY 12
+#endif
+
+/* Check for some required settings. This can save the user a lot of time
+ * in getting the right configuration.
+ */
+
+#ifdef CONFIG_DISABLE_SIGNALS
+# error "Signals are required. CONFIG_DISABLE_SIGNALS must not be selected."
+#endif
+
+#ifndef CONFIG_SCHED_WORKQUEUE
+# error "Work queue support required. CONFIG_SCHED_WORKQUEUE must be selected."
+#endif
+
+/****************************************************************************
+ * Public Types
+ ****************************************************************************/
+
+/* A reference to a structure of this type must be passed to the MAX11802
+ * driver. This structure provides information about the configuration
+ * of the MAX11802 and provides some board-specific hooks.
+ *
+ * Memory for this structure is provided by the caller. It is not copied
+ * by the driver and is presumed to persist while the driver is active. The
+ * memory must be writable because, under certain circumstances, the driver
+ * may modify frequency or X plate resistance values.
+ */
+
+struct max11802_config_s
+{
+ /* Device characterization */
+
+ uint32_t frequency; /* SPI frequency */
+
+ /* IRQ/GPIO access callbacks. These operations all hidden behind
+ * callbacks to isolate the MAX11802 driver from differences in GPIO
+ * interrupt handling by varying boards and MCUs. If possible,
+ * interrupts should be configured on both rising and falling edges
+ * so that contact and loss-of-contact events can be detected.
+ *
+ * attach - Attach the MAX11802 interrupt handler to the GPIO interrupt
+ * enable - Enable or disable the GPIO interrupt
+ * clear - Acknowledge/clear any pending GPIO interrupt
+ * pendown - Return the state of the pen down GPIO input
+ */
+
+ int (*attach)(FAR struct max11802_config_s *state, xcpt_t isr);
+ void (*enable)(FAR struct max11802_config_s *state, bool enable);
+ void (*clear)(FAR struct max11802_config_s *state);
+ bool (*pendown)(FAR struct max11802_config_s *state);
+};
+
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+
+#ifdef __cplusplus
+#define EXTERN extern "C"
+extern "C" {
+#else
+#define EXTERN extern
+#endif
+
+/****************************************************************************
+ * Name: max11802_register
+ *
+ * Description:
+ * Configure the MAX11802 to use the provided SPI device instance. This
+ * will register the driver as /dev/inputN where N is the minor device
+ * number
+ *
+ * Input Parameters:
+ * spi - An SPI driver instance
+ * config - Persistent board configuration data
+ * minor - The input device minor number
+ *
+ * Returned Value:
+ * Zero is returned on success. Otherwise, a negated errno value is
+ * returned to indicate the nature of the failure.
+ *
+ ****************************************************************************/
+
+EXTERN int max11802_register(FAR struct spi_dev_s *spi,
+ FAR struct max11802_config_s *config,
+ int minor);
+
+#undef EXTERN
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* CONFIG_INPUT && CONFIG_INPUT_MAX11802 */
+#endif /* __INCLUDE_NUTTX_INPUT_MAX11802_H */
diff --git a/nuttx/include/nuttx/lcd/ug-2864ambag01.h b/nuttx/include/nuttx/lcd/ug-2864ambag01.h
new file mode 100644
index 000000000..deb568981
--- /dev/null
+++ b/nuttx/include/nuttx/lcd/ug-2864ambag01.h
@@ -0,0 +1,245 @@
+/**************************************************************************************
+ * include/nuttx/lcd/ug-2864ambag01.h
+ * Driver for Univision UG-2864AMBAG01 OLED display (wih SH1101A controller) in SPI
+ * mode
+ *
+ * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * References:
+ * 1. Product Specification (Preliminary), Part Name: OEL Display Module, Part ID:
+ * UG-2864AMBAG01, Doc No: SASI-9015-A, Univision Technology Inc.
+ * 2. SH1101A, 132 X 64 Dot Matrix OLED/PLED, Preliminary Segment/Common Driver with
+ * Controller, Sino Wealth
+ *
+ * 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 __INCLUDE_NUTTX_UG_8264AMBAG01_H
+#define __INCLUDE_NUTTX_UG_8264AMBAG01_H
+
+/**************************************************************************************
+ * Included Files
+ **************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdbool.h>
+
+#include <nuttx/arch.h>
+
+#ifdef CONFIG_LCD_UG2864AMBAG01
+
+/**************************************************************************************
+ * Pre-processor Definitions
+ **************************************************************************************/
+/* Configuration **********************************************************************/
+/* UG-2864AMBAG01 Configuration Settings:
+ *
+ * CONFIG_UG2864AMBAG01_SPIMODE - Controls the SPI mode
+ * CONFIG_UG2864AMBAG01_FREQUENCY - Define to use a different bus frequency
+ * CONFIG_UG2864AMBAG01_NINTERFACES - Specifies the number of physical UG-2864AMBAG01
+ * devices that will be supported.
+ *
+ * Required LCD driver settings:
+ *
+ * CONFIG_LCD_UG28AMBAG01 - Enable UG-2864AMBAG01 support
+ * CONFIG_LCD_MAXCONTRAST should be 255, but any value >0 and <=255 will be accepted.
+ * CONFIG_LCD_MAXPOWER must be 1
+ *
+ * Option LCD driver settings:
+ * CONFIG_LCD_LANDSCAPE, CONFIG_LCD_PORTRAIT, CONFIG_LCD_RLANDSCAPE, and
+ * CONFIG_LCD_RPORTRAIT - Display orientation.
+ *
+ * Required SPI driver settings:
+ * CONFIG_SPI_CMDDATA - Include support for cmd/data selection.
+ */
+
+/* SPI Interface
+ *
+ * "The serial interface consists of serial clock SCL, serial data SI, A0 and
+ * CS . SI is shifted into an 8-bit shift register on every rising edge of
+ * SCL in the order of D7, D6, … and D0. A0 is sampled on every eighth clock
+ * and the data byte in the shift register is written to the display data RAM
+ * or command register in the same clock."
+ *
+ * MODE 3:
+ * Clock polarity: High (CPOL=1)
+ * Clock phase: Sample on trailing (rising edge) (CPHA 1)
+ */
+
+#ifndef CONFIG_UG2864AMBAG01_SPIMODE
+# define CONFIG_UG2864AMBAG01_SPIMODE SPIDEV_MODE3
+#endif
+
+/* "This module determines whether the input data is interpreted as data or
+ * command. When A0 = “H”, the inputs at D7 - D0 are interpreted as data and be
+ * written to display RAM. When A0 = “L”, the inputs at D7 - D0 are interpreted
+ * as command, they will be decoded and be written to the corresponding command
+ * registers.
+ */
+
+#ifndef CONFIG_SPI_CMDDATA
+# error "CONFIG_SPI_CMDDATA must be defined in your NuttX configuration"
+#endif
+
+/* CONFIG_UG2864AMBAG01_NINTERFACES determines the number of physical interfaces
+ * that will be supported.
+ */
+
+#ifndef CONFIG_UG2864AMBAG01_NINTERFACES
+# define CONFIG_UG2864AMBAG01_NINTERFACES 1
+#endif
+
+/* Check contrast selection */
+
+#if !defined(CONFIG_LCD_MAXCONTRAST)
+# define CONFIG_LCD_MAXCONTRAST 255
+#endif
+
+#if CONFIG_LCD_MAXCONTRAST <= 0|| CONFIG_LCD_MAXCONTRAST > 255
+# error "CONFIG_LCD_MAXCONTRAST exceeds supported maximum"
+#endif
+
+#if CONFIG_LCD_MAXCONTRAST < 255
+# warning "Optimal setting of CONFIG_LCD_MAXCONTRAST is 255"
+#endif
+
+/* Check power setting */
+
+#if !defined(CONFIG_LCD_MAXPOWER)
+# define CONFIG_LCD_MAXPOWER 1
+#endif
+
+#if CONFIG_LCD_MAXPOWER != 1
+# warning "CONFIG_LCD_MAXPOWER exceeds supported maximum"
+# undef CONFIG_LCD_MAXPOWER
+# define CONFIG_LCD_MAXPOWER 1
+#endif
+
+/* Color is 1bpp monochrome with leftmost column contained in bits 0 */
+
+#ifdef CONFIG_NX_DISABLE_1BPP
+# warning "1 bit-per-pixel support needed"
+#endif
+
+/* Orientation */
+
+#if defined(CONFIG_LCD_LANDSCAPE)
+# undef CONFIG_LCD_PORTRAIT
+# undef CONFIG_LCD_RLANDSCAPE
+# undef CONFIG_LCD_RPORTRAIT
+#elif defined(CONFIG_LCD_PORTRAIT)
+# undef CONFIG_LCD_LANDSCAPE
+# undef CONFIG_LCD_RLANDSCAPE
+# undef CONFIG_LCD_RPORTRAIT
+#elif defined(CONFIG_LCD_RLANDSCAPE)
+# undef CONFIG_LCD_LANDSCAPE
+# undef CONFIG_LCD_PORTRAIT
+# undef CONFIG_LCD_RPORTRAIT
+#elif defined(CONFIG_LCD_RPORTRAIT)
+# undef CONFIG_LCD_LANDSCAPE
+# undef CONFIG_LCD_PORTRAIT
+# undef CONFIG_LCD_RLANDSCAPE
+#else
+# define CONFIG_LCD_LANDSCAPE 1
+# warning "Assuming landscape orientation"
+#endif
+
+/* Some important "colors" */
+
+#define UG_Y1_BLACK 0
+#define UG_Y1_WHITE 1
+
+/**************************************************************************************
+ * Public Types
+ **************************************************************************************/
+
+/**************************************************************************************
+ * Public Data
+ **************************************************************************************/
+
+#ifdef __cplusplus
+extern "C"
+{
+#endif
+
+/**************************************************************************************
+ * Public Function Prototypes
+ **************************************************************************************/
+
+/**************************************************************************************
+ * Name: ug2864ambag01_initialize
+ *
+ * Description:
+ * Initialize the UG-2864AMBAG01 video hardware. The initial state of the
+ * OLED is fully initialized, display memory cleared, and the OLED ready
+ * to use, but with the power setting at 0 (full off == sleep mode).
+ *
+ * Input Parameters:
+ *
+ * spi - A reference to the SPI driver instance.
+ * devno - A value in the range of 0 through CONFIG_UG2864AMBAG01_NINTERFACES-1.
+ * This allows support for multiple OLED devices.
+ *
+ * Returned Value:
+ *
+ * On success, this function returns a reference to the LCD object for
+ * the specified OLED. NULL is returned on any failure.
+ *
+ **************************************************************************************/
+
+struct lcd_dev_s; /* See include/nuttx/lcd/lcd.h */
+struct spi_dev_s; /* See include/nuttx/spi.h */
+FAR struct lcd_dev_s *ug2864ambag01_initialize(FAR struct spi_dev_s *spi,
+ unsigned int devno);
+
+/************************************************************************************************
+ * Name: ug2864ambag01_fill
+ *
+ * Description:
+ * This non-standard method can be used to clear the entire display by writing one
+ * color to the display. This is much faster than writing a series of runs.
+ *
+ * Input Parameters:
+ * priv - Reference to private driver structure
+ *
+ * Assumptions:
+ * Caller has selected the OLED section.
+ *
+ **************************************************************************************/
+
+void ug2864ambag01_fill(FAR struct lcd_dev_s *dev, uint8_t color);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* CONFIG_LCD_UG2864AMBAG01 */
+#endif /* __INCLUDE_NUTTX_UG_8264AMBAG01_H */
diff --git a/nuttx/include/nuttx/lcd/ug-9664hswag01.h b/nuttx/include/nuttx/lcd/ug-9664hswag01.h
index 696005b5d..b470e0895 100644
--- a/nuttx/include/nuttx/lcd/ug-9664hswag01.h
+++ b/nuttx/include/nuttx/lcd/ug-9664hswag01.h
@@ -3,7 +3,7 @@
* Driver for the Univision UG-9664HSWAG01 Display with the Solomon Systech
* SSD1305 LCD controller.
*
- * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2011-2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -58,8 +58,6 @@
* CONFIG_UG9664HSWAG01_POWER
* If the hardware supports a controllable OLED a power supply, this
* configuration shold be defined. (See ug_power() below).
- * CONFIG_LCD_UGDEBUG - Enable detailed UG-9664HSWAG01 debug output
- * (CONFIG_DEBUG and CONFIG_VERBOSE must also be enabled).
*
* Required LCD driver settings:
* CONFIG_LCD_UG9664HSWAG01 - Enable UG-9664HSWAG01 support
@@ -90,10 +88,8 @@
****************************************************************************/
#ifdef __cplusplus
-#define EXTERN extern "C"
-extern "C" {
-#else
-#define EXTERN extern
+extern "C"
+{
#endif
/****************************************************************************
@@ -123,7 +119,7 @@ extern "C" {
struct lcd_dev_s; /* see nuttx/lcd.h */
struct spi_dev_s; /* see nuttx/spi.h */
-EXTERN FAR struct lcd_dev_s *ug_initialize(FAR struct spi_dev_s *spi, unsigned int devno);
+FAR struct lcd_dev_s *ug_initialize(FAR struct spi_dev_s *spi, unsigned int devno);
/****************************************************************************
* Name: ug_power
@@ -145,12 +141,11 @@ EXTERN FAR struct lcd_dev_s *ug_initialize(FAR struct spi_dev_s *spi, unsigned i
**************************************************************************************/
#ifdef CONFIG_UG9664HSWAG01_POWER
-EXTERN void ug_power(unsigned int devno, bool on);
+void ug_power(unsigned int devno, bool on);
#else
# define ug_power(a,b)
#endif
-#undef EXTERN
#ifdef __cplusplus
}
#endif
diff --git a/nuttx/include/nuttx/math.h b/nuttx/include/nuttx/math.h
index 84dbea6e0..aaadb9c91 100644
--- a/nuttx/include/nuttx/math.h
+++ b/nuttx/include/nuttx/math.h
@@ -50,14 +50,280 @@
#ifdef CONFIG_ARCH_MATH_H
# include <arch/math.h>
-#endif
+
+/* If CONFIG_LIB is enabled, then the math library at lib/math will be
+ * built. This library was taken from the math library developed for the
+ * Rhombus OS by Nick Johnson (https://github.com/nickbjohnson4224/rhombus).
+ * The port or the Rhombus math library was contributed by Darcy Gong.
+ */
+
+#else if defined CONFIG_LIBM
/****************************************************************************
- * Type Definitions
+ * Copyright (C) 2009-2011 Nick Johnson <nickbjohnson4224 at gmail.com>
+ *
+ * Permission to use, copy, modify, and distribute this software for any
+ * purpose with or without fee is hereby granted, provided that the above
+ * copyright notice and this permission notice appear in all copies.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
+ * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
+ * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
+ * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
+ * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
+ * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
+ * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
+ *
****************************************************************************/
/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#include <nuttx/compiler.h>
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/* General Constants ********************************************************/
+
+#define INFINITY (1.0/0.0)
+#define NAN (0.0/0.0)
+#define HUGE_VAL INFINITY
+
+#define isnan(x) ((x) != (x))
+#define isinf(x) (((x) == INFINITY) || ((x) == -INFINITY))
+
+/* Exponential and Logarithmic constants ************************************/
+
+#define M_E 2.7182818284590452353602874713526625
+#define M_SQRT2 1.4142135623730950488016887242096981
+#define M_SQRT1_2 0.7071067811865475244008443621048490
+#define M_LOG2E 1.4426950408889634073599246810018921
+#define M_LOG10E 0.4342944819032518276511289189166051
+#define M_LN2 0.6931471805599453094172321214581765
+#define M_LN10 2.3025850929940456840179914546843642
+
+/* Trigonometric Constants **************************************************/
+
+#define M_PI 3.1415926535897932384626433832795029
+#define M_PI_2 1.5707963267948966192313216916397514
+#define M_PI_4 0.7853981633974483096156608458198757
+#define M_1_PI 0.3183098861837906715377675267450287
+#define M_2_PI 0.6366197723675813430755350534900574
+#define M_2_SQRTPI 1.1283791670955125738961589031215452
+
+/****************************************************************************
* Public Function Prototypes
****************************************************************************/
+#if defined(__cplusplus)
+extern "C" {
+#endif
+
+/* General Functions ********************************************************/
+
+float ceilf (float x);
+#if CONFIG_HAVE_DOUBLE
+double ceil (double x);
+#endif
+#ifdef CONFIG_HAVE_LONG_DOUBLE
+long double ceill (long double x);
+#endif
+
+float floorf(float x);
+#if CONFIG_HAVE_DOUBLE
+double floor (double x);
+#endif
+#ifdef CONFIG_HAVE_LONG_DOUBLE
+long double floorl(long double x);
+#endif
+
+float roundf(float x);
+#if CONFIG_HAVE_DOUBLE
+double round (double x);
+#endif
+#ifdef CONFIG_HAVE_LONG_DOUBLE
+long double roundl(long double x);
+#endif
+
+float fabsf (float x);
+#if CONFIG_HAVE_DOUBLE
+double fabs (double x);
+#endif
+#ifdef CONFIG_HAVE_LONG_DOUBLE
+long double fabsl (long double x);
+#endif
+
+float modff (float x, float *iptr);
+#if CONFIG_HAVE_DOUBLE
+double modf (double x, double *iptr);
+#endif
+#ifdef CONFIG_HAVE_LONG_DOUBLE
+long double modfl (long double x, long double *iptr);
+#endif
+
+float fmodf (float x, float div);
+#if CONFIG_HAVE_DOUBLE
+double fmod (double x, double div);
+#endif
+#ifdef CONFIG_HAVE_LONG_DOUBLE
+long double fmodl (long double x, long double div);
+#endif
+
+/* Exponential and Logarithmic Functions ************************************/
+
+float powf (float b, float e);
+#if CONFIG_HAVE_DOUBLE
+double pow (double b, double e);
+#endif
+#ifdef CONFIG_HAVE_LONG_DOUBLE
+long double powl (long double b, long double e);
+#endif
+
+float expf (float x);
+#if CONFIG_HAVE_DOUBLE
+double exp (double x);
+#endif
+#ifdef CONFIG_HAVE_LONG_DOUBLE
+long double expl (long double x);
+#endif
+
+float logf (float x);
+#if CONFIG_HAVE_DOUBLE
+double log (double x);
+#endif
+#ifdef CONFIG_HAVE_LONG_DOUBLE
+long double logl (long double x);
+#endif
+
+float log10f(float x);
+#if CONFIG_HAVE_DOUBLE
+double log10 (double x);
+#endif
+#ifdef CONFIG_HAVE_LONG_DOUBLE
+long double log10l(long double x);
+#endif
+
+float log2f (float x);
+#if CONFIG_HAVE_DOUBLE
+double log2 (double x);
+#endif
+#ifdef CONFIG_HAVE_LONG_DOUBLE
+long double log2l (long double x);
+#endif
+
+float sqrtf (float x);
+#if CONFIG_HAVE_DOUBLE
+double sqrt (double x);
+#endif
+#ifdef CONFIG_HAVE_LONG_DOUBLE
+long double sqrtl (long double x);
+#endif
+
+float ldexpf(float x, int n);
+#if CONFIG_HAVE_DOUBLE
+double ldexp (double x, int n);
+#endif
+#ifdef CONFIG_HAVE_LONG_DOUBLE
+long double ldexpl(long double x, int n);
+#endif
+
+float frexpf(float x, int *exp);
+#if CONFIG_HAVE_DOUBLE
+double frexp (double x, int *exp);
+#endif
+#ifdef CONFIG_HAVE_LONG_DOUBLE
+long double frexpl(long double x, int *exp);
+#endif
+
+/* Trigonometric Functions **************************************************/
+
+float sinf (float x);
+#if CONFIG_HAVE_DOUBLE
+double sin (double x);
+#endif
+#ifdef CONFIG_HAVE_LONG_DOUBLE
+long double sinl (long double x);
+#endif
+
+float cosf (float x);
+#if CONFIG_HAVE_DOUBLE
+double cos (double x);
+#endif
+#ifdef CONFIG_HAVE_LONG_DOUBLE
+long double cosl (long double x);
+#endif
+
+float tanf (float x);
+#if CONFIG_HAVE_DOUBLE
+double tan (double x);
+#endif
+#ifdef CONFIG_HAVE_LONG_DOUBLE
+long double tanl (long double x);
+#endif
+
+float asinf (float x);
+#if CONFIG_HAVE_DOUBLE
+double asin (double x);
+#endif
+#ifdef CONFIG_HAVE_LONG_DOUBLE
+long double asinl (long double x);
+#endif
+
+float acosf (float x);
+#if CONFIG_HAVE_DOUBLE
+double acos (double x);
+#endif
+#ifdef CONFIG_HAVE_LONG_DOUBLE
+long double acosl (long double x);
+#endif
+
+float atanf (float x);
+#if CONFIG_HAVE_DOUBLE
+double atan (double x);
+#endif
+#ifdef CONFIG_HAVE_LONG_DOUBLE
+long double atanl (long double x);
+#endif
+
+float atan2f(float y, float x);
+#if CONFIG_HAVE_DOUBLE
+double atan2 (double y, double x);
+#endif
+#ifdef CONFIG_HAVE_LONG_DOUBLE
+long double atan2l(long double y, long double x);
+#endif
+
+float sinhf (float x);
+#if CONFIG_HAVE_DOUBLE
+double sinh (double x);
+#endif
+#ifdef CONFIG_HAVE_LONG_DOUBLE
+long double sinhl (long double x);
+#endif
+
+float coshf (float x);
+#if CONFIG_HAVE_DOUBLE
+double cosh (double x);
+#endif
+#ifdef CONFIG_HAVE_LONG_DOUBLE
+long double coshl (long double x);
+#endif
+
+float tanhf (float x);
+#if CONFIG_HAVE_DOUBLE
+double tanh (double x);
+#endif
+#ifdef CONFIG_HAVE_LONG_DOUBLE
+long double tanhl (long double x);
+#endif
+
+#if defined(__cplusplus)
+}
+#endif
+
+#endif /* CONFIG_LIBM */
#endif /* __INCLUDE_NUTTX_MATH_H */
diff --git a/nuttx/include/nuttx/mtd.h b/nuttx/include/nuttx/mtd.h
index 44582c412..ff48d313f 100644
--- a/nuttx/include/nuttx/mtd.h
+++ b/nuttx/include/nuttx/mtd.h
@@ -220,7 +220,6 @@ EXTERN FAR struct mtd_dev_s *at24c_initialize(FAR struct i2c_dev_s *dev);
EXTERN FAR struct mtd_dev_s *sst25_initialize(FAR struct spi_dev_s *dev);
-
/****************************************************************************
* Name: w25_initialize
*
@@ -233,6 +232,8 @@ EXTERN FAR struct mtd_dev_s *sst25_initialize(FAR struct spi_dev_s *dev);
EXTERN FAR struct mtd_dev_s *w25_initialize(FAR struct spi_dev_s *dev);
+EXTERN FAR struct mtd_dev_s *at25_initialize(FAR struct spi_dev_s *dev);
+
#undef EXTERN
#ifdef __cplusplus
}
diff --git a/nuttx/include/nuttx/net/ioctl.h b/nuttx/include/nuttx/net/ioctl.h
index be3f597f4..d5d1a001c 100644
--- a/nuttx/include/nuttx/net/ioctl.h
+++ b/nuttx/include/nuttx/net/ioctl.h
@@ -146,9 +146,15 @@
#define SIOCSIWPMKSA _SIOC(0x0036) /* PMKSA cache operation */
+/* Interface flags */
+
+#define SIOCSIFFLAGS _SIOC(0x0037) /* Sets the interface flags */
+#define SIOCGIFFLAGS _SIOC(0x0038) /* Gets the interface flags */
+
/****************************************************************************
* Type Definitions
****************************************************************************/
+
/* See include/net/if.h */
/****************************************************************************
diff --git a/nuttx/include/nuttx/net/uip/uip-arch.h b/nuttx/include/nuttx/net/uip/uip-arch.h
index 9546de04e..73805c6fb 100644
--- a/nuttx/include/nuttx/net/uip/uip-arch.h
+++ b/nuttx/include/nuttx/net/uip/uip-arch.h
@@ -90,6 +90,10 @@ struct uip_driver_s
char d_ifname[IFNAMSIZ];
#endif
+ /* Drivers interface flags. See IFF_* definitions in include/net/if.h */
+
+ uint8_t d_flags;
+
/* Ethernet device identity */
#ifdef CONFIG_NET_ETHERNET
diff --git a/nuttx/include/nuttx/power/pm.h b/nuttx/include/nuttx/power/pm.h
index 86e23f090..9c0568b2d 100644
--- a/nuttx/include/nuttx/power/pm.h
+++ b/nuttx/include/nuttx/power/pm.h
@@ -163,7 +163,7 @@
#endif
#if CONFIG_PM_IDLEENTER_THRESH >= CONFIG_PM_IDLEEXIT_THRESH
-# error "Must have CONFIG_PM_IDLEENTER_THRESH < CONFIG_PM_IDLEEXIT_THRESH
+# error "Must have CONFIG_PM_IDLEENTER_THRESH < CONFIG_PM_IDLEEXIT_THRESH"
#endif
#ifndef CONFIG_PM_IDLEENTER_COUNT
@@ -181,7 +181,7 @@
#endif
#if CONFIG_PM_STANDBYENTER_THRESH >= CONFIG_PM_STANDBYEXIT_THRESH
-# error "Must have CONFIG_PM_STANDBYENTER_THRESH < CONFIG_PM_STANDBYEXIT_THRESH
+# error "Must have CONFIG_PM_STANDBYENTER_THRESH < CONFIG_PM_STANDBYEXIT_THRESH"
#endif
#ifndef CONFIG_PM_STANDBYENTER_COUNT
@@ -199,7 +199,7 @@
#endif
#if CONFIG_PM_SLEEPENTER_THRESH >= CONFIG_PM_SLEEPEXIT_THRESH
-# error "Must have CONFIG_PM_SLEEPENTER_THRESH < CONFIG_PM_SLEEPEXIT_THRESH
+# error "Must have CONFIG_PM_SLEEPENTER_THRESH < CONFIG_PM_SLEEPEXIT_THRESH"
#endif
#ifndef CONFIG_PM_SLEEPENTER_COUNT
diff --git a/nuttx/include/nuttx/sched.h b/nuttx/include/nuttx/sched.h
index 241af6210..6eaba6e9c 100644
--- a/nuttx/include/nuttx/sched.h
+++ b/nuttx/include/nuttx/sched.h
@@ -138,11 +138,11 @@ typedef union entry_u entry_t;
*/
#ifdef CONFIG_SCHED_ATEXIT
-typedef void (*atexitfunc_t)(void);
+typedef CODE void (*atexitfunc_t)(void);
#endif
#ifdef CONFIG_SCHED_ONEXIT
-typedef void (*onexitfunc_t)(int exitcode, FAR void *arg);
+typedef CODE void (*onexitfunc_t)(int exitcode, FAR void *arg);
#endif
/* POSIX Message queue */
@@ -163,24 +163,40 @@ typedef struct environ_s environ_t;
# define SIZEOF_ENVIRON_T(alloc) (sizeof(environ_t) + alloc - 1)
#endif
-/* This structure describes a reference counted D-Space region */
+/* This structure describes a reference counted D-Space region. This must be a
+ * separately allocated "break-away" structure that can be owned by a task and
+ * any pthreads created by the task.
+ */
+#ifdef CONFIG_PIC
struct dspace_s
{
- uint32_t crefs; /* This is the number of pthreads that shared the
- * the same D-Space */
- uint8_t region[1]; /* Beginning of the allocated region */
-};
+ /* The life of the structure allocation is determined by this reference
+ * count. This count is number of threads that shared the the same D-Space.
+ * This includes the parent task as well as any pthreads created by the
+ * parent task or any of its child threads.
+ */
-#define SIZEOF_DSPACE_S(n) (sizeof(struct dspace_s) - 1 + (n))
+ uint16_t crefs;
-/* This is the task control block (TCB) */
+ /* This is the allocated D-Space memory region. This may be a physical
+ * address allocated with kmalloc(), or it may be virtual address associated
+ * with an address environment (if CONFIG_ADDRENV=y).
+ */
+
+ FAR uint8_t *region;
+};
+#endif
+
+/* This is the task control block (TCB). Each task or thread is represented by
+ * a TCB. The TCB is the heart of the NuttX task-control logic.
+ */
struct _TCB
{
/* Fields used to support list management *************************************/
- FAR struct _TCB *flink; /* link in DQ of TCBs */
+ FAR struct _TCB *flink; /* Doubly linked list */
FAR struct _TCB *blink;
/* Task Management Fields *****************************************************/
@@ -189,7 +205,7 @@ struct _TCB
start_t start; /* Thread start function */
entry_t entry; /* Entry Point into the thread */
-#ifdef CONFIG_SCHED_ATEXIT
+#if defined(CONFIG_SCHED_ATEXIT) && !defined(CONFIG_SCHED_ONEXIT)
# if defined(CONFIG_SCHED_ATEXIT_MAX) && CONFIG_SCHED_ATEXIT_MAX > 1
atexitfunc_t atexitfunc[CONFIG_SCHED_ATEXIT_MAX];
# else
diff --git a/nuttx/include/nuttx/usb/cdcacm.h b/nuttx/include/nuttx/usb/cdcacm.h
index 307f2a597..1dca050c4 100644
--- a/nuttx/include/nuttx/usb/cdcacm.h
+++ b/nuttx/include/nuttx/usb/cdcacm.h
@@ -205,7 +205,7 @@
/* USB Controller */
#ifndef CONFIG_USBDEV_SELFPOWERED
-# define SELFPOWERED USB_CONFIG_ATT_SELFPOWER
+# define SELFPOWERED USB_CONFIG_ATTR_SELFPOWER
#else
# define SELFPOWERED (0)
#endif
diff --git a/nuttx/include/nuttx/usb/usbdev_trace.h b/nuttx/include/nuttx/usb/usbdev_trace.h
index ae8e13c3a..ab3a5f4be 100644
--- a/nuttx/include/nuttx/usb/usbdev_trace.h
+++ b/nuttx/include/nuttx/usb/usbdev_trace.h
@@ -238,10 +238,6 @@
#define USBCOMPOSITE_TRACEERR_ALLOCDEVSTRUCT 0x000a
#define USBCOMPOSITE_TRACEERR_CLASSOBJECT 0x000b
#define USBCOMPOSITE_TRACEERR_DEVREGISTER 0x000c
-#define USBCOMPOSITE_TRACEERR_INVALIDARG 0x000d
-#define USBCOMPOSITE_TRACEERR_INVALIDARG 0x000f
-#define USBCOMPOSITE_TRACEERR_INVALIDARG 0x0010
-#define USBCOMPOSITE_TRACEERR_INVALIDARG 0x0011
/* USB Storage driver class events ******************************************/
diff --git a/nuttx/include/nuttx/vt100.h b/nuttx/include/nuttx/vt100.h
index d834f48f0..32344a1de 100644
--- a/nuttx/include/nuttx/vt100.h
+++ b/nuttx/include/nuttx/vt100.h
@@ -179,8 +179,8 @@
#define VT52_CLEAREOL {ASCII_ESC, 'K'} /* Erase to end of current line */
#define VT52_CLEAREOS {ASCII_ESC, 'J'} /* Erase to end of screen */
-#define VT52_IDENT {ASCII_ESC, 'Z'} /* dentify what the terminal is */
-#define VT52_IDENTRESP {ASCII_ESC, '/', 'Z'} /* Correct response to ident */
+#define VT52_IDENT {ASCII_ESC, 'Z'} /* Identify what the terminal is */
+#define VT52_IDENTRESP {ASCII_ESC, '/', 'Z'} /* Correct response to ident */
/* VT100 Special Key Codes
*
diff --git a/nuttx/include/nuttx/wqueue.h b/nuttx/include/nuttx/wqueue.h
index 644585c56..c509bf197 100644
--- a/nuttx/include/nuttx/wqueue.h
+++ b/nuttx/include/nuttx/wqueue.h
@@ -109,17 +109,35 @@
# endif
#endif
-/* Work queue IDs (indices). These are both zero if there is only one work
- * queue.
+/* Work queue IDs (indices):
+ *
+ * Kernel Work Queues:
+ * HPWORK: This ID of the high priority work queue that should only be used for
+ * hi-priority, time-critical, driver bottom-half functions.
+ *
+ * LPWORK: This is the ID of the low priority work queue that can be used for any
+ * purpose. if CONFIG_SCHED_LPWORK is not defined, then there is only one kernel
+ * work queue and LPWORK == HPWORK.
+ *
+ * User Work Queue:
+ * USRWORK: CONFIG_NUTTX_KERNEL and CONFIG_SCHED_USRWORK are defined, then NuttX
+ * will also support a user-accessible work queue. Otherwise, USRWORK == LPWORK.
*/
#define HPWORK 0
#ifdef CONFIG_SCHED_LPWORK
-# define LPWORK 1
+# define LPWORK (HPWORK+1)
#else
# define LPWORK HPWORK
#endif
+#if defined(CONFIG_NUTTX_KERNEL) && defined(CONFIG_SCHED_USRWORK)
+# warning "Feature not implemented"
+# define USRWORK (LPWORK+1)
+#else
+# define USRWORK LPWORK
+#endif
+
/****************************************************************************
* Public Types
****************************************************************************/
diff --git a/nuttx/include/stdbool.h b/nuttx/include/stdbool.h
index f11219912..9c16aee29 100644
--- a/nuttx/include/stdbool.h
+++ b/nuttx/include/stdbool.h
@@ -42,10 +42,33 @@
#include <nuttx/config.h>
+/* If CONFIG_ARCH_STDBOOL_H is set, then the archecture will provide its own
+ * stdbool.h file. In this case, this header file will simply re-direct to
+ * the architecture-specfiic stdbool.h header file.
+ */
+
#ifdef CONFIG_ARCH_STDBOOL_H
# include <arch/stdbool.h>
+
+/* NuttX will insist that the sizeof(bool) is 8-bits. The sizeof of _Bool
+ * used by any specific compiler is implementation specific: It can vary from
+ * compiler-to-compiler and even vary between different versions of the same
+ * compiler. Compilers seems to be converging to sizeof(_Bool) == 1. If that
+ * is true for your compiler, you should define CONFIG_C99_BOOL8 in your NuttX
+ * configuration for better standards compatibility.
+ *
+ * CONFIG_C99_BOOL8 - Means (1) your C++ compiler has sizeof(_Bool) == 8,
+ * (2) your C compiler supports the C99 _Bool intrinsic type, and (2) that
+ * the C99 _Bool type also has size 1.
+ */
+
#else
+
+ /* nuttx/compiler.h may also define or undefine CONFIG_C99_BOOL8 */
+
# include <nuttx/compiler.h>
+
+#if !defined(__cplusplus) || !defined(CONFIG_C99_BOOL8)
# include <stdint.h>
/****************************************************************************
@@ -58,10 +81,15 @@
* NOTE: Under C99 'bool' is required to be defined to be the intrinsic type
* _Bool. However, in this NuttX context, we need backward compatibility
* to pre-C99 standards where _Bool is not an intrinsic type. Hence, we
- * use _Bool8 as the underlying type.
+ * use _Bool8 as the underlying type (unless CONFIG_C99_BOOL8 is defined)
*/
-#define bool _Bool8
+#ifdef CONFIG_C99_BOOL8
+# define bool _Bool
+#else
+# define bool _Bool8
+#endif
+
#define true 1
#define false 0
@@ -83,7 +111,10 @@
* as the underlying type.
*/
+#ifndef CONFIG_C99_BOOL8
typedef uint8_t _Bool8;
+#endif
+#endif /* __cplusplus && CONFIG_C99_BOOL8 */
#endif /* CONFIG_ARCH_STDBOOL_H */
#endif /* __INCLUDE_STDBOOL_H */
diff --git a/nuttx/include/stdio.h b/nuttx/include/stdio.h
index 754cedbb4..0441ea4b8 100644
--- a/nuttx/include/stdio.h
+++ b/nuttx/include/stdio.h
@@ -102,6 +102,9 @@ extern "C" {
/* ANSI-like File System Interfaces */
+/* Operations on streams (FILE) */
+
+EXTERN void clearerr(register FILE *stream);
EXTERN int fclose(FAR FILE *stream);
EXTERN int fflush(FAR FILE *stream);
EXTERN int feof(FAR FILE *stream);
@@ -120,6 +123,9 @@ EXTERN int fsetpos(FAR FILE *stream, FAR fpos_t *pos);
EXTERN long ftell(FAR FILE *stream);
EXTERN size_t fwrite(FAR const void *ptr, size_t size, size_t n_items, FAR FILE *stream);
EXTERN FAR char *gets(FAR char *s);
+EXTERN int ungetc(int c, FAR FILE *stream);
+
+/* Operations on the stdout stream, buffers, paths, and the whole printf-family */
EXTERN int printf(const char *format, ...);
EXTERN int puts(FAR const char *s);
@@ -130,7 +136,6 @@ EXTERN int snprintf(FAR char *buf, size_t size, const char *format, ...);
EXTERN int sscanf(const char *buf, const char *fmt, ...);
EXTERN void perror(FAR const char *s);
-EXTERN int ungetc(int c, FAR FILE *stream);
EXTERN int vprintf(FAR const char *format, va_list ap);
EXTERN int vfprintf(FAR FILE *stream, const char *format, va_list ap);
EXTERN int vdprintf(FAR int fd, const char *format, va_list ap);
diff --git a/nuttx/include/termios.h b/nuttx/include/termios.h
index c8f590a5b..3032e4746 100644
--- a/nuttx/include/termios.h
+++ b/nuttx/include/termios.h
@@ -98,20 +98,20 @@
/* Control Modes (c_cflag in the termios structure) */
-#define CSIZE (3 << 0) /* Bits 0-1: Character size: */
-# define CS5 (0 << 0) /* 5 bits */
-# define CS6 (1 << 0) /* 6 bits */
-# define CS7 (2 << 0) /* 7 bits */
-# define CS8 (3 << 0) /* 8 bits */
-#define CSTOPB (1 << 2) /* Bit 2: Send two stop bits, else one */
-#define CREAD (1 << 3) /* Bit 3: Enable receiver */
-#define PARENB (1 << 4) /* Bit 4: Parity enable */
-#define PARODD (1 << 5) /* Bit 5: Odd parity, else even */
-#define HUPCL (1 << 6) /* Bit 6: Hang up on last close */
-#define CLOCAL (1 << 7) /* Bit 7: Ignore modem status lines */
-#define CCTS_OFLOW (1 << 8) /* Bit 8: CTS flow control of output */
-#define CRTSCTS CCTS_OFLOW
-#define CRTS_IFLOW (1 << 9) /* Bit 9: RTS flow control of input */
+#define CSIZE (3 << 0) /* Bits 0-1: Character size: */
+# define CS5 (0 << 0) /* 5 bits */
+# define CS6 (1 << 0) /* 6 bits */
+# define CS7 (2 << 0) /* 7 bits */
+# define CS8 (3 << 0) /* 8 bits */
+#define CSTOPB (1 << 2) /* Bit 2: Send two stop bits, else one */
+#define CREAD (1 << 3) /* Bit 3: Enable receiver */
+#define PARENB (1 << 4) /* Bit 4: Parity enable */
+#define PARODD (1 << 5) /* Bit 5: Odd parity, else even */
+#define HUPCL (1 << 6) /* Bit 6: Hang up on last close */
+#define CLOCAL (1 << 7) /* Bit 7: Ignore modem status lines */
+#define CCTS_OFLOW (1 << 8) /* Bit 8: CTS flow control of output */
+#define CRTSCTS CCTS_OFLOW
+#define CRTS_IFLOW (1 << 9) /* Bit 9: RTS flow control of input */
/* Local Modes (c_lflag in the termios structure) */
@@ -232,7 +232,7 @@ struct termios
* cf[set|get][o|i]speed() POSIX interfaces.
*/
- speed_t c_speed; /* Input/output speed (non-POSIX)*/
+ speed_t c_speed; /* Input/output speed (non-POSIX)*/
};
/****************************************************************************
diff --git a/nuttx/include/unistd.h b/nuttx/include/unistd.h
index e2ad6ff82..681ce9e63 100644
--- a/nuttx/include/unistd.h
+++ b/nuttx/include/unistd.h
@@ -133,6 +133,7 @@ EXTERN pid_t getpid(void);
EXTERN void _exit(int status) noreturn_function;
EXTERN unsigned int sleep(unsigned int seconds);
EXTERN int usleep(useconds_t usec);
+EXTERN int pause(void);
/* File descriptor operations */