aboutsummaryrefslogtreecommitdiff
path: root/nuttx
diff options
context:
space:
mode:
Diffstat (limited to 'nuttx')
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_i2c.c25
-rwxr-xr-xnuttx/configs/px4fmu/include/board.h2
-rw-r--r--nuttx/configs/px4fmu/nsh/appconfig2
-rwxr-xr-xnuttx/configs/px4io/io/defconfig10
4 files changed, 31 insertions, 8 deletions
diff --git a/nuttx/arch/arm/src/stm32/stm32_i2c.c b/nuttx/arch/arm/src/stm32/stm32_i2c.c
index a4b10b55c..80f157504 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
@@ -847,6 +863,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) */
@@ -870,8 +887,8 @@ static void stm32_i2c_tracedump(FAR struct stm32_i2c_priv_s *priv)
for (i = 0; i <= priv->tndx; i++)
{
trace = &priv->trace[i];
- lib_rawprintf("%2d. STATUS: %08x COUNT: %3d EVENT: %2d PARM: %08x TIME: %d\n",
- i+1, trace->status, trace->count, trace->event, trace->parm,
+ lib_rawprintf("%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);
}
}
@@ -1613,8 +1630,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
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 fcdf689aa..5a85a8877 100644
--- a/nuttx/configs/px4fmu/nsh/appconfig
+++ b/nuttx/configs/px4fmu/nsh/appconfig
@@ -95,7 +95,7 @@ CONFIGURED_APPS += attitude_estimator_ekf
# Hacking tools
#CONFIGURED_APPS += system/i2c
-#CONFIGURED_APPS += tools/i2c_dev
+CONFIGURED_APPS += systemcmds/i2c
# Communication and Drivers
CONFIGURED_APPS += drivers/boards/px4fmu
diff --git a/nuttx/configs/px4io/io/defconfig b/nuttx/configs/px4io/io/defconfig
index 30ec5be08..d2a4f3848 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:
@@ -188,6 +188,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
#