aboutsummaryrefslogtreecommitdiff
path: root/src/modules
diff options
context:
space:
mode:
authorAndrew Tridgell <tridge@samba.org>2013-10-28 15:49:26 +1100
committerLorenz Meier <lm@inf.ethz.ch>2013-10-28 13:10:23 +0100
commit9064f8bf09dd91388b9fd3e66568d086bf1be69b (patch)
tree3038c253f0a406a4d061cc6d2d7df08632ce783a /src/modules
parent0b89051be1abd9094ac454053f47d2c2f3d183ae (diff)
downloadpx4-firmware-9064f8bf09dd91388b9fd3e66568d086bf1be69b.tar.gz
px4-firmware-9064f8bf09dd91388b9fd3e66568d086bf1be69b.tar.bz2
px4-firmware-9064f8bf09dd91388b9fd3e66568d086bf1be69b.zip
px4io: fixed the io_reg_{set,get} errors
this fixes the PX4IO state machine to avoid the io errors we were seeing. There are still some open questions with this code, but it now seems to give zero errors, which is an improvement!
Diffstat (limited to 'src/modules')
-rw-r--r--src/modules/px4iofirmware/i2c.c6
-rw-r--r--src/modules/px4iofirmware/px4io.c10
-rw-r--r--src/modules/px4iofirmware/serial.c20
3 files changed, 5 insertions, 31 deletions
diff --git a/src/modules/px4iofirmware/i2c.c b/src/modules/px4iofirmware/i2c.c
index 10aeb5c9f..79b6546b3 100644
--- a/src/modules/px4iofirmware/i2c.c
+++ b/src/modules/px4iofirmware/i2c.c
@@ -149,12 +149,6 @@ interface_init(void)
#endif
}
-void
-interface_tick()
-{
-}
-
-
/*
reset the I2C bus
used to recover from lockups
diff --git a/src/modules/px4iofirmware/px4io.c b/src/modules/px4iofirmware/px4io.c
index e70b3fe88..e28106971 100644
--- a/src/modules/px4iofirmware/px4io.c
+++ b/src/modules/px4iofirmware/px4io.c
@@ -159,9 +159,6 @@ user_start(int argc, char *argv[])
/* start the FMU interface */
interface_init();
- /* add a performance counter for the interface */
- perf_counter_t interface_perf = perf_alloc(PC_ELAPSED, "interface");
-
/* add a performance counter for mixing */
perf_counter_t mixer_perf = perf_alloc(PC_ELAPSED, "mix");
@@ -203,11 +200,6 @@ user_start(int argc, char *argv[])
/* track the rate at which the loop is running */
perf_count(loop_perf);
- /* kick the interface */
- perf_begin(interface_perf);
- interface_tick();
- perf_end(interface_perf);
-
/* kick the mixer */
perf_begin(mixer_perf);
mixer_tick();
@@ -218,6 +210,7 @@ user_start(int argc, char *argv[])
controls_tick();
perf_end(controls_perf);
+#if 0
/* check for debug activity */
show_debug_messages();
@@ -234,6 +227,7 @@ user_start(int argc, char *argv[])
(unsigned)minfo.mxordblk);
last_debug_time = hrt_absolute_time();
}
+#endif
}
}
diff --git a/src/modules/px4iofirmware/serial.c b/src/modules/px4iofirmware/serial.c
index 94d7407df..e9adc8cd6 100644
--- a/src/modules/px4iofirmware/serial.c
+++ b/src/modules/px4iofirmware/serial.c
@@ -74,9 +74,6 @@ static DMA_HANDLE rx_dma;
static int serial_interrupt(int irq, void *context);
static void dma_reset(void);
-/* if we spend this many ticks idle, reset the DMA */
-static unsigned idle_ticks;
-
static struct IOPacket dma_packet;
/* serial register accessors */
@@ -150,16 +147,6 @@ interface_init(void)
debug("serial init");
}
-void
-interface_tick()
-{
- /* XXX look for stuck/damaged DMA and reset? */
- if (idle_ticks++ > 100) {
- dma_reset();
- idle_ticks = 0;
- }
-}
-
static void
rx_handle_packet(void)
{
@@ -230,9 +217,6 @@ rx_dma_callback(DMA_HANDLE handle, uint8_t status, void *arg)
/* disable UART DMA */
rCR3 &= ~(USART_CR3_DMAT | USART_CR3_DMAR);
- /* reset the idle counter */
- idle_ticks = 0;
-
/* handle the received packet */
rx_handle_packet();
@@ -308,6 +292,7 @@ serial_interrupt(int irq, void *context)
/* it was too short - possibly truncated */
perf_count(pc_badidle);
+ dma_reset();
return 0;
}
@@ -343,7 +328,8 @@ dma_reset(void)
sizeof(dma_packet),
DMA_CCR_MINC |
DMA_CCR_PSIZE_8BITS |
- DMA_CCR_MSIZE_8BITS);
+ DMA_CCR_MSIZE_8BITS |
+ DMA_CCR_PRIVERYHI);
/* start receive DMA ready for the next packet */
stm32_dmastart(rx_dma, rx_dma_callback, NULL, false);