aboutsummaryrefslogtreecommitdiff
path: root/nuttx
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2013-01-06 11:32:08 +0100
committerLorenz Meier <lm@inf.ethz.ch>2013-01-06 11:32:08 +0100
commit34d078b556bdd5f82bfcfbe8ce13d4c3b333e458 (patch)
tree8cf77215fb1b37105a4c1b1a136992820c064359 /nuttx
parent8eb8909a3c24c6028e4945e4a057d6d2f27f3d04 (diff)
parent58309fd6a863805e16602f4bec82eb35e0a14262 (diff)
downloadpx4-firmware-34d078b556bdd5f82bfcfbe8ce13d4c3b333e458.tar.gz
px4-firmware-34d078b556bdd5f82bfcfbe8ce13d4c3b333e458.tar.bz2
px4-firmware-34d078b556bdd5f82bfcfbe8ce13d4c3b333e458.zip
Merged latest master
Diffstat (limited to 'nuttx')
-rwxr-xr-xnuttx/configs/px4fmu/nsh/defconfig18
-rwxr-xr-xnuttx/configs/px4io/common/ld.script9
-rw-r--r--nuttx/configs/px4io/io/appconfig3
-rwxr-xr-xnuttx/configs/px4io/io/defconfig6
-rw-r--r--nuttx/drivers/serial/serial.c6
-rw-r--r--nuttx/include/stdio.h1
-rw-r--r--nuttx/lib/lib_internal.h1
-rw-r--r--nuttx/lib/stdio/Make.defs2
-rw-r--r--nuttx/lib/stdio/lib_rawprintf.c15
-rw-r--r--nuttx/lib/stdio/lib_vdprintf.c81
-rwxr-xr-xnuttx/tools/mkdeps.sh8
11 files changed, 134 insertions, 16 deletions
diff --git a/nuttx/configs/px4fmu/nsh/defconfig b/nuttx/configs/px4fmu/nsh/defconfig
index d9a48f2c8..52013457e 100755
--- a/nuttx/configs/px4fmu/nsh/defconfig
+++ b/nuttx/configs/px4fmu/nsh/defconfig
@@ -246,18 +246,18 @@ CONFIG_USART6_SERIAL_CONSOLE=n
#Mavlink messages can be bigger than 128
CONFIG_USART1_TXBUFSIZE=512
-CONFIG_USART2_TXBUFSIZE=128
-CONFIG_USART3_TXBUFSIZE=128
-CONFIG_UART4_TXBUFSIZE=128
-CONFIG_UART5_TXBUFSIZE=64
+CONFIG_USART2_TXBUFSIZE=256
+CONFIG_USART3_TXBUFSIZE=256
+CONFIG_UART4_TXBUFSIZE=256
+CONFIG_UART5_TXBUFSIZE=256
CONFIG_USART6_TXBUFSIZE=128
CONFIG_USART1_RXBUFSIZE=512
-CONFIG_USART2_RXBUFSIZE=128
-CONFIG_USART3_RXBUFSIZE=128
-CONFIG_UART4_RXBUFSIZE=128
-CONFIG_UART5_RXBUFSIZE=128
-CONFIG_USART6_RXBUFSIZE=128
+CONFIG_USART2_RXBUFSIZE=256
+CONFIG_USART3_RXBUFSIZE=256
+CONFIG_UART4_RXBUFSIZE=256
+CONFIG_UART5_RXBUFSIZE=256
+CONFIG_USART6_RXBUFSIZE=256
CONFIG_USART1_BAUD=57600
CONFIG_USART2_BAUD=115200
diff --git a/nuttx/configs/px4io/common/ld.script b/nuttx/configs/px4io/common/ld.script
index 17f816acf..69c2f9cb2 100755
--- a/nuttx/configs/px4io/common/ld.script
+++ b/nuttx/configs/px4io/common/ld.script
@@ -74,6 +74,15 @@ SECTIONS
_etext = ABSOLUTE(.);
} > flash
+ /*
+ * Init functions (static constructors and the like)
+ */
+ .init_section : {
+ _sinit = ABSOLUTE(.);
+ KEEP(*(.init_array .init_array.*))
+ _einit = ABSOLUTE(.);
+ } > flash
+
.ARM.extab : {
*(.ARM.extab*)
} > flash
diff --git a/nuttx/configs/px4io/io/appconfig b/nuttx/configs/px4io/io/appconfig
index 21a6fbacf..628607a51 100644
--- a/nuttx/configs/px4io/io/appconfig
+++ b/nuttx/configs/px4io/io/appconfig
@@ -35,3 +35,6 @@ CONFIGURED_APPS += drivers/boards/px4io
CONFIGURED_APPS += drivers/stm32
CONFIGURED_APPS += px4io
+
+# Mixer library from systemlib
+CONFIGURED_APPS += systemlib/mixer
diff --git a/nuttx/configs/px4io/io/defconfig b/nuttx/configs/px4io/io/defconfig
index 043754e29..30ec5be08 100755
--- a/nuttx/configs/px4io/io/defconfig
+++ b/nuttx/configs/px4io/io/defconfig
@@ -87,6 +87,8 @@ CONFIG_ARCH_LEDS=n
CONFIG_ARCH_BUTTONS=n
CONFIG_ARCH_CALIBRATION=n
CONFIG_ARCH_DMA=n
+CONFIG_ARCH_MATH_H=y
+
CONFIG_ARMV7M_CMNVECTOR=y
#
@@ -343,8 +345,8 @@ CONFIG_DEBUG_I2C=n
CONFIG_DEBUG_INPUT=n
CONFIG_MSEC_PER_TICK=1
-CONFIG_HAVE_CXX=n
-CONFIG_HAVE_CXXINITIALIZE=n
+CONFIG_HAVE_CXX=y
+CONFIG_HAVE_CXXINITIALIZE=y
CONFIG_MM_REGIONS=1
CONFIG_MM_SMALL=y
CONFIG_ARCH_LOWPUTC=y
diff --git a/nuttx/drivers/serial/serial.c b/nuttx/drivers/serial/serial.c
index 28c657af0..da326f8c6 100644
--- a/nuttx/drivers/serial/serial.c
+++ b/nuttx/drivers/serial/serial.c
@@ -660,8 +660,10 @@ static int uart_ioctl(FAR struct file *filep, int cmd, unsigned long arg)
int ret = dev->ops->ioctl(filep, cmd, arg);
- /* If the low-level handler didn't handle the call, see if we can handle it here */
-
+ /*
+ * The device ioctl() handler returns -ENOTTY when it doesn't know
+ * how to handle the command. Check if we can handle it here.
+ */
if (ret == -ENOTTY)
{
switch (cmd)
diff --git a/nuttx/include/stdio.h b/nuttx/include/stdio.h
index e9218046c..754cedbb4 100644
--- a/nuttx/include/stdio.h
+++ b/nuttx/include/stdio.h
@@ -133,6 +133,7 @@ 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);
EXTERN int vsprintf(FAR char *buf, const char *format, va_list ap);
EXTERN int avsprintf(FAR char **ptr, const char *fmt, va_list ap);
EXTERN int vsnprintf(FAR char *buf, size_t size, const char *format, va_list ap);
diff --git a/nuttx/lib/lib_internal.h b/nuttx/lib/lib_internal.h
index c3d9bfd18..49cba9996 100644
--- a/nuttx/lib/lib_internal.h
+++ b/nuttx/lib/lib_internal.h
@@ -140,6 +140,7 @@ extern int lib_vsprintf(FAR struct lib_outstream_s *obj,
/* Defined lib_rawprintf.c */
extern int lib_rawvprintf(const char *src, va_list ap);
+extern int lib_rawvdprintf(int fd, const char *fmt, va_list ap);
/* Defined lib_lowprintf.c */
diff --git a/nuttx/lib/stdio/Make.defs b/nuttx/lib/stdio/Make.defs
index f88a5edd9..a4e900705 100644
--- a/nuttx/lib/stdio/Make.defs
+++ b/nuttx/lib/stdio/Make.defs
@@ -50,7 +50,7 @@ CSRCS += lib_fopen.c lib_fclose.c lib_fread.c lib_libfread.c lib_fseek.c \
lib_gets.c lib_fwrite.c lib_libfwrite.c lib_fflush.c \
lib_libflushall.c lib_libfflush.c lib_rdflush.c lib_wrflush.c \
lib_fputc.c lib_puts.c lib_fputs.c lib_ungetc.c lib_vprintf.c \
- lib_fprintf.c lib_vfprintf.c lib_stdinstream.c lib_stdoutstream.c \
+ lib_fprintf.c lib_vfprintf.c lib_vdprintf.c lib_stdinstream.c lib_stdoutstream.c \
lib_perror.c
endif
endif
diff --git a/nuttx/lib/stdio/lib_rawprintf.c b/nuttx/lib/stdio/lib_rawprintf.c
index 19dfa895e..1a6eb16b7 100644
--- a/nuttx/lib/stdio/lib_rawprintf.c
+++ b/nuttx/lib/stdio/lib_rawprintf.c
@@ -149,3 +149,18 @@ int lib_rawprintf(const char *fmt, ...)
return ret;
}
+
+
+/****************************************************************************
+ * Name: lib_rawvdprintf
+ ****************************************************************************/
+
+int lib_rawvdprintf(int fd, const char *fmt, va_list ap)
+{
+ /* Wrap the stdout in a stream object and let lib_vsprintf
+ * do the work.
+ */
+ struct lib_rawoutstream_s rawoutstream;
+ lib_rawoutstream(&rawoutstream, fd);
+ return lib_vsprintf(&rawoutstream.public, fmt, ap);
+}
diff --git a/nuttx/lib/stdio/lib_vdprintf.c b/nuttx/lib/stdio/lib_vdprintf.c
new file mode 100644
index 000000000..c2b576110
--- /dev/null
+++ b/nuttx/lib/stdio/lib_vdprintf.c
@@ -0,0 +1,81 @@
+/****************************************************************************
+ * lib/stdio/lib_vdprintf.c
+ *
+ * Copyright (C) 2007-2009, 2011 Andrew Tridgell. All rights reserved.
+ * Author: Andrew Tridgell <andrew@tridgell.net>
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdio.h>
+
+#include "lib_internal.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Type Declarations
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Constant Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Constant Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+int vdprintf(int fd, FAR const char *fmt, va_list ap)
+{
+ return lib_rawvdprintf(fd, fmt, ap);
+}
diff --git a/nuttx/tools/mkdeps.sh b/nuttx/tools/mkdeps.sh
index acb600150..d8984e553 100755
--- a/nuttx/tools/mkdeps.sh
+++ b/nuttx/tools/mkdeps.sh
@@ -86,8 +86,12 @@ dodep ()
fi
done
if [ -z "$fullpath" ]; then
- echo "# ERROR: No readable file for $1 found at any location"
- show_usage
+ if [ -r $1 ]; then
+ fullpath=$1
+ else
+ echo "# ERROR: No readable file for $1 found at any location"
+ show_usage
+ fi
fi
fi