aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--apps/px4io/px4io.c10
-rwxr-xr-xnuttx/configs/px4io/io/defconfig3
2 files changed, 12 insertions, 1 deletions
diff --git a/apps/px4io/px4io.c b/apps/px4io/px4io.c
index 4e3555b13..e51c1c73c 100644
--- a/apps/px4io/px4io.c
+++ b/apps/px4io/px4io.c
@@ -51,6 +51,8 @@
#include <drivers/drv_pwm_output.h>
#include <drivers/drv_hrt.h>
+#include <stm32_uart.h>
+
#include "px4io.h"
__EXPORT int user_start(int argc, char *argv[]);
@@ -59,6 +61,8 @@ extern void up_cxxinitialize(void);
struct sys_state_s system_state;
+static struct hrt_call serial_dma_call;
+
int user_start(int argc, char *argv[])
{
/* run C++ ctors before we go any further */
@@ -72,6 +76,12 @@ int user_start(int argc, char *argv[])
/* configure the high-resolution time/callout interface */
hrt_init();
+ /*
+ * Poll at 1ms intervals for received bytes that have not triggered
+ * a DMA event.
+ */
+ hrt_call_every(&serial_dma_call, 1000, 1000, (hrt_callout)stm32_serial_dma_poll, NULL);
+
/* print some startup info */
lib_lowprintf("\nPX4IO: starting\n");
diff --git a/nuttx/configs/px4io/io/defconfig b/nuttx/configs/px4io/io/defconfig
index e0986b72c..d2a4f3848 100755
--- a/nuttx/configs/px4io/io/defconfig
+++ b/nuttx/configs/px4io/io/defconfig
@@ -190,7 +190,8 @@ CONFIG_USART3_2STOP=0
CONFIG_USART1_RXDMA=y
SERIAL_HAVE_CONSOLE_DMA=y
-CONFIG_USART2_RXDMA=y
+# Conflicts with I2C1 DMA
+CONFIG_USART2_RXDMA=n
CONFIG_USART3_RXDMA=y
#