aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorDavid Sidrane <david_s5@nscdg.com>2015-04-20 15:43:36 -1000
committerDavid Sidrane <david_s5@nscdg.com>2015-04-22 02:30:14 -1000
commitda07b7e5d3d76c6bd151f5ccf56d8c0ed5dbccc4 (patch)
treef30770bc2ad7eb2554dfe92d94fda99e79598472
parentdf88a792c6e86b1ae76d6b855b10d5bdadcea3e5 (diff)
downloadpx4-firmware-da07b7e5d3d76c6bd151f5ccf56d8c0ed5dbccc4.tar.gz
px4-firmware-da07b7e5d3d76c6bd151f5ccf56d8c0ed5dbccc4.tar.bz2
px4-firmware-da07b7e5d3d76c6bd151f5ccf56d8c0ed5dbccc4.zip
Nuttx Confiuration docment pass 1
-rw-r--r--nuttx-configs/px4cannode-v1/bootloader/Make.defs1
-rw-r--r--nuttx-configs/px4cannode-v1/bootloader/README.txt75
-rwxr-xr-xnuttx-configs/px4cannode-v1/bootloader/setenv.sh2
-rw-r--r--nuttx-configs/px4cannode-v1/src/Makefile4
-rw-r--r--nuttx-configs/px4cannode-v1/src/ostubs.c84
5 files changed, 111 insertions, 55 deletions
diff --git a/nuttx-configs/px4cannode-v1/bootloader/Make.defs b/nuttx-configs/px4cannode-v1/bootloader/Make.defs
index 3b5d78f4b..1ce59a3ed 100644
--- a/nuttx-configs/px4cannode-v1/bootloader/Make.defs
+++ b/nuttx-configs/px4cannode-v1/bootloader/Make.defs
@@ -3,6 +3,7 @@
#
# Copyright (C) 2015 Gregory Nutt. All rights reserved.
# Author: Gregory Nutt <gnutt@nuttx.org>
+# David Sidrane <david_s5@nscdg.com>
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
diff --git a/nuttx-configs/px4cannode-v1/bootloader/README.txt b/nuttx-configs/px4cannode-v1/bootloader/README.txt
index 530accb85..66a96d804 100644
--- a/nuttx-configs/px4cannode-v1/bootloader/README.txt
+++ b/nuttx-configs/px4cannode-v1/bootloader/README.txt
@@ -1,3 +1,42 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2015 PX4 Development Team. All rights reserved.
+ * Author: Ben Dyer <ben_dyer@mac.com>
+ * Pavel Kirienko <pavel.kirienko@zubax.com>
+ * David Sidrane <david_s5@nscdg.com>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+This file currently list the SoC that are in uses and the features from the Mfg description.
+ It includes what is current upported in Nuttx and nearest Soc to help with porting
+
Pixhawk ESC- v1.2 - STM32F105RCT6
Pixhawk ESC- v1.3 - STM32F105RCT6
Pixhawk ESC- v1.4 - STM32F105RCT6
@@ -35,42 +74,6 @@ STM32F207IG BGA 176; LQFP 176 24x24x1.4 Active ARM Cortex-M3 120 1024 - 128 12
STM32F207ZE LQFP 144 20x20x1.4 Active ARM Cortex-M3 120 512 - 128 12x16-bit 2x32-bit 2 x WDG, RTC, 24-bit down counter 24x12-bit 140 - 2x12-bit - 3xSPI 2xI2S 2xI2C 4xUSART(IrDA, ISO 7816) 2xUART 2xUSB OTG (FS+FS/HS) 2xCAN Ethernet MAC10/100 SDIO 2.5 188 -40 85
-
-
-CONFIG_ARMV7M_CMNVECTOR = y
-2+N+16
-
-stm32f10xxx 61 CONFIG_STM32_VALUELINE
-stm32f10xxx 68 CONFIG_STM32_CONNECTIVITYLINE
-VECTOR(stm32_can1tx, STM32_IRQ_CAN1TX) /* Vector 16+19: CAN1 TX interrupts */
-VECTOR(stm32_can1rx0, STM32_IRQ_CAN1RX0) /* Vector 16+20: CAN1 RX0 interrupts */
-VECTOR(stm32_can1rx, STM32_IRQ_CAN1RX1) /* Vector 16+21: CAN1 RX1 interrupt */
-VECTOR(stm32_can1sce, STM32_IRQ_CAN1SCE) /* Vector 16+22: CAN1 SCE interrupt */
-VECTOR(stm32_can2tx, STM32_IRQ_CAN2TX) /* Vector 16+63: CAN2 TX interrupts */
-VECTOR(stm32_can2rx0, STM32_IRQ_CAN2RX0) /* Vector 16+64: CAN2 RX0 interrupts */
-VECTOR(stm32_can2rx1, STM32_IRQ_CAN2RX1) /* Vector 16+65: CAN2 RX1 interrupt */
-VECTOR(stm32_can2sce, STM32_IRQ_CAN2SCE) /* Vector 16+66: CAN2 SCE interrupt */
-stm32f10xxx 60
-
-stm32f20xxx 82
-stm32f37xxx 82
-stm32f30xxx 82
-# if defined(CONFIG_STM32_STM32F427)
-# define ARMV7M_PERIPHERAL_INTERRUPTS 87
-# elif defined(CONFIG_STM32_STM32F429)
-# define ARMV7M_PERIPHERAL_INTERRUPTS 91
-# else
-# define ARMV7M_PERIPHERAL_INTERRUPTS 82
-# endif
-stm32f40xxx 87
-stm32f40xxx 91
-stm32f40xxx 82
-
-
-Notes:
-Stack for stack overflow on each function call
-
-
Nuttx HAS:
STM32F100C8
STM32F100CB
diff --git a/nuttx-configs/px4cannode-v1/bootloader/setenv.sh b/nuttx-configs/px4cannode-v1/bootloader/setenv.sh
index 92cc37485..f755f3832 100755
--- a/nuttx-configs/px4cannode-v1/bootloader/setenv.sh
+++ b/nuttx-configs/px4cannode-v1/bootloader/setenv.sh
@@ -1,7 +1,7 @@
#!/bin/bash
# configs/olimexino-stm32/tiny/setenv.sh
#
-# Copyright (C) 2025 Gregory Nutt. All rights reserved.
+# Copyright (C) 2015 Gregory Nutt. All rights reserved.
# Author: Gregory Nutt <gnutt@nuttx.org>
#
# Redistribution and use in source and binary forms, with or without
diff --git a/nuttx-configs/px4cannode-v1/src/Makefile b/nuttx-configs/px4cannode-v1/src/Makefile
index ee1bf0651..f3365d3f1 100644
--- a/nuttx-configs/px4cannode-v1/src/Makefile
+++ b/nuttx-configs/px4cannode-v1/src/Makefile
@@ -1,8 +1,8 @@
############################################################################
-# nuttx-configs/px4cannode-v1//src/Makefile
#
# Copyright (C) 2015 Gregory Nutt. All rights reserved.
-# Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+# Author: Gregory Nutt <gnutt@nuttx.org>
+# David Sidrane <david_s5@nscdg.com>
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
diff --git a/nuttx-configs/px4cannode-v1/src/ostubs.c b/nuttx-configs/px4cannode-v1/src/ostubs.c
index f39d6aa22..2d523ee1d 100644
--- a/nuttx-configs/px4cannode-v1/src/ostubs.c
+++ b/nuttx-configs/px4cannode-v1/src/ostubs.c
@@ -1,10 +1,7 @@
-
-/************************************************************************************
- * configs/olimexino-stm32/src/stm32_nss.c
+/****************************************************************************
*
- * Copyright (C) 2015 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <gnutt@nuttx.org>
- * David Sidrane <david_s5@nscdg.com>
+ * Copyright (c) 2015 PX4 Development Team. All rights reserved.
+ * Author: David Sidrane <david_s5@nscdg.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -16,7 +13,7 @@
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
- * 3. Neither the name NuttX nor the names of its contributors may be
+ * 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
@@ -43,9 +40,11 @@
#include <nuttx/init.h>
#include <nuttx/arch.h>
+#include <nuttx/kmalloc.h>
#include <stdbool.h>
#include <stdio.h>
+#include <stdlib.h>
#include <syslog.h>
#include <errno.h>
@@ -58,10 +57,24 @@
****************************************************************************/
/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
* Private Data
****************************************************************************/
/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+volatile dq_queue_t g_readytorun;
+
+/****************************************************************************
* Private Functions
****************************************************************************/
@@ -69,16 +82,20 @@
* Public Functions
****************************************************************************/
void timer_init(void);
-
-FAR void *malloc(size_t size);
-void exit(int status);
-void sched_ufree(FAR void *address);
int __wrap_up_svcall(int irq, FAR void *context);
-void os_start(void);
+/****************************************************************************
+ * Name: os_start
+ *
+ * Description:
+ * This function hijacks the entry point of the OS. Normally called by the
+ * statup code for a given architecture
+ *
+ ****************************************************************************/
void os_start(void)
{
+ /* Intalize the timer software subsystem */
timer_init();
@@ -87,34 +104,69 @@ void os_start(void)
up_irqinitialize();
+ /* Initialize the OS's timer subsystem */
#if !defined(CONFIG_SUPPRESS_INTERRUPTS) && !defined(CONFIG_SUPPRESS_TIMER_INTS) && \
!defined(CONFIG_SYSTEMTICK_EXTCLK)
up_timer_initialize();
#endif
+ /* Keep the compiler happy for a no return function*/
+
while (1)
- {
- main(0, 0);
- }
+ {
+ main(0, 0);
+ }
}
+/****************************************************************************
+ * Name: malloc
+ *
+ * Description:
+ * This function hijacks the OS's malloc and provides no allocation
+ *
+ ****************************************************************************/
+
FAR void *malloc(size_t size)
{
return NULL;
}
+/****************************************************************************
+ * Name: malloc
+ *
+ * Description:
+ * This function hijacks the systems exit
+ *
+ ****************************************************************************/
void exit(int status)
{
while (1);
}
+/****************************************************************************
+ * Name: sched_ufree
+ *
+ * Description:
+ * This function hijacks the systems sched_ufree that my be called during
+ * exception processing.
+ *
+ ****************************************************************************/
+
void sched_ufree(FAR void *address)
{
}
+/****************************************************************************
+ * Name: up_svcall
+ *
+ * Description:
+ * This function hijacks by the way of a compile time wrapper the systems
+ * up_svcall
+ *
+ ****************************************************************************/
+
int __wrap_up_svcall(int irq, FAR void *context)
{
return 0;
}
-volatile dq_queue_t g_readytorun;