aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorThomas Gubler <thomasgubler@gmail.com>2015-01-27 10:16:48 +0100
committerThomas Gubler <thomasgubler@gmail.com>2015-01-27 10:16:48 +0100
commitf0c87ef9cb68ec5e2b48bcfa00d9efb757c8ce4f (patch)
treef932706d3d5bc8967d4bb1f67b3af8aa690afe95
parent7f0e8660016638e7ca178ce80169baf864765fdb (diff)
parentb52ef8ce857bf6d70ba107285ce7c119a4df5125 (diff)
downloadpx4-firmware-f0c87ef9cb68ec5e2b48bcfa00d9efb757c8ce4f.tar.gz
px4-firmware-f0c87ef9cb68ec5e2b48bcfa00d9efb757c8ce4f.tar.bz2
px4-firmware-f0c87ef9cb68ec5e2b48bcfa00d9efb757c8ce4f.zip
Merge remote-tracking branch 'upstream/nuttx_bringup' into ros_messagelayer_merge_nuttx_bringup
Conflicts: NuttX
m---------NuttX0
-rw-r--r--nuttx-configs/aerocore/nsh/defconfig1
-rw-r--r--nuttx-configs/px4fmu-v1/nsh/defconfig1
-rw-r--r--nuttx-configs/px4fmu-v2/nsh/defconfig2
-rwxr-xr-xnuttx-configs/px4io-v1/nsh/defconfig1
-rwxr-xr-xnuttx-configs/px4io-v2/nsh/defconfig1
-rw-r--r--src/drivers/px4io/px4io_serial.cpp9
-rw-r--r--src/systemcmds/top/top.c21
8 files changed, 26 insertions, 10 deletions
diff --git a/NuttX b/NuttX
-Subproject d6d68d7d117318c7e1eadf40e989e28cba57941
+Subproject 69283d36b665ba41085021eb36066bfa074c688
diff --git a/nuttx-configs/aerocore/nsh/defconfig b/nuttx-configs/aerocore/nsh/defconfig
index 141e1d9a0..dcb132e01 100644
--- a/nuttx-configs/aerocore/nsh/defconfig
+++ b/nuttx-configs/aerocore/nsh/defconfig
@@ -318,6 +318,7 @@ CONFIG_ARCH_DMA=y
# CONFIG_ADDRENV is not set
CONFIG_ARCH_HAVE_VFORK=y
CONFIG_ARCH_STACKDUMP=y
+CONFIG_STACK_COLORATION=y
# CONFIG_ENDIAN_BIG is not set
# CONFIG_ARCH_HAVE_RAMFUNCS is not set
CONFIG_ARCH_HAVE_RAMVECTORS=y
diff --git a/nuttx-configs/px4fmu-v1/nsh/defconfig b/nuttx-configs/px4fmu-v1/nsh/defconfig
index f5adc4c4a..5bb7bed15 100644
--- a/nuttx-configs/px4fmu-v1/nsh/defconfig
+++ b/nuttx-configs/px4fmu-v1/nsh/defconfig
@@ -407,6 +407,7 @@ CONFIG_ARCH_HAVE_MPU=y
# CONFIG_ARCH_USE_MPU is not set
# CONFIG_ARCH_IRQPRIO is not set
CONFIG_ARCH_STACKDUMP=y
+CONFIG_STACK_COLORATION=y
# CONFIG_ENDIAN_BIG is not set
# CONFIG_ARCH_IDLE_CUSTOM is not set
# CONFIG_ARCH_HAVE_RAMFUNCS is not set
diff --git a/nuttx-configs/px4fmu-v2/nsh/defconfig b/nuttx-configs/px4fmu-v2/nsh/defconfig
index 2aeef89b5..ba39a3125 100644
--- a/nuttx-configs/px4fmu-v2/nsh/defconfig
+++ b/nuttx-configs/px4fmu-v2/nsh/defconfig
@@ -44,6 +44,7 @@ CONFIG_ARCH_MATH_H=y
# CONFIG_DEBUG is not set
CONFIG_ARCH_HAVE_STACKCHECK=y
CONFIG_ARCH_HAVE_HEAPCHECK=y
+CONFIG_STACK_COLORATION=y
CONFIG_DEBUG_SYMBOLS=y
CONFIG_ARCH_HAVE_CUSTOMOPT=y
CONFIG_DEBUG_NOOPT=y
@@ -1079,7 +1080,6 @@ CONFIG_EXAMPLES_NSH=y
# CONFIG_EXAMPLES_THTTPD is not set
# CONFIG_EXAMPLES_TIFF is not set
# CONFIG_EXAMPLES_TOUCHSCREEN is not set
-# CONFIG_EXAMPLES_UDP is not set
# CONFIG_EXAMPLES_WEBSERVER is not set
# CONFIG_EXAMPLES_USBSERIAL is not set
# CONFIG_EXAMPLES_USBTERM is not set
diff --git a/nuttx-configs/px4io-v1/nsh/defconfig b/nuttx-configs/px4io-v1/nsh/defconfig
index 54161dc77..10a278801 100755
--- a/nuttx-configs/px4io-v1/nsh/defconfig
+++ b/nuttx-configs/px4io-v1/nsh/defconfig
@@ -372,6 +372,7 @@ CONFIG_ARCH_HAVE_MPU=y
# CONFIG_ARCH_USE_MPU is not set
# CONFIG_ARCH_IRQPRIO is not set
CONFIG_ARCH_STACKDUMP=y
+CONFIG_STACK_COLORATION=y
# CONFIG_ENDIAN_BIG is not set
# CONFIG_ARCH_IDLE_CUSTOM is not set
# CONFIG_ARCH_HAVE_RAMFUNCS is not set
diff --git a/nuttx-configs/px4io-v2/nsh/defconfig b/nuttx-configs/px4io-v2/nsh/defconfig
index 00cf17427..bfd6f9ba9 100755
--- a/nuttx-configs/px4io-v2/nsh/defconfig
+++ b/nuttx-configs/px4io-v2/nsh/defconfig
@@ -43,6 +43,7 @@ CONFIG_ARCH_MATH_H=y
#
# CONFIG_DEBUG is not set
CONFIG_ARCH_HAVE_STACKCHECK=y
+CONFIG_STACK_COLORATION=y
CONFIG_ARCH_HAVE_HEAPCHECK=y
CONFIG_DEBUG_SYMBOLS=y
CONFIG_ARCH_HAVE_CUSTOMOPT=y
diff --git a/src/drivers/px4io/px4io_serial.cpp b/src/drivers/px4io/px4io_serial.cpp
index 928e2dab8..91f11eea1 100644
--- a/src/drivers/px4io/px4io_serial.cpp
+++ b/src/drivers/px4io/px4io_serial.cpp
@@ -217,6 +217,9 @@ PX4IO_serial::~PX4IO_serial()
stm32_unconfiggpio(PX4IO_SERIAL_TX_GPIO);
stm32_unconfiggpio(PX4IO_SERIAL_RX_GPIO);
+ /* Disable APB clock for the USART peripheral */
+ modifyreg32(STM32_RCC_APB2ENR, RCC_APB2ENR_USART6EN, 0);
+
/* and kill our semaphores */
sem_destroy(&_completion_semaphore);
sem_destroy(&_bus_semaphore);
@@ -239,12 +242,17 @@ PX4IO_serial::~PX4IO_serial()
int
PX4IO_serial::init()
{
+
/* allocate DMA */
_tx_dma = stm32_dmachannel(PX4IO_SERIAL_TX_DMAMAP);
_rx_dma = stm32_dmachannel(PX4IO_SERIAL_RX_DMAMAP);
if ((_tx_dma == nullptr) || (_rx_dma == nullptr))
return -1;
+
+ /* Enable the APB clock for the USART peripheral */
+ modifyreg32(STM32_RCC_APB2ENR, 0, RCC_APB2ENR_USART6EN);
+
/* configure pins for serial use */
stm32_configgpio(PX4IO_SERIAL_TX_GPIO);
stm32_configgpio(PX4IO_SERIAL_RX_GPIO);
@@ -258,6 +266,7 @@ PX4IO_serial::init()
(void)rSR;
(void)rDR;
+
/* configure line speed */
uint32_t usartdiv32 = PX4IO_SERIAL_CLOCK / (PX4IO_SERIAL_BITRATE / 2);
uint32_t mantissa = usartdiv32 >> 5;
diff --git a/src/systemcmds/top/top.c b/src/systemcmds/top/top.c
index 37e913040..03a049386 100644
--- a/src/systemcmds/top/top.c
+++ b/src/systemcmds/top/top.c
@@ -41,6 +41,7 @@
*/
#include <nuttx/config.h>
+#include <nuttx/arch.h>
#include <stdio.h>
#include <fcntl.h>
#include <stdbool.h>
@@ -217,18 +218,20 @@ top_main(void)
);
}
- unsigned stack_size = (uintptr_t)system_load.tasks[i].tcb->adj_stack_ptr -
- (uintptr_t)system_load.tasks[i].tcb->stack_alloc_ptr;
- unsigned stack_free = 0;
- uint8_t *stack_sweeper = (uint8_t *)system_load.tasks[i].tcb->stack_alloc_ptr;
- while (stack_free < stack_size) {
- if (*stack_sweeper++ != 0xff)
- break;
+ size_t stack_size = system_load.tasks[i].tcb->adj_stack_size;
+ ssize_t stack_free = 0;
- stack_free++;
+#if CONFIG_ARCH_INTERRUPTSTACK > 3
+ if (system_load.tasks[i].tcb->pid == 0) {
+ stack_size = (CONFIG_ARCH_INTERRUPTSTACK & ~3);
+ stack_free = up_check_intstack_remain();
+ } else {
+#endif
+ stack_free = up_check_tcbstack_remain(system_load.tasks[i].tcb);
+#if CONFIG_ARCH_INTERRUPTSTACK > 3
}
-
+#endif
printf(CL "%4d %*-s %8lld %2d.%03d %5u/%5u %3u (%3u) ",
system_load.tasks[i].tcb->pid,
CONFIG_TASK_NAME_SIZE, system_load.tasks[i].tcb->name,