aboutsummaryrefslogtreecommitdiff
path: root/nuttx
diff options
context:
space:
mode:
authorSimon Wilks <sjwilks@gmail.com>2013-01-11 16:52:42 +0100
committerSimon Wilks <sjwilks@gmail.com>2013-01-11 16:52:42 +0100
commit64925c33cd751b05128fedc566bd42d381418593 (patch)
treee316a05a1e2a3dfad0e4cd547aa759b65882c4fe /nuttx
parent097aeddcadc6c0b5decf8374c05586bfff5e403d (diff)
parent40dfbf0d977729951d73bcb089ca8f89c7b83efe (diff)
downloadpx4-firmware-64925c33cd751b05128fedc566bd42d381418593.tar.gz
px4-firmware-64925c33cd751b05128fedc566bd42d381418593.tar.bz2
px4-firmware-64925c33cd751b05128fedc566bd42d381418593.zip
Merged
Diffstat (limited to 'nuttx')
-rw-r--r--nuttx/configs/px4fmu/common/Make.defs5
-rw-r--r--nuttx/configs/px4fmu/nsh/appconfig11
-rwxr-xr-xnuttx/configs/px4fmu/nsh/defconfig44
-rwxr-xr-xnuttx/configs/px4io/common/ld.script9
-rw-r--r--nuttx/configs/px4io/io/appconfig3
-rwxr-xr-xnuttx/configs/px4io/io/defconfig7
-rw-r--r--nuttx/drivers/serial/serial.c44
-rw-r--r--nuttx/include/nuttx/fs/ioctl.h4
-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
14 files changed, 192 insertions, 43 deletions
diff --git a/nuttx/configs/px4fmu/common/Make.defs b/nuttx/configs/px4fmu/common/Make.defs
index ff2e4c5fa..3d2df6314 100644
--- a/nuttx/configs/px4fmu/common/Make.defs
+++ b/nuttx/configs/px4fmu/common/Make.defs
@@ -143,8 +143,9 @@ ARCHCWARNINGS = $(ARCHWARNINGS) \
-Wmissing-prototypes \
-Wnested-externs \
-Wunsuffixed-float-constants
-ARCHWARNINGSXX = $(ARCHWARNINGS)
-ARCHDEFINES =
+ARCHWARNINGSXX = $(ARCHWARNINGS) \
+ -Wno-psabi
+ARCHDEFINES =
ARCHPICFLAGS = -fpic -msingle-pic-base -mpic-register=r10
# this seems to be the only way to add linker flags
diff --git a/nuttx/configs/px4fmu/nsh/appconfig b/nuttx/configs/px4fmu/nsh/appconfig
index 0959687de..fcdf689aa 100644
--- a/nuttx/configs/px4fmu/nsh/appconfig
+++ b/nuttx/configs/px4fmu/nsh/appconfig
@@ -45,6 +45,16 @@ CONFIGURED_APPS += system/readline
CONFIGURED_APPS += systemlib
CONFIGURED_APPS += systemlib/mixer
+# Math library
+CONFIGURED_APPS += mathlib
+CONFIGURED_APPS += mathlib/CMSIS
+CONFIGURED_APPS += examples/math_demo
+
+# Control library
+CONFIGURED_APPS += controllib
+CONFIGURED_APPS += examples/control_demo
+CONFIGURED_APPS += examples/kalman_demo
+
# System utility commands
CONFIGURED_APPS += systemcmds/reboot
CONFIGURED_APPS += systemcmds/perf
@@ -100,6 +110,7 @@ CONFIGURED_APPS += drivers/stm32
CONFIGURED_APPS += drivers/led
CONFIGURED_APPS += drivers/blinkm
CONFIGURED_APPS += drivers/stm32/tone_alarm
+CONFIGURED_APPS += drivers/stm32/adc
CONFIGURED_APPS += drivers/px4fmu
CONFIGURED_APPS += drivers/hil
diff --git a/nuttx/configs/px4fmu/nsh/defconfig b/nuttx/configs/px4fmu/nsh/defconfig
index bc724c006..52013457e 100755
--- a/nuttx/configs/px4fmu/nsh/defconfig
+++ b/nuttx/configs/px4fmu/nsh/defconfig
@@ -189,9 +189,10 @@ CONFIG_STM32_TIM1=n
CONFIG_STM32_TIM8=n
CONFIG_STM32_USART1=y
CONFIG_STM32_USART6=y
-CONFIG_STM32_ADC1=n
+# We use our own driver, but leave this on.
+CONFIG_STM32_ADC1=y
CONFIG_STM32_ADC2=n
-CONFIG_STM32_ADC3=y
+CONFIG_STM32_ADC3=n
CONFIG_STM32_SDIO=n
CONFIG_STM32_SPI1=y
CONFIG_STM32_SYSCFG=y
@@ -245,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
@@ -359,27 +360,6 @@ CONFIG_STM32_I2CTIMEOUS_START_STOP=700
CONFIG_I2C_WRITEREAD=y
#
-# ADC configuration
-#
-# Enable ADC driver support.
-#
-# CONFIG_ADC=y : Enable the generic ADC infrastructure
-# CONFIG_STM32_TIM1_ADC=y : Indicate that timer 1 will be used to trigger an ADC
-# CONFIG_STM32_TIM1_ADC3=y : Assign timer 1 to drive ADC3 sampling
-# CONFIG_STM32_ADC3_SAMPLE_FREQUENCY=100 : Select a sampling frequency
-#
-CONFIG_ADC=y
-CONFIG_STM32_TIM4_ADC3=y
-# select sample frequency 1^=1.5Msamples/second
-# 65535^=10samples/second 16bit-timer runs at 84/128 MHz
-CONFIG_STM32_ADC3_SAMPLE_FREQUENCY=6000
-# select timer channel 0=CC1,...,3=CC4
-CONFIG_STM32_ADC3_TIMTRIG=3
-CONFIG_ADC_DMA=y
-# only 4 places usable!
-CONFIG_ADC_FIFOSIZE=5
-
-#
# General build options
#
# CONFIG_RRLOAD_BINARY - make the rrload binary format used with
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 1ac70f8ab..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
#
@@ -131,6 +133,7 @@ CONFIG_STM32_BKP=n
CONFIG_STM32_PWR=n
CONFIG_STM32_DAC=n
# APB2:
+# We use our own ADC driver, but leave this on for clocking purposes.
CONFIG_STM32_ADC1=y
CONFIG_STM32_ADC2=n
# TIM1 is owned by the HRT
@@ -342,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 c31d12eee..da326f8c6 100644
--- a/nuttx/drivers/serial/serial.c
+++ b/nuttx/drivers/serial/serial.c
@@ -660,9 +660,11 @@ static int uart_ioctl(FAR struct file *filep, int cmd, unsigned long arg)
int ret = dev->ops->ioctl(filep, cmd, arg);
- /* Append any higher level TTY flags */
-
- if (ret == OK)
+ /*
+ * 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)
{
@@ -686,9 +688,43 @@ static int uart_ioctl(FAR struct file *filep, int cmd, unsigned long arg)
irqrestore(state);
*(int *)arg = count;
+ ret = 0;
+
+ break;
}
- break;
+ case FIONWRITE:
+ {
+ int count;
+ irqstate_t state = irqsave();
+
+ /* determine the number of bytes free in the buffer */
+
+ if (dev->xmit.head < dev->xmit.tail)
+ {
+ count = dev->xmit.tail - dev->xmit.head - 1;
+ }
+ else
+ {
+ count = dev->xmit.size - (dev->xmit.head - dev->xmit.tail) - 1;
+ }
+
+ irqrestore(state);
+
+ *(int *)arg = count;
+ ret = 0;
+
+ break;
+ }
+ }
+ }
+
+ /* Append any higher level TTY flags */
+
+ else if (ret == OK)
+ {
+ switch (cmd)
+ {
#ifdef CONFIG_SERIAL_TERMIOS
case TCGETS:
{
diff --git a/nuttx/include/nuttx/fs/ioctl.h b/nuttx/include/nuttx/fs/ioctl.h
index 08f62e164..6d60c2ee9 100644
--- a/nuttx/include/nuttx/fs/ioctl.h
+++ b/nuttx/include/nuttx/fs/ioctl.h
@@ -110,6 +110,10 @@
* OUT: Bytes readable from this fd
*/
+#define FIONWRITE _FIOC(0x0005) /* IN: Location to return value (int *)
+ * OUT: Bytes writable to this fd
+ */
+
/* NuttX file system ioctl definitions **************************************/
#define _DIOCVALID(c) (_IOC_TYPE(c)==_DIOCBASE)
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