aboutsummaryrefslogtreecommitdiff
path: root/nuttx
diff options
context:
space:
mode:
Diffstat (limited to 'nuttx')
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_i2c.c27
-rwxr-xr-xnuttx/configs/px4fmu/include/board.h2
-rw-r--r--nuttx/configs/px4fmu/nsh/appconfig13
-rwxr-xr-xnuttx/configs/px4fmu/nsh/defconfig6
-rwxr-xr-xnuttx/configs/px4io/io/defconfig20
-rw-r--r--nuttx/libc/stdio/lib_sscanf.c52
6 files changed, 80 insertions, 40 deletions
diff --git a/nuttx/arch/arm/src/stm32/stm32_i2c.c b/nuttx/arch/arm/src/stm32/stm32_i2c.c
index 82ae6af5f..05c3f7095 100644
--- a/nuttx/arch/arm/src/stm32/stm32_i2c.c
+++ b/nuttx/arch/arm/src/stm32/stm32_i2c.c
@@ -185,6 +185,22 @@ enum stm32_trace_e
I2CEVENT_ERROR /* Error occurred, param = 0 */
};
+#ifdef CONFIG_I2C_TRACE
+static const char *stm32_trace_names[] = {
+ "NONE ",
+ "SENDADDR ",
+ "SENDBYTE ",
+ "ITBUFEN ",
+ "RCVBYTE ",
+ "REITBUFEN ",
+ "DISITBUFEN",
+ "BTFNOSTART",
+ "BTFRESTART",
+ "BTFSTOP ",
+ "ERROR "
+};
+#endif
+
/* Trace data */
struct stm32_trace_s
@@ -846,6 +862,7 @@ static void stm32_i2c_traceevent(FAR struct stm32_i2c_priv_s *priv,
trace->event = event;
trace->parm = parm;
+ trace->time = clock_systimer();
/* Bump up the trace index (unless we are out of trace entries) */
@@ -869,8 +886,8 @@ static void stm32_i2c_tracedump(FAR struct stm32_i2c_priv_s *priv)
for (i = 0; i <= priv->tndx; i++)
{
trace = &priv->trace[i];
- syslog("%2d. STATUS: %08x COUNT: %3d EVENT: %2d PARM: %08x TIME: %d\n",
- i+1, trace->status, trace->count, trace->event, trace->parm,
+ syslog("%2d. STATUS: %08x COUNT: %3d EVENT: %s PARM: %08x TIME: %d\n",
+ i+1, trace->status, trace->count, stm32_trace_names[trace->event], trace->parm,
trace->time - priv->start_time);
}
}
@@ -1620,8 +1637,8 @@ static int stm32_i2c_process(FAR struct i2c_dev_s *dev, FAR struct i2c_msg_s *ms
status = stm32_i2c_getstatus(priv);
errval = ETIMEDOUT;
- i2cdbg("Timed out: CR1: %04x status: %08x\n",
- stm32_i2c_getreg(priv, STM32_I2C_CR1_OFFSET), status);
+ i2cdbg("Timed out: CR1: %04x status: %08x after %d\n",
+ stm32_i2c_getreg(priv, STM32_I2C_CR1_OFFSET), status, timeout_us);
/* "Note: When the STOP, START or PEC bit is set, the software must
* not perform any write access to I2C_CR1 before this bit is
@@ -2005,7 +2022,7 @@ int up_i2creset(FAR struct i2c_dev_s * dev)
/* Give up if we have tried too hard */
- if (clock_count++ > 1000)
+ if (clock_count++ > CONFIG_STM32_I2CTIMEOTICKS)
{
goto out;
}
diff --git a/nuttx/configs/px4fmu/include/board.h b/nuttx/configs/px4fmu/include/board.h
index 3f0f26ba1..8ad56a4c6 100755
--- a/nuttx/configs/px4fmu/include/board.h
+++ b/nuttx/configs/px4fmu/include/board.h
@@ -299,7 +299,7 @@
#define PX4_I2C_OBDEV_EEPROM NOTDEFINED
#define PX4_I2C_OBDEV_PX4IO_BL 0x18
-#define PX4_I2C_OBDEV_PX4IO 0x19
+#define PX4_I2C_OBDEV_PX4IO 0x1a
/*
* SPI
diff --git a/nuttx/configs/px4fmu/nsh/appconfig b/nuttx/configs/px4fmu/nsh/appconfig
index 5518548a6..80cf6f312 100644
--- a/nuttx/configs/px4fmu/nsh/appconfig
+++ b/nuttx/configs/px4fmu/nsh/appconfig
@@ -46,14 +46,18 @@ CONFIGURED_APPS += systemlib
CONFIGURED_APPS += systemlib/mixer
# Math library
+ifneq ($(CONFIG_APM),y)
CONFIGURED_APPS += mathlib
CONFIGURED_APPS += mathlib/CMSIS
CONFIGURED_APPS += examples/math_demo
+endif
# Control library
+ifneq ($(CONFIG_APM),y)
CONFIGURED_APPS += controllib
CONFIGURED_APPS += examples/control_demo
CONFIGURED_APPS += examples/kalman_demo
+endif
# System utility commands
CONFIGURED_APPS += systemcmds/reboot
@@ -63,6 +67,7 @@ CONFIGURED_APPS += systemcmds/boardinfo
CONFIGURED_APPS += systemcmds/mixer
CONFIGURED_APPS += systemcmds/eeprom
CONFIGURED_APPS += systemcmds/param
+CONFIGURED_APPS += systemcmds/pwm
CONFIGURED_APPS += systemcmds/bl_update
CONFIGURED_APPS += systemcmds/preflight_check
CONFIGURED_APPS += systemcmds/delay_test
@@ -77,7 +82,7 @@ CONFIGURED_APPS += systemcmds/delay_test
# Tutorial code from
# https://pixhawk.ethz.ch/px4/dev/debug_values
-CONFIGURED_APPS += examples/px4_mavlink_debug
+# CONFIGURED_APPS += examples/px4_mavlink_debug
# Shared object broker; required by many parts of the system.
CONFIGURED_APPS += uORB
@@ -87,6 +92,8 @@ CONFIGURED_APPS += mavlink_onboard
CONFIGURED_APPS += commander
CONFIGURED_APPS += sdlog
CONFIGURED_APPS += sensors
+
+ifneq ($(CONFIG_APM),y)
CONFIGURED_APPS += ardrone_interface
CONFIGURED_APPS += multirotor_att_control
CONFIGURED_APPS += multirotor_pos_control
@@ -96,10 +103,11 @@ CONFIGURED_APPS += fixedwing_pos_control
CONFIGURED_APPS += position_estimator
CONFIGURED_APPS += attitude_estimator_ekf
CONFIGURED_APPS += hott_telemetry
+endif
# Hacking tools
#CONFIGURED_APPS += system/i2c
-#CONFIGURED_APPS += tools/i2c_dev
+CONFIGURED_APPS += systemcmds/i2c
# Communication and Drivers
CONFIGURED_APPS += drivers/boards/px4fmu
@@ -118,6 +126,7 @@ CONFIGURED_APPS += drivers/stm32/adc
CONFIGURED_APPS += drivers/px4fmu
CONFIGURED_APPS += drivers/hil
CONFIGURED_APPS += drivers/gps
+CONFIGURED_APPS += drivers/mb12xx
# Testing stuff
CONFIGURED_APPS += px4/sensors_bringup
diff --git a/nuttx/configs/px4fmu/nsh/defconfig b/nuttx/configs/px4fmu/nsh/defconfig
index 5a54e350c..130886aac 100755
--- a/nuttx/configs/px4fmu/nsh/defconfig
+++ b/nuttx/configs/px4fmu/nsh/defconfig
@@ -369,11 +369,12 @@ CONFIG_I2C_WRITEREAD=y
# I2C configuration
#
CONFIG_I2C=y
-CONFIG_I2C_POLLED=y
+CONFIG_I2C_POLLED=n
CONFIG_I2C_TRANSFER=y
CONFIG_I2C_TRACE=n
CONFIG_I2C_RESET=y
-
+# XXX fixed per-transaction timeout
+CONFIG_STM32_I2CTIMEOMS=10
# XXX re-enable after integration testing
@@ -778,6 +779,7 @@ CONFIG_NXFFS_MAXNAMLEN=32
CONFIG_NXFFS_TAILTHRESHOLD=2048
CONFIG_NXFFS_PREALLOCATED=y
CONFIG_FS_ROMFS=y
+CONFIG_FS_BINFS=y
#
# SPI-based MMC/SD driver
diff --git a/nuttx/configs/px4io/io/defconfig b/nuttx/configs/px4io/io/defconfig
index 1185813db..bb937cf4e 100755
--- a/nuttx/configs/px4io/io/defconfig
+++ b/nuttx/configs/px4io/io/defconfig
@@ -86,7 +86,7 @@ CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=n
CONFIG_ARCH_BUTTONS=n
CONFIG_ARCH_CALIBRATION=n
-CONFIG_ARCH_DMA=n
+CONFIG_ARCH_DMA=y
CONFIG_ARCH_MATH_H=y
CONFIG_ARMV7M_CMNVECTOR=y
@@ -112,7 +112,7 @@ CONFIG_STM32_JTAG_SW_ENABLE=n
# Individual subsystems can be enabled:
#
# AHB:
-CONFIG_STM32_DMA1=n
+CONFIG_STM32_DMA1=y
CONFIG_STM32_DMA2=n
CONFIG_STM32_CRC=n
# APB1:
@@ -189,6 +189,12 @@ CONFIG_USART1_2STOP=0
CONFIG_USART2_2STOP=0
CONFIG_USART3_2STOP=0
+CONFIG_USART1_RXDMA=y
+SERIAL_HAVE_CONSOLE_DMA=y
+# Conflicts with I2C1 DMA
+CONFIG_USART2_RXDMA=n
+CONFIG_USART3_RXDMA=y
+
#
# PX4IO specific driver settings
#
@@ -399,7 +405,7 @@ CONFIG_DISABLE_SIGNALS=y
CONFIG_DISABLE_MQUEUE=y
CONFIG_DISABLE_MOUNTPOINT=y
CONFIG_DISABLE_ENVIRON=y
-CONFIG_DISABLE_POLL=n
+CONFIG_DISABLE_POLL=y
#
# Misc libc settings
@@ -469,12 +475,12 @@ CONFIG_ARCH_BZERO=n
# timer structures to minimize dynamic allocations. Set to
# zero for all dynamic allocations.
#
-CONFIG_MAX_TASKS=8
+CONFIG_MAX_TASKS=4
CONFIG_MAX_TASK_ARGS=4
-CONFIG_NPTHREAD_KEYS=4
+CONFIG_NPTHREAD_KEYS=2
CONFIG_NFILE_DESCRIPTORS=8
CONFIG_NFILE_STREAMS=0
-CONFIG_NAME_MAX=32
+CONFIG_NAME_MAX=12
CONFIG_STDIO_BUFFER_SIZE=32
CONFIG_STDIO_LINEBUFFER=n
CONFIG_NUNGET_CHARS=2
@@ -535,7 +541,7 @@ CONFIG_BOOT_COPYTORAM=n
CONFIG_CUSTOM_STACK=n
CONFIG_STACK_POINTER=
CONFIG_IDLETHREAD_STACKSIZE=1024
-CONFIG_USERMAIN_STACKSIZE=1024
+CONFIG_USERMAIN_STACKSIZE=1200
CONFIG_PTHREAD_STACK_MIN=512
CONFIG_PTHREAD_STACK_DEFAULT=1024
CONFIG_HEAP_BASE=
diff --git a/nuttx/libc/stdio/lib_sscanf.c b/nuttx/libc/stdio/lib_sscanf.c
index 77a6cf212..0092fbec2 100644
--- a/nuttx/libc/stdio/lib_sscanf.c
+++ b/nuttx/libc/stdio/lib_sscanf.c
@@ -197,7 +197,7 @@ int vsscanf(FAR char *buf, FAR const char *fmt, va_list ap)
noassign = false;
lflag = false;
- while (*fmt && *buf)
+ while (*fmt)
{
/* Skip over white space */
@@ -242,6 +242,33 @@ int vsscanf(FAR char *buf, FAR const char *fmt, va_list ap)
fmt--;
}
}
+
+ /* Process %n: Character count */
+
+ if (*fmt == 'n')
+ {
+ lvdbg("vsscanf: Performing character count\n");
+
+ if (!noassign)
+ {
+ size_t nchars = (size_t)(buf - bufstart);
+
+ if (lflag)
+ {
+ long *plong = va_arg(ap, long*);
+ *plong = (long)nchars;
+ }
+ else
+ {
+ int *pint = va_arg(ap, int*);
+ *pint = (int)nchars;
+ }
+ }
+ } else {
+
+ /* Check for valid data in input string */
+ if (!(*buf))
+ break;
/* Process %s: String conversion */
@@ -445,28 +472,7 @@ int vsscanf(FAR char *buf, FAR const char *fmt, va_list ap)
#endif
}
- /* Process %n: Character count */
-
- else if (*fmt == 'n')
- {
- lvdbg("vsscanf: Performing character count\n");
-
- if (!noassign)
- {
- size_t nchars = (size_t)(buf - bufstart);
-
- if (lflag)
- {
- long *plong = va_arg(ap, long*);
- *plong = (long)nchars;
- }
- else
- {
- int *pint = va_arg(ap, int*);
- *pint = (int)nchars;
- }
- }
- }
+ }
/* Note %n does not count as a conversion */