You are viewing a plain text version of this content. The canonical link for it is here.
Posted to commits@nuttx.apache.org by ag...@apache.org on 2020/04/11 20:19:54 UTC

[incubator-nuttx] branch master updated (554d56b -> 8b87baa)

This is an automated email from the ASF dual-hosted git repository.

aguettouche pushed a change to branch master
in repository https://gitbox.apache.org/repos/asf/incubator-nuttx.git.


    from 554d56b  sched/sched_setpriority.c:  DEBUGVERIFY, not DEBUGASSERT.
     new 67ec3d7  Remove CONFIG_CAN_PASS_STRUCT
     new 72104c1  nxstyle fixes
     new 8b87baa  Update README.txt files for boards using SDCC

The 3 revisions listed above as "new" are entirely new to this
repository and will be described in separate emails.  The revisions
listed as "add" were already present in the repository and have only
been added to this reference.


Summary of changes:
 arch/arm/src/cxd56xx/cxd56_gnss.c     |  33 ++++-----
 arch/arm/src/cxd56xx/cxd56_icc.c      |   5 +-
 arch/arm/src/cxd56xx/cxd56_scu.c      |  13 +---
 arch/arm/src/cxd56xx/cxd56_usbdev.c   |  24 ++++---
 binfmt/libnxflat/libnxflat_bind.c     | 125 +++++++++++++++-------------------
 boards/z80/z180/p112/README.txt       |   8 +++
 boards/z80/z80/z80sim/README.txt      |   9 +++
 fs/aio/aio_signal.c                   |  45 ++++--------
 fs/procfs/fs_procfsmeminfo.c          |  55 +++++----------
 include/arpa/inet.h                   |  52 ++++----------
 include/cxx/cstdlib                   |  41 ++++-------
 include/nuttx/compiler.h              |  59 ++++------------
 include/nuttx/kmalloc.h               |  54 ++++-----------
 include/nuttx/mm/mm.h                 |  46 ++++---------
 include/nuttx/signal.h                |  47 ++++---------
 include/signal.h                      |  62 +++++++----------
 include/stdlib.h                      |  47 ++++---------
 libs/libc/libc.csv                    |   3 +-
 libs/libc/net/lib_inetntoa.c          |  55 ++++-----------
 libs/libc/stdlib/lib_div.c            |   4 --
 libs/libc/stdlib/lib_ldiv.c           |   4 --
 libs/libc/stdlib/lib_lldiv.c          |   4 +-
 mm/kmm_heap/kmm_mallinfo.c            |  49 ++++---------
 mm/umm_heap/umm_mallinfo.c            |  50 ++++----------
 sched/pthread/pthread_condtimedwait.c |   4 --
 sched/signal/sig_notification.c       |  10 +--
 sched/signal/sig_queue.c              |  63 ++++-------------
 sched/timer/timer_settime.c           |  34 ---------
 28 files changed, 306 insertions(+), 699 deletions(-)


[incubator-nuttx] 01/03: Remove CONFIG_CAN_PASS_STRUCT

Posted by ag...@apache.org.
This is an automated email from the ASF dual-hosted git repository.

aguettouche pushed a commit to branch master
in repository https://gitbox.apache.org/repos/asf/incubator-nuttx.git

commit 67ec3d7926d871c515fb1a55a11da8630fe53649
Author: Gregory Nutt <gn...@nuttx.org>
AuthorDate: Sat Apr 11 11:17:55 2020 -0600

    Remove CONFIG_CAN_PASS_STRUCT
    
    This commit resolves issue #620:
    
    Remove CONFIG_CAN_PASS_STRUCTS #620
    
    The configuration option CONFIG_CAN_PASS_STRUCTS was added many years ago to support an old version of the SDCC compiler. That compiler is currently used only with the Z80 and Z180 targets. The limitation of that old compiler was that it could not pass structures or unions as either inputs or outputs. For example:
    
        #ifdef CONFIG_CAN_PASS_STRUCTS
        struct mallinfo mallinfo(void);
        #else
        int      mallinfo(FAR struct mallinfo *info);
        #endif
    
    And even leads to violation of a few POSIX interfaces like:
    
        #ifdef CONFIG_CAN_PASS_STRUCTS
        int  sigqueue(int pid, int signo, union sigval value);
        #else
        int  sigqueue(int pid, int signo, FAR void *sival_ptr);
        #endif
    
    This breaks the 1st INVIOLABLES rule:
    
    Strict POSIX compliance
    -----------------------
    
      o Strict conformance to the portable standard OS interface as defined at
        OpenGroup.org.
      o A deeply embedded system requires some special support.  Special
        support must be minimized.
      o The portable interface must never be compromised only for the sake of
        expediency.
      o Expediency or even improved performance are not justifications for
       violation of the strict POSIX interface
    
    Also, it appears that the current SDCC compilers have resolve this issue and so, perhaps, this is no longer a problem: z88dk/z88dk#1132
    
    NOTE:  This commit cannot pass the PR checks because it depends on matching changes to the apps/ directory.
---
 arch/arm/src/cxd56xx/cxd56_gnss.c     |  5 +--
 arch/arm/src/cxd56xx/cxd56_icc.c      |  5 +--
 arch/arm/src/cxd56xx/cxd56_scu.c      | 13 ++------
 arch/arm/src/cxd56xx/cxd56_usbdev.c   |  4 ---
 binfmt/libnxflat/libnxflat_bind.c     | 48 ++++++++------------------
 fs/aio/aio_signal.c                   | 45 +++++++------------------
 fs/procfs/fs_procfsmeminfo.c          | 49 +++++++--------------------
 include/arpa/inet.h                   | 49 +++++++--------------------
 include/cxx/cstdlib                   | 41 +++++++----------------
 include/nuttx/compiler.h              | 55 +++++++-----------------------
 include/nuttx/kmalloc.h               | 54 ++++++++----------------------
 include/nuttx/mm/mm.h                 | 46 ++++++++-----------------
 include/nuttx/signal.h                | 47 ++++++++------------------
 include/signal.h                      | 47 +++++++-------------------
 include/stdlib.h                      | 45 +++++++------------------
 libs/libc/libc.csv                    |  3 +-
 libs/libc/net/lib_inetntoa.c          | 51 ++++++++--------------------
 libs/libc/stdlib/lib_div.c            |  4 ---
 libs/libc/stdlib/lib_ldiv.c           |  4 ---
 libs/libc/stdlib/lib_lldiv.c          |  4 +--
 mm/kmm_heap/kmm_mallinfo.c            | 49 +++++++--------------------
 mm/umm_heap/umm_mallinfo.c            | 50 +++++++--------------------
 sched/pthread/pthread_condtimedwait.c |  4 ---
 sched/signal/sig_notification.c       | 10 +-----
 sched/signal/sig_queue.c              | 63 ++++++++---------------------------
 sched/timer/timer_settime.c           | 34 -------------------
 26 files changed, 197 insertions(+), 632 deletions(-)

diff --git a/arch/arm/src/cxd56xx/cxd56_gnss.c b/arch/arm/src/cxd56xx/cxd56_gnss.c
index b984c38..ace24a8 100644
--- a/arch/arm/src/cxd56xx/cxd56_gnss.c
+++ b/arch/arm/src/cxd56xx/cxd56_gnss.c
@@ -2154,13 +2154,10 @@ static void cxd56_gnss_common_signalhandler(uint32_t data,
       struct cxd56_gnss_sig_s *sig = &priv->sigs[i];
       if (sig->enable && sig->info.gnsssig == sigtype)
         {
-#ifdef CONFIG_CAN_PASS_STRUCTS
           union sigval value;
+
           value.sival_ptr = &sig->info;
           sigqueue(sig->pid, sig->info.signo, value);
-#else
-          sigqueue(sig->pid, sig->info.signo, &sig->info);
-#endif
           issetmask = 1;
         }
     }
diff --git a/arch/arm/src/cxd56xx/cxd56_icc.c b/arch/arm/src/cxd56xx/cxd56_icc.c
index 74c7b37..aa6be14 100644
--- a/arch/arm/src/cxd56xx/cxd56_icc.c
+++ b/arch/arm/src/cxd56xx/cxd56_icc.c
@@ -251,13 +251,10 @@ static int icc_irqhandler(int cpuid, uint32_t word[2])
 #ifndef CONFIG_DISABLE_SIGNAL
   if (priv->pid != INVALID_PROCESS_ID)
     {
-#  ifdef CONFIG_CAN_PASS_STRUCTS
       union sigval value;
+
       value.sival_ptr = priv->sigdata;
       sigqueue(priv->pid, priv->signo, value);
-#  else
-      sigqueue(priv->pid, priv->signo, priv->sigdata);
-#  endif
     }
 #endif
 
diff --git a/arch/arm/src/cxd56xx/cxd56_scu.c b/arch/arm/src/cxd56xx/cxd56_scu.c
index cb927fb..67fe218 100644
--- a/arch/arm/src/cxd56xx/cxd56_scu.c
+++ b/arch/arm/src/cxd56xx/cxd56_scu.c
@@ -1490,9 +1490,7 @@ static void seq_handlefifointr(FAR struct cxd56_scudev_s *priv,
   int i;
 #ifndef CONFIG_DISABLE_SIGNAL
   struct wm_notify_s *notify;
-#  ifdef CONFIG_CAN_PASS_STRUCTS
   union sigval value;
-#  endif
 #endif
 
   if ((intr & 0x007ffe00) == 0)
@@ -1520,12 +1518,8 @@ static void seq_handlefifointr(FAR struct cxd56_scudev_s *priv,
 
           DEBUGASSERT(notify->pid != 0);
 
-#  ifdef CONFIG_CAN_PASS_STRUCTS
           value.sival_ptr = notify->ts;
           sigqueue(notify->pid, notify->signo, value);
-#  else
-          sigqueue(notify->pid, notify->signo, (FAR void *)notify->ts);
-#  endif
 #endif
         }
     }
@@ -1611,15 +1605,12 @@ static void seq_handlemathfintr(FAR struct cxd56_scudev_s *priv,
 #ifndef CONFIG_DISABLE_SIGNAL
       if (detected)
         {
+          union sigval value;
+
           DEBUGASSERT(notify->pid != 0);
 
-#  ifdef CONFIG_CAN_PASS_STRUCTS
-          union sigval value;
           value.sival_ptr = notify->arg;
           sigqueue(notify->pid, notify->signo, value);
-#  else
-          sigqueue(notify->pid, notify->signo, (FAR void *)notify->arg);
-#  endif
           detected = 0;
         }
 #endif
diff --git a/arch/arm/src/cxd56xx/cxd56_usbdev.c b/arch/arm/src/cxd56xx/cxd56_usbdev.c
index 120dcd5..ba282d1 100644
--- a/arch/arm/src/cxd56xx/cxd56_usbdev.c
+++ b/arch/arm/src/cxd56xx/cxd56_usbdev.c
@@ -3392,13 +3392,9 @@ static void cxd56_notify_signal(uint16_t state, uint16_t power)
 
   if (priv->signo > 0)
     {
-#ifdef CONFIG_CAN_PASS_STRUCTS
       union sigval value;
       value.sival_int = state << 16 | power;
       sigqueue(priv->pid, priv->signo, value);
-#else
-      sigqueue(priv->pid, priv->signo, state << 16 | power);
-#endif
     }
 }
 
diff --git a/binfmt/libnxflat/libnxflat_bind.c b/binfmt/libnxflat/libnxflat_bind.c
index 1ac9f4d..4267264 100644
--- a/binfmt/libnxflat/libnxflat_bind.c
+++ b/binfmt/libnxflat/libnxflat_bind.c
@@ -1,35 +1,20 @@
 /****************************************************************************
  * binfmt/libnxflat/libnxflat_bind.c
  *
- *   Copyright (C) 2009, 2020 Gregory Nutt. All rights reserved.
- *   Author: Gregory Nutt <gn...@nuttx.org>
+ * Licensed to the Apache Software Foundation (ASF) under one or more
+ * contributor license agreements.  See the NOTICE file distributed with
+ * this work for additional information regarding copyright ownership.  The
+ * ASF licenses this file to you under the Apache License, Version 2.0 (the
+ * "License"); you may not use this file except in compliance with the
+ * License.  You may obtain a copy of the License at
  *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
+ *   http://www.apache.org/licenses/LICENSE-2.0
  *
- * 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.
+ * Unless required by applicable law or agreed to in writing, software
+ * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
+ * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.  See the
+ * License for the specific language governing permissions and limitations
+ * under the License.
  *
  ****************************************************************************/
 
@@ -277,14 +262,9 @@ static inline int nxflat_gotrelocs(FAR struct nxflat_loadinfo_s *loadinfo)
     {
       /* Handle the relocation by the relocation type */
 
-#ifdef CONFIG_CAN_PASS_STRUCTS
-      reloc = *relocs++;
-#else
-      memcpy(&reloc, relocs, sizeof(struct nxflat_reloc_s));
-      relocs++;
-#endif
-
+      reloc  = *relocs++;
       result = OK;
+
       switch (NXFLAT_RELOC_TYPE(reloc.r_info))
         {
         /* NXFLAT_RELOC_TYPE_REL32I  Meaning: Object file contains a 32-bit
diff --git a/fs/aio/aio_signal.c b/fs/aio/aio_signal.c
index 85e058a..f0ba64a 100644
--- a/fs/aio/aio_signal.c
+++ b/fs/aio/aio_signal.c
@@ -1,35 +1,20 @@
 /****************************************************************************
  * fs/aio/aio_signal.c
  *
- *   Copyright (C) 2014-2015, 2018 Gregory Nutt. All rights reserved.
- *   Author: Gregory Nutt <gn...@nuttx.org>
+ * Licensed to the Apache Software Foundation (ASF) under one or more
+ * contributor license agreements.  See the NOTICE file distributed with
+ * this work for additional information regarding copyright ownership.  The
+ * ASF licenses this file to you under the Apache License, Version 2.0 (the
+ * "License"); you may not use this file except in compliance with the
+ * License.  You may obtain a copy of the License at
  *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
+ *   http://www.apache.org/licenses/LICENSE-2.0
  *
- * 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.
+ * Unless required by applicable law or agreed to in writing, software
+ * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
+ * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.  See the
+ * License for the specific language governing permissions and limitations
+ * under the License.
  *
  ****************************************************************************/
 
@@ -79,9 +64,7 @@
 
 int aio_signal(pid_t pid, FAR struct aiocb *aiocbp)
 {
-#ifdef CONFIG_CAN_PASS_STRUCTS
   union sigval value;
-#endif
   int status;
   int ret;
 
@@ -102,12 +85,8 @@ int aio_signal(pid_t pid, FAR struct aiocb *aiocbp)
    * on sig_suspend();
    */
 
-#ifdef CONFIG_CAN_PASS_STRUCTS
   value.sival_ptr = aiocbp;
   status = nxsig_queue(pid, SIGPOLL, value);
-#else
-  status = nxsig_queue(pid, SIGPOLL, aiocbp);
-#endif
   if (status < 0)
     {
       ferr("ERROR: nxsig_queue #2 failed: %d\n", status);
diff --git a/fs/procfs/fs_procfsmeminfo.c b/fs/procfs/fs_procfsmeminfo.c
index 2a9d4bb..d1f0dec 100644
--- a/fs/procfs/fs_procfsmeminfo.c
+++ b/fs/procfs/fs_procfsmeminfo.c
@@ -1,35 +1,20 @@
 /****************************************************************************
  * fs/procfs/fs_procfsmeminfo.c
  *
- *   Copyright (C) 2016-2017 Gregory Nutt. All rights reserved.
- *   Author: Gregory Nutt <gn...@nuttx.org>
+ * Licensed to the Apache Software Foundation (ASF) under one or more
+ * contributor license agreements.  See the NOTICE file distributed with
+ * this work for additional information regarding copyright ownership.  The
+ * ASF licenses this file to you under the Apache License, Version 2.0 (the
+ * "License"); you may not use this file except in compliance with the
+ * License.  You may obtain a copy of the License at
  *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
+ *   http://www.apache.org/licenses/LICENSE-2.0
  *
- * 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.
+ * Unless required by applicable law or agreed to in writing, software
+ * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
+ * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.  See the
+ * License for the specific language governing permissions and limitations
+ * under the License.
  *
  ****************************************************************************/
 
@@ -312,12 +297,7 @@ static ssize_t meminfo_read(FAR struct file *filep, FAR char *buffer,
 
       /* Show kernel heap information */
 
-#ifdef CONFIG_CAN_PASS_STRUCTS
       mem        = kmm_mallinfo();
-#else
-      kmm_mallinfo(&mem);
-#endif
-
       linesize   = snprintf(procfile->line, MEMINFO_LINELEN,
                             "Kmem:  %11lu%11lu%11lu%11lu\n",
                             (unsigned long)mem.arena,
@@ -338,12 +318,7 @@ static ssize_t meminfo_read(FAR struct file *filep, FAR char *buffer,
 
       /* Show user heap information */
 
-#ifdef CONFIG_CAN_PASS_STRUCTS
       mem        = kumm_mallinfo();
-#else
-      kumm_mallinfo(&mem);
-#endif
-
       linesize   = snprintf(procfile->line, MEMINFO_LINELEN,
                             "Umem:  %11lu%11lu%11lu%11lu\n",
                             (unsigned long)mem.arena,
diff --git a/include/arpa/inet.h b/include/arpa/inet.h
index 26b9e31..afb9d06 100644
--- a/include/arpa/inet.h
+++ b/include/arpa/inet.h
@@ -1,35 +1,20 @@
 /****************************************************************************
  * include/arpa/inet.h
  *
- *   Copyright (C) 2007, 2009 Gregory Nutt. All rights reserved.
- *   Author: Gregory Nutt <gn...@nuttx.org>
+ * Licensed to the Apache Software Foundation (ASF) under one or more
+ * contributor license agreements.  See the NOTICE file distributed with
+ * this work for additional information regarding copyright ownership.  The
+ * ASF licenses this file to you under the Apache License, Version 2.0 (the
+ * "License"); you may not use this file except in compliance with the
+ * License.  You may obtain a copy of the License at
  *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
+ *   http://www.apache.org/licenses/LICENSE-2.0
  *
- * 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 Gregory Nutt 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.
+ * Unless required by applicable law or agreed to in writing, software
+ * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
+ * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.  See the
+ * License for the specific language governing permissions and limitations
+ * under the License.
  *
  ****************************************************************************/
 
@@ -112,20 +97,10 @@ int         inet_aton(FAR const char *cp, FAR struct in_addr *inp);
 in_addr_t   inet_addr(FAR const char *cp);
 in_addr_t   inet_network(FAR const char *cp);
 
-#ifdef CONFIG_CAN_PASS_STRUCTS
 FAR char   *inet_ntoa(struct in_addr in);
 in_addr_t   inet_lnaof(struct in_addr in);
 in_addr_t   inet_netof(struct in_addr in);
-#else
-FAR char   *_inet_ntoa(in_addr_t in);
-# define inet_ntoa(in) _inet_ntoa(in.s_addr)
 
-in_addr_t   _inet_lnaof(in_addr_t in);
-# define inet_lnaof(in) _inet_lnaof(in.s_addr)
-
-in_addr_t   _inet_netof(in_addr_t in);
-# define inet_netof(in) _inet_netof(in.s_addr)
-#endif
 struct in_addr inet_makeaddr(in_addr_t net, in_addr_t host);
 
 int         inet_pton(int af, FAR const char *src, FAR void *dst);
diff --git a/include/cxx/cstdlib b/include/cxx/cstdlib
index 714319e..cf12ddf 100644
--- a/include/cxx/cstdlib
+++ b/include/cxx/cstdlib
@@ -1,35 +1,20 @@
 //***************************************************************************
 // include/cxx/cstdlib
 //
-//   Copyright (C) 2009, 2012, 2015-2017 Gregory Nutt. All rights reserved.
-//   Author: Gregory Nutt <gn...@nuttx.org>
+// Licensed to the Apache Software Foundation (ASF) under one or more
+// contributor license agreements.  See the NOTICE file distributed with
+// this work for additional information regarding copyright ownership.  The
+// ASF licenses this file to you under the Apache License, Version 2.0 (the
+// "License"); you may not use this file except in compliance with the
+// License.  You may obtain a copy of the License at
 //
-// Redistribution and use in source and binary forms, with or without
-// modification, are permitted provided that the following conditions
-// are met:
+//   http://www.apache.org/licenses/LICENSE-2.0
 //
-// 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.
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
+// WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.  See the
+// License for the specific language governing permissions and limitations
+// under the License.
 //
 //***************************************************************************
 
@@ -138,13 +123,11 @@ namespace std
   using ::llabs;
 #endif
 
-#ifdef CONFIG_CAN_PASS_STRUCTS
   using ::div;
   using ::ldiv;
 #ifdef CONFIG_HAVE_LONG_LONG
   using ::lldiv;
 #endif
-#endif
 
   // Temporary files
 
diff --git a/include/nuttx/compiler.h b/include/nuttx/compiler.h
index b027ae6..aef87bb 100644
--- a/include/nuttx/compiler.h
+++ b/include/nuttx/compiler.h
@@ -1,36 +1,20 @@
 /****************************************************************************
  * include/nuttx/compiler.h
  *
- *   Copyright (C) 2007-2009, 2012-2013, 2015-2017 Gregory Nutt. All rights
- *     reserved.
- *   Author: Gregory Nutt <gn...@nuttx.org>
+ * Licensed to the Apache Software Foundation (ASF) under one or more
+ * contributor license agreements.  See the NOTICE file distributed with
+ * this work for additional information regarding copyright ownership.  The
+ * ASF licenses this file to you under the Apache License, Version 2.0 (the
+ * "License"); you may not use this file except in compliance with the
+ * License.  You may obtain a copy of the License at
  *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
+ *   http://www.apache.org/licenses/LICENSE-2.0
  *
- * 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.
+ * Unless required by applicable law or agreed to in writing, software
+ * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
+ * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.  See the
+ * License for the specific language governing permissions and limitations
+ * under the License.
  *
  ****************************************************************************/
 
@@ -299,10 +283,6 @@
 #  define CONFIG_HAVE_DOUBLE 1
 #  define CONFIG_HAVE_LONG_DOUBLE 1
 
-/* Structures and unions can be assigned and passed as values */
-
-#  define CONFIG_CAN_PASS_STRUCTS 1
-
 /* Indicate that a local variable is not used */
 
 #  define UNUSED(a) ((void)(a))
@@ -445,12 +425,6 @@
 #  undef  CONFIG_HAVE_DOUBLE
 #  undef  CONFIG_HAVE_LONG_DOUBLE
 
-/* Structures and unions cannot be passed as values or used
- * in assignments.
- */
-
-#  undef  CONFIG_CAN_PASS_STRUCTS
-
 /* Indicate that a local variable is not used */
 
 #  define UNUSED(a) ((void)(a))
@@ -580,10 +554,6 @@
 #  undef  CONFIG_HAVE_DOUBLE
 #  undef  CONFIG_HAVE_LONG_DOUBLE
 
-/* Structures and unions can be assigned and passed as values */
-
-#  define CONFIG_CAN_PASS_STRUCTS 1
-
 /* Indicate that a local variable is not used */
 
 #  define UNUSED(a) ((void)(a))
@@ -677,7 +647,6 @@
 #  define CONFIG_HAVE_FLOAT 1
 #  undef  CONFIG_HAVE_DOUBLE
 #  undef  CONFIG_HAVE_LONG_DOUBLE
-#  undef  CONFIG_CAN_PASS_STRUCTS
 #  undef  CONFIG_HAVE_ANONYMOUS_STRUCT
 #  undef  CONFIG_HAVE_ANONYMOUS_UNION
 
diff --git a/include/nuttx/kmalloc.h b/include/nuttx/kmalloc.h
index a1d5170..6ea4d8e 100644
--- a/include/nuttx/kmalloc.h
+++ b/include/nuttx/kmalloc.h
@@ -1,36 +1,20 @@
 /****************************************************************************
  * include/nuttx/kmalloc.h
  *
- *   Copyright (C) 2007-2008, 2011, 2013, 2016, 2018 Gregory Nutt. All
- *     rights reserved.
- *   Author: Gregory Nutt <gn...@nuttx.org>
+ * Licensed to the Apache Software Foundation (ASF) under one or more
+ * contributor license agreements.  See the NOTICE file distributed with
+ * this work for additional information regarding copyright ownership.  The
+ * ASF licenses this file to you under the Apache License, Version 2.0 (the
+ * "License"); you may not use this file except in compliance with the
+ * License.  You may obtain a copy of the License at
  *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
+ *   http://www.apache.org/licenses/LICENSE-2.0
  *
- * 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.
+ * Unless required by applicable law or agreed to in writing, software
+ * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
+ * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.  See the
+ * License for the specific language governing permissions and limitations
+ * under the License.
  *
  ****************************************************************************/
 
@@ -96,11 +80,7 @@ extern "C"
 #define kumm_realloc(p,s)        realloc(p,s)
 #define kumm_memalign(a,s)       memalign(a,s)
 #define kumm_free(p)             free(p)
-#ifdef CONFIG_CAN_PASS_STRUCTS
-#  define kumm_mallinfo()        mallinfo()
-#else
-#  define kumm_mallinfo(i)       mallinfo(i)
-#endif
+#define kumm_mallinfo()          mallinfo()
 
 /* This family of allocators is used to manage kernel protected memory */
 
@@ -120,11 +100,7 @@ extern "C"
 #  define kmm_realloc(p,s)       realloc(p,s)
 #  define kmm_memalign(a,s)      memalign(a,s)
 #  define kmm_free(p)            free(p)
-#ifdef CONFIG_CAN_PASS_STRUCTS
 #  define kmm_mallinfo()         mallinfo()
-#else
-#  define kmm_mallinfo(i)        mallinfo(i)
-#endif
 
 #elif !defined(CONFIG_MM_KERNEL_HEAP)
 /* If this the kernel phase of a kernel build, and there are only user-space
@@ -143,11 +119,7 @@ extern "C"
 #  define kmm_realloc(p,s)       realloc(p,s)
 #  define kmm_memalign(a,s)      memalign(a,s)
 #  define kmm_free(p)            free(p)
-#ifdef CONFIG_CAN_PASS_STRUCTS
 #  define kmm_mallinfo()         mallinfo()
-#else
-#  define kmm_mallinfo(i)        mallinfo(i)
-#endif
 
 #else
 /* Otherwise, the kernel-space allocators are declared in
diff --git a/include/nuttx/mm/mm.h b/include/nuttx/mm/mm.h
index d32a346..4536200 100644
--- a/include/nuttx/mm/mm.h
+++ b/include/nuttx/mm/mm.h
@@ -1,36 +1,20 @@
 /****************************************************************************
  * include/nuttx/mm/mm.h
  *
- *   Copyright (C) 2007-2009, 2013-2014, 2017 Gregory Nutt.
- *    All rights reserved.
- *   Author: Gregory Nutt <gn...@nuttx.org>
+ * Licensed to the Apache Software Foundation (ASF) under one or more
+ * contributor license agreements.  See the NOTICE file distributed with
+ * this work for additional information regarding copyright ownership.  The
+ * ASF licenses this file to you under the Apache License, Version 2.0 (the
+ * "License"); you may not use this file except in compliance with the
+ * License.  You may obtain a copy of the License at
  *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
+ *   http://www.apache.org/licenses/LICENSE-2.0
  *
- * 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.
+ * Unless required by applicable law or agreed to in writing, software
+ * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
+ * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.  See the
+ * License for the specific language governing permissions and limitations
+ * under the License.
  *
  ****************************************************************************/
 
@@ -513,12 +497,8 @@ int mm_mallinfo(FAR struct mm_heap_s *heap, FAR struct mallinfo *info);
 /* Functions contained in kmm_mallinfo.c ************************************/
 
 #ifdef CONFIG_MM_KERNEL_HEAP
-#ifdef CONFIG_CAN_PASS_STRUCTS
 struct mallinfo kmm_mallinfo(void);
-#else
-int kmm_mallinfo(struct mallinfo *info);
-#endif /* CONFIG_CAN_PASS_STRUCTS */
-#endif /* CONFIG_MM_KERNEL_HEAP */
+#endif
 
 /* Functions contained in mm_shrinkchunk.c **********************************/
 
diff --git a/include/nuttx/signal.h b/include/nuttx/signal.h
index e9f0983..85f119b 100644
--- a/include/nuttx/signal.h
+++ b/include/nuttx/signal.h
@@ -1,35 +1,20 @@
 /****************************************************************************
  * include/nuttx/signal.h
  *
- *   Copyright (C) 2015, 2017 Gregory Nutt. All rights reserved.
- *   Author: Gregory Nutt <gn...@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.
+ * Licensed to the Apache Software Foundation (ASF) under one or more
+ * contributor license agreements.  See the NOTICE file distributed with
+ * this work for additional information regarding copyright ownership.  The
+ * ASF licenses this file to you under the Apache License, Version 2.0 (the
+ * "License"); you may not use this file except in compliance with the
+ * License.  You may obtain a copy of the License at
+ *
+ *   http://www.apache.org/licenses/LICENSE-2.0
+ *
+ * Unless required by applicable law or agreed to in writing, software
+ * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
+ * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.  See the
+ * License for the specific language governing permissions and limitations
+ * under the License.
  *
  ****************************************************************************/
 
@@ -230,11 +215,7 @@ int nxsig_action(int signo, FAR const struct sigaction *act,
  *
  ****************************************************************************/
 
-#ifdef CONFIG_CAN_PASS_STRUCTS
 int nxsig_queue(int pid, int signo, union sigval value);
-#else
-int nxsig_queue(int pid, int signo, void *sival_ptr);
-#endif
 
 /****************************************************************************
  * Name: nxsig_kill
diff --git a/include/signal.h b/include/signal.h
index 8921cc6..95f95a3 100644
--- a/include/signal.h
+++ b/include/signal.h
@@ -1,35 +1,20 @@
 /********************************************************************************
  * include/signal.h
  *
- *   Copyright (C) 2007-2009, 2011, 2013-2018 Gregory Nutt. All rights reserved.
- *   Author: Gregory Nutt <gn...@nuttx.org>
+ * Licensed to the Apache Software Foundation (ASF) under one or more
+ * contributor license agreements.  See the NOTICE file distributed with
+ * this work for additional information regarding copyright ownership.  The
+ * ASF licenses this file to you under the Apache License, Version 2.0 (the
+ * "License"); you may not use this file except in compliance with the
+ * License.  You may obtain a copy of the License at
  *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
+ *   http://www.apache.org/licenses/LICENSE-2.0
  *
- * 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.
+ * Unless required by applicable law or agreed to in writing, software
+ * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
+ * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.  See the
+ * License for the specific language governing permissions and limitations
+ * under the License.
  *
  ********************************************************************************/
 
@@ -305,11 +290,7 @@ union sigval
  * available on a queue
  */
 
-#ifdef CONFIG_CAN_PASS_STRUCTS
 typedef CODE void (*sigev_notify_function_t)(union sigval value);
-#else
-typedef CODE void (*sigev_notify_function_t)(FAR void *sival_ptr);
-#endif
 
 struct sigevent
 {
@@ -400,11 +381,7 @@ _sa_handler_t signal(int signo, _sa_handler_t func);
 int  sigpause(int signo);
 int  sigpending(FAR sigset_t *set);
 int  sigprocmask(int how, FAR const sigset_t *set, FAR sigset_t *oset);
-#ifdef CONFIG_CAN_PASS_STRUCTS
 int  sigqueue(int pid, int signo, union sigval value);
-#else
-int  sigqueue(int pid, int signo, FAR void *sival_ptr);
-#endif
 int  sigrelse(int signo);
 _sa_handler_t sigset(int signo, _sa_handler_t func);
 int  sigwait(FAR const sigset_t *set, FAR int *sig);
diff --git a/include/stdlib.h b/include/stdlib.h
index 60e7e7b..16912df 100644
--- a/include/stdlib.h
+++ b/include/stdlib.h
@@ -1,35 +1,20 @@
 /****************************************************************************
  * include/stdlib.h
  *
- *   Copyright (C) 2007-2016, 2018 Gregory Nutt. All rights reserved.
- *   Author: Gregory Nutt <gn...@nuttx.org>
+ * Licensed to the Apache Software Foundation (ASF) under one or more
+ * contributor license agreements.  See the NOTICE file distributed with
+ * this work for additional information regarding copyright ownership.  The
+ * ASF licenses this file to you under the Apache License, Version 2.0 (the
+ * "License"); you may not use this file except in compliance with the
+ * License.  You may obtain a copy of the License at
  *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
+ *   http://www.apache.org/licenses/LICENSE-2.0
  *
- * 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.
+ * Unless required by applicable law or agreed to in writing, software
+ * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
+ * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.  See the
+ * License for the specific language governing permissions and limitations
+ * under the License.
  *
  ****************************************************************************/
 
@@ -231,11 +216,7 @@ FAR void *memalign(size_t, size_t);
 FAR void *zalloc(size_t);
 FAR void *calloc(size_t, size_t);
 
-#ifdef CONFIG_CAN_PASS_STRUCTS
 struct mallinfo mallinfo(void);
-#else
-int      mallinfo(FAR struct mallinfo *info);
-#endif
 
 /* Pseudo-Terminals */
 
@@ -260,13 +241,11 @@ long int labs(long int j);
 long long int llabs(long long int j);
 #endif
 
-#ifdef CONFIG_CAN_PASS_STRUCTS
 div_t    div(int number, int denom);
 ldiv_t   ldiv(long number, long denom);
 #ifdef CONFIG_HAVE_LONG_LONG
 lldiv_t  lldiv(long long number, long long denom);
 #endif
-#endif
 
 /* Temporary files */
 
diff --git a/libs/libc/libc.csv b/libs/libc/libc.csv
index ee6c542..a979851 100644
--- a/libs/libc/libc.csv
+++ b/libs/libc/libc.csv
@@ -1,4 +1,3 @@
-"_inet_ntoa","arpa/inet.h","defined(CONFIG_NET_IPv4) && !defined(CONFIG_CAN_PASS_STRUCTS)","FAR char","in_addr_t"
 "abort","stdlib.h","","void"
 "abs","stdlib.h","","int","int"
 "aio_error","aio.h","defined(CONFIG_FS_AIO)","int","FAR struct aiocb *"
@@ -62,7 +61,7 @@
 "htons","arpa/inet.h","","uint16_t","uint16_t"
 "imaxabs","inttypes.h","","intmax_t","intmax_t"
 "inet_addr","arpa/inet.h","","in_addr_t","FAR const char "
-"inet_ntoa","arpa/inet.h","defined(CONFIG_NET_IPv4) && defined(CONFIG_CAN_PASS_STRUCTS)","FAR char","struct in_addr"
+"inet_ntoa","arpa/inet.h","defined(CONFIG_NET_IPv4)","FAR char","struct in_addr"
 "inet_ntop","arpa/inet.h","","FAR const char","int","FAR const void *","FAR char *","socklen_t"
 "inet_pton","arpa/inet.h","","int","int","FAR const char *","FAR void *"
 "ioctl","sys/ioctl.h","defined(CONFIG_LIBC_IOCTL_VARIADIC)","int","int","int","..."
diff --git a/libs/libc/net/lib_inetntoa.c b/libs/libc/net/lib_inetntoa.c
index 62b1416..e4078eb 100644
--- a/libs/libc/net/lib_inetntoa.c
+++ b/libs/libc/net/lib_inetntoa.c
@@ -1,35 +1,20 @@
 /****************************************************************************
  * libs/libc/net/lib_inetntoa.c
  *
- *   Copyright (C) 2007-2008, 2011-2012, 2015 Gregory Nutt. All rights reserved.
- *   Author: Gregory Nutt <gn...@nuttx.org>
+ * Licensed to the Apache Software Foundation (ASF) under one or more
+ * contributor license agreements.  See the NOTICE file distributed with
+ * this work for additional information regarding copyright ownership.  The
+ * ASF licenses this file to you under the Apache License, Version 2.0 (the
+ * "License"); you may not use this file except in compliance with the
+ * License.  You may obtain a copy of the License at
  *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
+ *   http://www.apache.org/licenses/LICENSE-2.0
  *
- * 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.
+ * Unless required by applicable law or agreed to in writing, software
+ * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
+ * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.  See the
+ * License for the specific language governing permissions and limitations
+ * under the License.
  *
  ****************************************************************************/
 
@@ -61,7 +46,6 @@
  *
  ****************************************************************************/
 
-#ifdef CONFIG_CAN_PASS_STRUCTS
 FAR char *inet_ntoa(struct in_addr in)
 {
   static char buffer[INET_ADDRSTRLEN + 2];
@@ -70,14 +54,5 @@ FAR char *inet_ntoa(struct in_addr in)
            ptr[0], ptr[1], ptr[2], ptr[3]);
   return buffer;
 }
-#else
-FAR char *_inet_ntoa(in_addr_t in)
-{
-  static char buffer[INET_ADDRSTRLEN + 2];
-  FAR unsigned char *ptr = (FAR unsigned char *)&in;
-  snprintf(buffer, INET_ADDRSTRLEN + 2, "%u.%u.%u.%u",
-           ptr[0], ptr[1], ptr[2], ptr[3]);
-  return buffer;
-}
-#endif
+
 #endif /* CONFIG_NET_IPv4 || CONFIG_LIBC_IPv4_ADDRCONV */
diff --git a/libs/libc/stdlib/lib_div.c b/libs/libc/stdlib/lib_div.c
index 62474dc..780100b 100644
--- a/libs/libc/stdlib/lib_div.c
+++ b/libs/libc/stdlib/lib_div.c
@@ -42,8 +42,6 @@
 
 #include <stdlib.h>
 
-#ifdef CONFIG_CAN_PASS_STRUCTS
-
 /****************************************************************************
  * Public Functions
  ****************************************************************************/
@@ -76,5 +74,3 @@ div_t div(int numer, int denom)
   f.rem  = numer % denom;
   return f;
 }
-
-#endif /* CONFIG_CAN_PASS_STRUCTS */
diff --git a/libs/libc/stdlib/lib_ldiv.c b/libs/libc/stdlib/lib_ldiv.c
index d7cd499..1c86649 100644
--- a/libs/libc/stdlib/lib_ldiv.c
+++ b/libs/libc/stdlib/lib_ldiv.c
@@ -47,8 +47,6 @@
 
 #include <stdlib.h>
 
-#ifdef CONFIG_CAN_PASS_STRUCTS
-
 /****************************************************************************
  * Public Functions
  ****************************************************************************/
@@ -81,5 +79,3 @@ ldiv_t ldiv(long numer, long denom)
   f.rem  = numer % denom;
   return f;
 }
-
-#endif /* CONFIG_CAN_PASS_STRUCTS */
diff --git a/libs/libc/stdlib/lib_lldiv.c b/libs/libc/stdlib/lib_lldiv.c
index 8279fe9..b5c54b1 100644
--- a/libs/libc/stdlib/lib_lldiv.c
+++ b/libs/libc/stdlib/lib_lldiv.c
@@ -47,7 +47,7 @@
 
 #include <stdlib.h>
 
-#if defined(CONFIG_CAN_PASS_STRUCTS) && defined(CONFIG_HAVE_LONG_LONG)
+#if defined(CONFIG_HAVE_LONG_LONG)
 
 /****************************************************************************
  * Public Functions
@@ -82,4 +82,4 @@ lldiv_t lldiv(long long numer, long long denom)
   return f;
 }
 
-#endif /* CONFIG_CAN_PASS_STRUCTS && CONFIG_HAVE_LONG_LONG */
+#endif /* CONFIG_HAVE_LONG_LONG */
diff --git a/mm/kmm_heap/kmm_mallinfo.c b/mm/kmm_heap/kmm_mallinfo.c
index 9f812ba..c1da814 100644
--- a/mm/kmm_heap/kmm_mallinfo.c
+++ b/mm/kmm_heap/kmm_mallinfo.c
@@ -1,35 +1,20 @@
 /****************************************************************************
  * mm/kmm_heap/kmm_mallinfo.c
  *
- *   Copyright (C) 2014 Gregory Nutt. All rights reserved.
- *   Author: Gregory Nutt <gn...@nuttx.org>
+ * Licensed to the Apache Software Foundation (ASF) under one or more
+ * contributor license agreements.  See the NOTICE file distributed with
+ * this work for additional information regarding copyright ownership.  The
+ * ASF licenses this file to you under the Apache License, Version 2.0 (the
+ * "License"); you may not use this file except in compliance with the
+ * License.  You may obtain a copy of the License at
  *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
+ *   http://www.apache.org/licenses/LICENSE-2.0
  *
- * 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.
+ * Unless required by applicable law or agreed to in writing, software
+ * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
+ * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.  See the
+ * License for the specific language governing permissions and limitations
+ * under the License.
  *
  ****************************************************************************/
 
@@ -58,8 +43,6 @@
  *
  ****************************************************************************/
 
-#ifdef CONFIG_CAN_PASS_STRUCTS
-
 struct mallinfo kmm_mallinfo(void)
 {
   struct mallinfo info;
@@ -67,12 +50,4 @@ struct mallinfo kmm_mallinfo(void)
   return info;
 }
 
-#else
-
-int kmm_mallinfo(struct mallinfo *info)
-{
-  return mm_mallinfo(&g_kmmheap, info);
-}
-
-#endif /* CONFIG_CAN_PASS_STRUCTS */
 #endif /* CONFIG_MM_KERNEL_HEAP */
diff --git a/mm/umm_heap/umm_mallinfo.c b/mm/umm_heap/umm_mallinfo.c
index a6c1aaa..39a4058 100644
--- a/mm/umm_heap/umm_mallinfo.c
+++ b/mm/umm_heap/umm_mallinfo.c
@@ -1,35 +1,20 @@
 /****************************************************************************
  * mm/umm_heap/umm_mallinfo.c
  *
- *   Copyright (C) 2007, 2009, 2013-2015 Gregory Nutt. All rights reserved.
- *   Author: Gregory Nutt <gn...@nuttx.org>
+ * Licensed to the Apache Software Foundation (ASF) under one or more
+ * contributor license agreements.  See the NOTICE file distributed with
+ * this work for additional information regarding copyright ownership.  The
+ * ASF licenses this file to you under the Apache License, Version 2.0 (the
+ * "License"); you may not use this file except in compliance with the
+ * License.  You may obtain a copy of the License at
  *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
+ *   http://www.apache.org/licenses/LICENSE-2.0
  *
- * 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.
+ * Unless required by applicable law or agreed to in writing, software
+ * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
+ * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.  See the
+ * License for the specific language governing permissions and limitations
+ * under the License.
  *
  ****************************************************************************/
 
@@ -58,20 +43,9 @@
  *
  ****************************************************************************/
 
-#ifdef CONFIG_CAN_PASS_STRUCTS
-
 struct mallinfo mallinfo(void)
 {
   struct mallinfo info;
   mm_mallinfo(USR_HEAP, &info);
   return info;
 }
-
-#else
-
-int mallinfo(FAR struct mallinfo *info)
-{
-  return mm_mallinfo(USR_HEAP, info);
-}
-
-#endif /* CONFIG_CAN_PASS_STRUCTS */
diff --git a/sched/pthread/pthread_condtimedwait.c b/sched/pthread/pthread_condtimedwait.c
index 6f14009..e0c2246 100644
--- a/sched/pthread/pthread_condtimedwait.c
+++ b/sched/pthread/pthread_condtimedwait.c
@@ -124,16 +124,12 @@ static void pthread_condtimedout(int argc, wdparm_t arg1, ...)
        *  just use nxsig_queue().
        */
 
-#ifdef CONFIG_CAN_PASS_STRUCTS
       union sigval value;
 
       /* Send the specified signal to the specified task. */
 
       value.sival_ptr = NULL;
       nxsig_queue((int)pid, signo, value);
-#else
-      nxsig_queue((int)pid, signo, NULL);
-#endif
     }
 
 #endif /* HAVE_GROUP_MEMBERS */
diff --git a/sched/signal/sig_notification.c b/sched/signal/sig_notification.c
index 8b51019..f8033dd 100644
--- a/sched/signal/sig_notification.c
+++ b/sched/signal/sig_notification.c
@@ -86,11 +86,7 @@ static void nxsig_notification_worker(FAR void *arg)
 
   /* Perform the callback */
 
-#ifdef CONFIG_CAN_PASS_STRUCTS
   work->func(work->value);
-#else
-  work->func(work->value.sival_ptr);
-#endif
 }
 
 #endif /* CONFIG_SIG_EVTHREAD */
@@ -167,12 +163,8 @@ int nxsig_notification(pid_t pid, FAR struct sigevent *event,
     {
       /* Initialize the work information */
 
-#ifdef CONFIG_CAN_PASS_STRUCTS
       work->value = event->sigev_value;
-#else
-      work->value.sival_ptr = event->sigev_value.sival_ptr;
-#endif
-      work->func = event->sigev_notify_function;
+      work->func  = event->sigev_notify_function;
 
       /* Then queue the work */
 
diff --git a/sched/signal/sig_queue.c b/sched/signal/sig_queue.c
index 9f5ea4a..5f0d920 100644
--- a/sched/signal/sig_queue.c
+++ b/sched/signal/sig_queue.c
@@ -1,35 +1,20 @@
 /****************************************************************************
  * sched/signal/sig_queue.c
  *
- *   Copyright (C) 2007-2009, 2013, 2017 Gregory Nutt. All rights reserved.
- *   Author: Gregory Nutt <gn...@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.
+ * Licensed to the Apache Software Foundation (ASF) under one or more
+ * contributor license agreements.  See the NOTICE file distributed with
+ * this work for additional information regarding copyright ownership.  The
+ * ASF licenses this file to you under the Apache License, Version 2.0 (the
+ * "License"); you may not use this file except in compliance with the
+ * License.  You may obtain a copy of the License at
+ *
+ *   http://www.apache.org/licenses/LICENSE-2.0
+ *
+ * Unless required by applicable law or agreed to in writing, software
+ * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
+ * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.  See the
+ * License for the specific language governing permissions and limitations
+ * under the License.
  *
  ****************************************************************************/
 
@@ -89,11 +74,7 @@
  *
  ****************************************************************************/
 
-#ifdef CONFIG_CAN_PASS_STRUCTS
 int nxsig_queue (int pid, int signo, union sigval value)
-#else
-int nxsig_queue(int pid, int signo, void *sival_ptr)
-#endif
 {
 #ifdef CONFIG_SCHED_HAVE_PARENT
   FAR struct tcb_s *rtcb = this_task();
@@ -101,11 +82,7 @@ int nxsig_queue(int pid, int signo, void *sival_ptr)
   siginfo_t info;
   int ret;
 
-#ifdef CONFIG_CAN_PASS_STRUCTS
   sinfo("pid=0x%08x signo=%d value=%d\n", pid, signo, value.sival_int);
-#else
-  sinfo("pid=0x%08x signo=%d value=%p\n", pid, signo, sival_ptr);
-#endif
 
   /* Sanity checks */
 
@@ -119,11 +96,7 @@ int nxsig_queue(int pid, int signo, void *sival_ptr)
   info.si_signo           = signo;
   info.si_code            = SI_QUEUE;
   info.si_errno           = OK;
-#ifdef CONFIG_CAN_PASS_STRUCTS
   info.si_value           = value;
-#else
-  info.si_value.sival_ptr = sival_ptr;
-#endif
 #ifdef CONFIG_SCHED_HAVE_PARENT
   info.si_pid             = rtcb->pid;
   info.si_status          = OK;
@@ -170,21 +143,13 @@ int nxsig_queue(int pid, int signo, void *sival_ptr)
  *
  ****************************************************************************/
 
-#ifdef CONFIG_CAN_PASS_STRUCTS
 int sigqueue (int pid, int signo, union sigval value)
-#else
-int sigqueue(int pid, int signo, void *sival_ptr)
-#endif
 {
   int ret;
 
   /* Let nxsig_queue() do all of the real work */
 
-#ifdef CONFIG_CAN_PASS_STRUCTS
   ret = nxsig_queue(pid, signo, value);
-#else
-  ret = nxsig_queue(pid, signo, sival_ptr);
-#endif
   if (ret < 0)
     {
       set_errno(-ret);
diff --git a/sched/timer/timer_settime.c b/sched/timer/timer_settime.c
index b9669e3..b492383 100644
--- a/sched/timer/timer_settime.c
+++ b/sched/timer/timer_settime.c
@@ -125,39 +125,6 @@ static inline void timer_restart(FAR struct posix_timer_s *timer,
 
 static void timer_timeout(int argc, wdparm_t itimer, ...)
 {
-#ifndef CONFIG_CAN_PASS_STRUCTS
-  /* On many small machines, pointers are encoded and cannot be simply cast
-   * from wdparm_t to struct tcb_s *.  The following union works around this
-   * (see wdogparm_t).
-   */
-
-  union
-  {
-    FAR struct posix_timer_s *timer;
-    wdparm_t                  itimer;
-  } u;
-
-  u.itimer = itimer;
-
-  /* Send the specified signal to the specified task.   Increment the
-   * reference count on the timer first so that will not be deleted until
-   * after the signal handler returns.
-   */
-
-  u.timer->pt_crefs++;
-  timer_signotify(u.timer);
-
-  /* Release the reference.  timer_release will return nonzero if the timer
-   * was not deleted.
-   */
-
-  if (timer_release(u.timer))
-    {
-      /* If this is a repetitive timer, then restart the watchdog */
-
-      timer_restart(u.timer, itimer);
-    }
-#else
   FAR struct posix_timer_s *timer = (FAR struct posix_timer_s *)itimer;
 
   /* Send the specified signal to the specified task.   Increment the
@@ -178,7 +145,6 @@ static void timer_timeout(int argc, wdparm_t itimer, ...)
 
       timer_restart(timer, itimer);
     }
-#endif
 }
 
 /****************************************************************************


[incubator-nuttx] 02/03: nxstyle fixes

Posted by ag...@apache.org.
This is an automated email from the ASF dual-hosted git repository.

aguettouche pushed a commit to branch master
in repository https://gitbox.apache.org/repos/asf/incubator-nuttx.git

commit 72104c182c669e5ea1c8bdef2f6bfec273e4beee
Author: Gregory Nutt <gn...@nuttx.org>
AuthorDate: Sat Apr 11 11:43:37 2020 -0600

    nxstyle fixes
    
    Run all files modified by PR 766 through nxstyle and fix any resulting complaints.
    
    NOTE:  Numerous "Mixed case identifier" errors in arch/arm/src/cxd56xx/cxd56_gnss.c were not fixed because this problem is of much larger scope than this file.
---
 arch/arm/src/cxd56xx/cxd56_gnss.c   | 28 ++++++--------
 arch/arm/src/cxd56xx/cxd56_usbdev.c | 20 +++++++---
 binfmt/libnxflat/libnxflat_bind.c   | 77 ++++++++++++++++++++-----------------
 fs/procfs/fs_procfsmeminfo.c        |  6 ++-
 include/arpa/inet.h                 |  3 +-
 include/nuttx/compiler.h            |  4 +-
 include/signal.h                    | 15 ++++++--
 include/stdlib.h                    |  2 +-
 libs/libc/net/lib_inetntoa.c        |  4 +-
 9 files changed, 92 insertions(+), 67 deletions(-)

diff --git a/arch/arm/src/cxd56xx/cxd56_gnss.c b/arch/arm/src/cxd56xx/cxd56_gnss.c
index ace24a8..0e5e61c 100644
--- a/arch/arm/src/cxd56xx/cxd56_gnss.c
+++ b/arch/arm/src/cxd56xx/cxd56_gnss.c
@@ -160,6 +160,12 @@ struct cxd56_gnss_shared_info_s
   uint32_t argv[GNSS_SHARED_INFO_MAX_ARGC];
 };
 
+struct cxd56_devsig_table_s
+{
+  uint8_t                sigtype;
+  cxd56_cpu1sighandler_t handler;
+};
+
 struct cxd56_gnss_dev_s
 {
   sem_t                           devsem;
@@ -2037,7 +2043,9 @@ static FAR char *cxd56_gnss_read_cep_file(FAR FILE *fp, int32_t offset,
 
   return buf;
 
-  /* send signal to CPU1 in error for just notify completion of read sequence */
+  /* Send signal to CPU1 in error for just notify completion of read
+   * sequence.
+   */
 
   _err1:
   free(buf);
@@ -2829,62 +2837,50 @@ static int cxd56_gnss_register(FAR const char *devpath)
   FAR struct cxd56_gnss_dev_s *priv;
   int                          i;
   int                          ret;
-  static struct
+
+  static struct cxd56_devsig_table_s devsig_table[] =
   {
-    uint8_t                sigtype;
-    cxd56_cpu1sighandler_t handler;
-  } devsig_table[] =
-    {
     {
       CXD56_CPU1_DATA_TYPE_GNSS,
       cxd56_gnss_default_sighandler
     },
-
     {
       CXD56_CPU1_DATA_TYPE_AGPS,
       cxd56_gnss_common_signalhandler
     },
-
     {
       CXD56_CPU1_DATA_TYPE_RTK,
       cxd56_gnss_common_signalhandler
     },
-
     {
       CXD56_CPU1_DATA_TYPE_GPSEPHEMERIS,
       cxd56_gnss_common_signalhandler
     },
-
     {
       CXD56_CPU1_DATA_TYPE_GLNEPHEMERIS,
       cxd56_gnss_common_signalhandler
     },
-
     {
       CXD56_CPU1_DATA_TYPE_SPECTRUM,
       cxd56_gnss_common_signalhandler
     },
-
     {
       CXD56_CPU1_DATA_TYPE_PVTLOG,
       cxd56_gnss_common_signalhandler
     },
-
     {
       CXD56_CPU1_DATA_TYPE_CPUFIFOAPI,
       cxd56_gnss_cpufifoapi_signalhandler
     },
-
     {
       CXD56_CPU1_DATA_TYPE_SBAS,
       cxd56_gnss_common_signalhandler
     },
-
     {
       CXD56_CPU1_DATA_TYPE_DCREPORT,
       cxd56_gnss_common_signalhandler
     }
-    };
+  };
 
   priv = (FAR struct cxd56_gnss_dev_s *)kmm_malloc(
     sizeof(struct cxd56_gnss_dev_s));
diff --git a/arch/arm/src/cxd56xx/cxd56_usbdev.c b/arch/arm/src/cxd56xx/cxd56_usbdev.c
index ba282d1..ccb3de8 100644
--- a/arch/arm/src/cxd56xx/cxd56_usbdev.c
+++ b/arch/arm/src/cxd56xx/cxd56_usbdev.c
@@ -563,7 +563,9 @@ static const struct usbdev_ops_s g_devops =
   .pullup      = cxd56_pullup,
 };
 
-/* There is only one, single, pre-allocated instance of the driver structure */
+/* There is only one, single, pre-allocated instance of the driver
+ * structure.
+ */
 
 static struct cxd56_usbdev_s g_usbdev;
 
@@ -1622,7 +1624,9 @@ static int cxd56_epinterrupt(int irq, FAR void *context)
 
                   cxd56_txdmacomplete(privep);
 
-                  /* Clear NAK to raise IN interrupt for send next IN packets */
+                  /* Clear NAK to raise IN interrupt for send next IN
+                   * packets.
+                   */
 
                   putreg32(ctrl | USB_CNAK, CXD56_USB_IN_EP_CONTROL(n));
                 }
@@ -1718,7 +1722,9 @@ static int cxd56_epinterrupt(int irq, FAR void *context)
                           priv->ep0datlen += len;
                         }
 
-                      /* Dispatch to cxd56_ep0setup if received all OUT data */
+                      /* Dispatch to cxd56_ep0setup if received all OUT
+                       * data.
+                       */
 
                       if (priv->ep0datlen == priv->ep0reqlen)
                         {
@@ -1791,7 +1797,9 @@ static int cxd56_epinterrupt(int irq, FAR void *context)
 
                   if (!(stat & USB_INT_MRXFIFOEMPTY))
                     {
-                      /* Flush Receive FIFO and clear NAK to finish status stage */
+                      /* Flush Receive FIFO and clear NAK to finish status
+                       * stage.
+                       */
 
                       putreg32(ctrl | USB_MRXFLUSH,
                                CXD56_USB_OUT_EP_CONTROL(n));
@@ -2467,7 +2475,9 @@ static int cxd56_epsubmit(FAR struct usbdev_ep_s *ep,
       if (priv->ctrl.req == USB_REQ_SETCONFIGURATION ||
           priv->ctrl.req == USB_REQ_SETINTERFACE)
         {
-          /* Nothing to transfer -- exit success, with zero bytes transferred */
+          /* Nothing to transfer -- exit success, with zero bytes
+           * transferred
+           */
 
           usbtrace(TRACE_COMPLETE(privep->epphy), privreq->req.xfrd);
           cxd56_reqcomplete(privep, OK);
diff --git a/binfmt/libnxflat/libnxflat_bind.c b/binfmt/libnxflat/libnxflat_bind.c
index 4267264..01de7df 100644
--- a/binfmt/libnxflat/libnxflat_bind.c
+++ b/binfmt/libnxflat/libnxflat_bind.c
@@ -43,8 +43,8 @@
  * Pre-processor Definitions
  ****************************************************************************/
 
-/* CONFIG_DEBUG_FEATURES, CONFIG_DEBUG_INFO, and CONFIG_DEBUG_BINFMT have to be
- * defined or CONFIG_NXFLAT_DUMPBUFFER does nothing.
+/* CONFIG_DEBUG_FEATURES, CONFIG_DEBUG_INFO, and CONFIG_DEBUG_BINFMT have to
+ * be defined or CONFIG_NXFLAT_DUMPBUFFER does nothing.
  */
 
 #if !defined(CONFIG_DEBUG_INFO) || !defined (CONFIG_DEBUG_BINFMT)
@@ -58,14 +58,6 @@
 #endif
 
 /****************************************************************************
- * Private Types
- ****************************************************************************/
-
-/****************************************************************************
- * Private Data
- ****************************************************************************/
-
-/****************************************************************************
  * Private Functions
  ****************************************************************************/
 
@@ -75,7 +67,8 @@
  * Description:
  *   Perform the NXFLAT_RELOC_TYPE_REL32I binding:
  *
- *   Meaning: Object file contains a 32-bit offset into I-Space at the offset.
+ *   Meaning: Object file contains a 32-bit offset into I-Space at the
+ *            offset.
  *   Fixup:   Add mapped I-Space address to the offset.
  *
  * Returned Value:
@@ -114,7 +107,8 @@ static inline int nxflat_bindrel32i(FAR struct nxflat_loadinfo_s *loadinfo,
  * Description:
  *   Perform the NXFLAT_RELOC_TYPE_REL32D binding:
  *
- *   Meaning: Object file contains a 32-bit offset into D-Space at the offset.
+ *   Meaning: Object file contains a 32-bit offset into D-Space at the
+ *            offset.
  *   Fixup:   Add allocated D-Space address to the offset.
  *
  * Returned Value:
@@ -175,10 +169,13 @@ static inline int nxflat_bindrel32id(FAR struct nxflat_loadinfo_s *loadinfo,
 
   if (offset < loadinfo->dsize)
     {
-      addr = (FAR uint32_t *)(offset + loadinfo->dspace->region);
+      addr  = (FAR uint32_t *)(offset + loadinfo->dspace->region);
       binfo("  Before: %08x\n", *addr);
-     *addr += ((uint32_t)loadinfo->ispace - (uint32_t)(loadinfo->dspace->region));
+
+     *addr += ((uint32_t)loadinfo->ispace -
+               (uint32_t)(loadinfo->dspace->region));
       binfo("  After: %08x\n", *addr);
+
       return OK;
     }
   else
@@ -268,36 +265,42 @@ static inline int nxflat_gotrelocs(FAR struct nxflat_loadinfo_s *loadinfo)
       switch (NXFLAT_RELOC_TYPE(reloc.r_info))
         {
         /* NXFLAT_RELOC_TYPE_REL32I  Meaning: Object file contains a 32-bit
-         *                                    offset into I-Space at the offset.
-         *                           Fixup:   Add mapped I-Space address to the
+         *                                    offset into I-Space at the
          *                                    offset.
+         *                           Fixup:   Add mapped I-Space address
+         *                                    to the offset.
          */
 
         case NXFLAT_RELOC_TYPE_REL32I:
           {
-            result = nxflat_bindrel32i(loadinfo, NXFLAT_RELOC_OFFSET(reloc.r_info));
+            result = nxflat_bindrel32i(loadinfo,
+                                       NXFLAT_RELOC_OFFSET(reloc.r_info));
           }
           break;
 
-        /* NXFLAT_RELOC_TYPE_REL32D  Meaning: Object file contains a 32-bit offset
-         *                                    into D-Space at the offset.
-         *                           Fixup:   Add allocated D-Space address to the
+        /* NXFLAT_RELOC_TYPE_REL32D  Meaning: Object file contains a 32-bit
+         *                                    offset into D-Space at the
          *                                    offset.
+         *                           Fixup:   Add allocated D-Space address
+         *                                    to the offset.
          */
 
         case NXFLAT_RELOC_TYPE_REL32D:
           {
-            result = nxflat_bindrel32d(loadinfo, NXFLAT_RELOC_OFFSET(reloc.r_info));
+            result = nxflat_bindrel32d(loadinfo,
+                                       NXFLAT_RELOC_OFFSET(reloc.r_info));
           }
           break;
 
-        /* NXFLAT_RELOC_TYPE_REL32ID Meaning: Object file contains a 32-bit offset
-         *                                    into I-Space at the offset that will
-         *                                    unfortunately be references relative
-         *                                    to the GOT
-         *                           Fixup:   Add allocated the mapped I-Space
-         *                                    address MINUS the allocated D-Space
-         *                                    address to the offset.
+        /* NXFLAT_RELOC_TYPE_REL32ID Meaning: Object file contains a 32-bit
+         *                                    offset into I-Space at the
+         *                                    offset that will unfortunately
+         *                                    be references relative to the
+         *                                    GOT
+         *                           Fixup:   Add allocated the mapped
+         *                                    I-Space address MINUS the
+         *                                    allocated D-Space address to
+         *                                    the offset.
          */
 
 #ifdef NXFLAT_RELOC_TYPE_REL32ID
@@ -436,7 +439,8 @@ static inline int nxflat_bindimports(FAR struct nxflat_loadinfo_s *loadinfo,
       for (i = 0; i < nimports; i++)
         {
           binfo("Import[%d] (%08p) offset: %08x func: %08x\n",
-                i, &imports[i], imports[i].i_funcname, imports[i].i_funcaddress);
+                i, &imports[i], imports[i].i_funcname,
+                imports[i].i_funcaddress);
 
           /* Get a pointer to the imported symbol name.  The name itself
            * lies in the TEXT segment.  But the reference to the name
@@ -518,10 +522,10 @@ static inline int nxflat_clearbss(FAR struct nxflat_loadinfo_s *loadinfo)
   int ret;
 #endif
 
-  /* .bss resides within the D-Space allocation.  If CONFIG_ARCH_ADDRENV=y, then
-   * that D-Space allocation lies in an address environment that may not be
-   * in place.  So, in that case, we must call nxflat_addrenv_select to
-   * temporarily instantiate that address space before the .bss can be
+  /* .bss resides within the D-Space allocation.  If CONFIG_ARCH_ADDRENV=y,
+   * then that D-Space allocation lies in an address environment that may
+   * not be in place.  So, in that case, we must call nxflat_addrenv_select
+   * to temporarily instantiate that address space before the .bss can be
    * accessed.
    */
 
@@ -564,8 +568,8 @@ static inline int nxflat_clearbss(FAR struct nxflat_loadinfo_s *loadinfo)
  * Description:
  *   Bind the imported symbol names in the loaded module described by
  *   'loadinfo' using the exported symbol values provided by 'symtab'.
- *   After binding the module, clear the BSS region (which held the relocation
- *   data) in preparation for execution.
+ *   After binding the module, clear the BSS region (which held the
+ *   relocation data) in preparation for execution.
  *
  * Returned Value:
  *   0 (OK) is returned on success and a negated errno is returned on
@@ -578,7 +582,8 @@ int nxflat_bind(FAR struct nxflat_loadinfo_s *loadinfo,
 {
   /* Bind the imported symbol, absolute relocations separately.  This is done
    * before the standard relocations because that logic may modify the
-   * import list (for the better hopefully, but we don't want to depend on it).
+   * import list (for the better hopefully, but we don't want to depend on
+   * it).
    */
 
   int ret = nxflat_bindimports(loadinfo, exports, nexports);
diff --git a/fs/procfs/fs_procfsmeminfo.c b/fs/procfs/fs_procfsmeminfo.c
index d1f0dec..661d655 100644
--- a/fs/procfs/fs_procfsmeminfo.c
+++ b/fs/procfs/fs_procfsmeminfo.c
@@ -281,8 +281,10 @@ static ssize_t meminfo_read(FAR struct file *filep, FAR char *buffer,
 
   /* The first line is the headers */
 
-  linesize  = snprintf(procfile->line, MEMINFO_LINELEN,
-                       "             total       used       free    largest\n");
+  linesize  =
+    snprintf(procfile->line, MEMINFO_LINELEN,
+             "             total       used       free    largest\n");
+
   copysize  = procfs_memcpy(procfile->line, linesize, buffer, buflen,
                             &offset);
   totalsize = copysize;
diff --git a/include/arpa/inet.h b/include/arpa/inet.h
index afb9d06..ae46379 100644
--- a/include/arpa/inet.h
+++ b/include/arpa/inet.h
@@ -104,7 +104,8 @@ in_addr_t   inet_netof(struct in_addr in);
 struct in_addr inet_makeaddr(in_addr_t net, in_addr_t host);
 
 int         inet_pton(int af, FAR const char *src, FAR void *dst);
-const char *inet_ntop(int af, FAR const void *src, FAR char *dst, socklen_t size);
+const char *inet_ntop(int af, FAR const void *src, FAR char *dst,
+                      socklen_t size);
 
 #undef EXTERN
 #ifdef __cplusplus
diff --git a/include/nuttx/compiler.h b/include/nuttx/compiler.h
index aef87bb..1dd5b84 100644
--- a/include/nuttx/compiler.h
+++ b/include/nuttx/compiler.h
@@ -604,7 +604,9 @@
 
 #  undef CONFIG_HAVE_CXX14
 
-/* ISO C11 supports anonymous (unnamed) structures and unions.  Does ICCARM? */
+/* ISO C11 supports anonymous (unnamed) structures and unions.  Does
+ * ICCARM?
+ */
 
 #  undef CONFIG_HAVE_ANONYMOUS_STRUCT
 #  undef  CONFIG_HAVE_ANONYMOUS_UNION
diff --git a/include/signal.h b/include/signal.h
index 95f95a3..5045c2a 100644
--- a/include/signal.h
+++ b/include/signal.h
@@ -38,6 +38,7 @@
 /********************************************************************************
  * Pre-processor Definitions
  ********************************************************************************/
+
 /* Signal set management definitions and macros. */
 
 #define NULL_SIGNAL_SET ((sigset_t)0x00000000)
@@ -258,7 +259,7 @@
 #endif
 
 /********************************************************************************
- * Public Type Definitions
+ * Public Types
  ********************************************************************************/
 
 /* This defines a set of 32 signals (numbered 0 through 31).
@@ -401,12 +402,20 @@ int  sigwaitinfo(FAR const sigset_t *set, FAR struct siginfo *value);
 
 #else /* __INCLUDE_SIGNAL_H */
 
-#include <stdint.h>
-
 /* Avoid circular dependencies by assuring that simple type definitions are
  * available in any inclusion ordering.
  */
 
+/********************************************************************************
+ * Included Files
+ ********************************************************************************/
+
+#include <stdint.h>
+
+/********************************************************************************
+ * Public Types
+ ********************************************************************************/
+
 #ifndef __SIGSET_T_DEFINED
 typedef uint32_t sigset_t;
 #  define __SIGSET_T_DEFINED 1
diff --git a/include/stdlib.h b/include/stdlib.h
index 16912df..004fe01 100644
--- a/include/stdlib.h
+++ b/include/stdlib.h
@@ -79,7 +79,7 @@ struct mallinfo
   int uordblks; /* This is the total size of memory occupied by
                  * chunks handed out by malloc. */
   int fordblks; /* This is the total size of memory occupied
-                 * by free (not in use) chunks.*/
+                 * by free (not in use) chunks. */
 };
 
 /* Structure type returned by the div() function. */
diff --git a/libs/libc/net/lib_inetntoa.c b/libs/libc/net/lib_inetntoa.c
index e4078eb..bc7d334 100644
--- a/libs/libc/net/lib_inetntoa.c
+++ b/libs/libc/net/lib_inetntoa.c
@@ -41,8 +41,8 @@
  * Description:
  *   The inet_ntoa() function converts the Internet host address given in
  *   network byte order to a string in standard numbers-and-dots notation.
- *   The string is returned in a statically allocated buffer, which subsequent
- *   calls will overwrite.
+ *   The string is returned in a statically allocated buffer, which
+ *   subsequent calls will overwrite.
  *
  ****************************************************************************/
 


[incubator-nuttx] 03/03: Update README.txt files for boards using SDCC

Posted by ag...@apache.org.
This is an automated email from the ASF dual-hosted git repository.

aguettouche pushed a commit to branch master
in repository https://gitbox.apache.org/repos/asf/incubator-nuttx.git

commit 8b87baa7143948a63acc994d7ad1522cfb93e291
Author: Gregory Nutt <gn...@nuttx.org>
AuthorDate: Sat Apr 11 13:13:15 2020 -0600

    Update README.txt files for boards using SDCC
    
    Modified boards/z80/z180/p112/README.txt and boards/z80/z80/z80sim/README.txt:
    
    IMPORTANT NOTE as of 2020-4-11:  Support for CONFIG_CAN_PASS_STRUCTS was removed in NuttX-9.1.  This was necessary to enforce some POSIX interface compliance but also means that ALL older SDCC versions will no long build with NuttX.  I have been told that the newest SDCC compilers can indeed pass structure and union parameters and return values.  If that is correct, then perhaps the newer SDCC compilers will be used.  Otherwise, it will be necessary to use some other, more compliant c [...]
---
 boards/z80/z180/p112/README.txt  | 8 ++++++++
 boards/z80/z80/z80sim/README.txt | 9 +++++++++
 2 files changed, 17 insertions(+)

diff --git a/boards/z80/z180/p112/README.txt b/boards/z80/z180/p112/README.txt
index 7a32cc6..3bdb596 100644
--- a/boards/z80/z180/p112/README.txt
+++ b/boards/z80/z180/p112/README.txt
@@ -138,6 +138,14 @@ the Z85230 ESCC channel A.
 Status
 ======
 
+2020-4-11:  Support for CONFIG_CAN_PASS_STRUCTS was removed in NuttX-9.1.
+  This was necessary to enforce some POSIX interface compliance but also
+  means that ALL older SDCC versions will no long build with NuttX.  I have
+  been told that the newest SDCC compilers can indeed pass structure and
+  union parameters and return values.  If that is correct, then perhaps
+  the newer SDCC compilers will be used.  Otherwise, it will be necessary
+  to use some other, more compliant compiler.
+
 2014-8-22:  After some time idling away, I tried rebuilding with Windows 8,
   the latest MinGW and the latest SDCC.  I fixed a few things but there a
   still a few issues.  The last "show stopper" before I gave up for now was
diff --git a/boards/z80/z80/z80sim/README.txt b/boards/z80/z80/z80sim/README.txt
index c2a47d0..9a6610d 100644
--- a/boards/z80/z80/z80sim/README.txt
+++ b/boards/z80/z80/z80sim/README.txt
@@ -6,6 +6,7 @@ This port uses an instruction set simulator called z80sim.
 
 The SDCC toolchain is available from http://sdcc.sourceforge.net/.  All
 testing has been performed using version 2.6.0 of the SDCC toolchain.
+IMPORTANT: See notes in the SDCC section.
 
 Contents
 ^^^^^^^^
@@ -138,6 +139,14 @@ or custom built for Cygwin (see below).
 SDCC
 ^^^^
 
+IMPORTANT NOTE as of 2020-4-11:  Support for CONFIG_CAN_PASS_STRUCTS was
+removed in NuttX-9.1.  This was necessary to enforce some POSIX interface
+compliance but also means that ALL older SDCC versions will no long build
+with NuttX.  I have been told that the newest SDCC compilers can indeed
+pass structure and union parameters and return values.  If that is correct,
+then perhaps the newer SDCC compilers will be used.  Otherwise, it will be
+necessary to use some other, more compliant compiler.
+
 These z80 configurations all use the SDCC toolchain (http://sdcc.sourceforge.net/).
 Source and pre-built SDCC binaries can be downloaded from the SDCC SourceForge
 site: http://sourceforge.net/projects/sdcc/files/ .  Pre-built binaries are