aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--Makefile33
-rw-r--r--makefiles/firmware.mk2
-rw-r--r--makefiles/nuttx.mk23
-rw-r--r--nuttx-configs/px4cannode-v1/src/ostubs.c120
4 files changed, 147 insertions, 31 deletions
diff --git a/Makefile b/Makefile
index a6ca97eae..d35d15307 100644
--- a/Makefile
+++ b/Makefile
@@ -62,16 +62,11 @@ CONFIGS ?= $(KNOWN_CONFIGS)
KNOWN_BOARDS := $(subst board_,,$(basename $(notdir $(wildcard $(PX4_MK_DIR)board_*.mk))))
BOARDS ?= $(KNOWN_BOARDS)
-
#
-# Nuttx configurations
+# Canned firmware configurations for bootloader that we (know how to) build.
#
-NUTTX_CONFIGURATION ?= nsh
-
-ifeq ($(NUTTX_CONFIGURATION),bootloader)
-BOOTLOADER = bootloader
-BOOTLOADEREXT =.$(BOOTLOADER)
-endif
+KNOWN_BOARDS_WITH_BOOTLOADERS := $(subst _bootloader,, $(filter %_bootloader, $(CONFIGS)))
+BOARDS_WITH_BOOTLOADERS := $(filter $(BOARDS), $(KNOWN_BOARDS_WITH_BOOTLOADERS))
#
# Debugging
@@ -134,17 +129,18 @@ $(STAGED_FIRMWARES): $(IMAGE_DIR)%.px4: $(BUILD_DIR)%.build/firmware.px4
#
.PHONY: $(FIRMWARES)
$(BUILD_DIR)%.build/firmware.px4: config = $(patsubst $(BUILD_DIR)%.build/firmware.px4,%,$@)
+$(BUILD_DIR)%.build/firmware.px4: NUTTX_CONFIG = $(if $(findstring bootloader,$@),bootloader,nsh)
$(BUILD_DIR)%.build/firmware.px4: work_dir = $(BUILD_DIR)$(config).build/
$(FIRMWARES): $(BUILD_DIR)%.build/firmware.px4: generateuorbtopicheaders checksubmodules
@$(ECHO) %%%%
- @$(ECHO) %%%% Building $(config) in $(work_dir)
+ @$(ECHO) %%%% Building $(config) on $(NUTTX_CONFIG) in $(work_dir)
@$(ECHO) %%%%
$(Q) $(MKDIR) -p $(work_dir)
$(Q) $(MAKE) -r -C $(work_dir) \
-f $(PX4_MK_DIR)firmware.mk \
CONFIG=$(config) \
WORK_DIR=$(work_dir) \
- BOOTLOADER=$(BOOTLOADER) \
+ NUTTX_CONFIG=$(NUTTX_CONFIG) \
$(FIRMWARE_GOAL)
#
@@ -171,7 +167,8 @@ $(foreach config,$(FMU_CONFIGS),$(eval $(call FMU_DEP,$(config))))
# XXX Should support fetching/unpacking from a separate directory to permit
# downloads of the prebuilt archives as well...
#
-NUTTX_ARCHIVES = $(foreach board,$(BOARDS),$(ARCHIVE_DIR)$(board).export)
+NUTTX_BOOTLOADER_ARCHIVES = $(foreach board,$(BOARDS_WITH_BOOTLOADERS),$(ARCHIVE_DIR)$(board).bootloader.export)
+NUTTX_ARCHIVES = $(NUTTX_BOOTLOADER_ARCHIVES) $(foreach board,$(BOARDS),$(ARCHIVE_DIR)$(board).nsh.export)
.PHONY: archives
archives: checksubmodules nuttxpatches $(NUTTX_ARCHIVES)
@@ -183,18 +180,18 @@ endif
J?=1
-$(ARCHIVE_DIR)%.export: board = $(notdir $(basename $@))
-$(ARCHIVE_DIR)%.export: configuration = $(NUTTX_CONFIGURATION)
+$(ARCHIVE_DIR)%.export: board = $(basename $(notdir $(basename $@)))
+$(ARCHIVE_DIR)%.export: configuration = $(lastword $(subst ., ,$(notdir $(basename $@))))
$(NUTTX_ARCHIVES): $(ARCHIVE_DIR)%.export: $(NUTTX_SRC)
- @$(ECHO) %% Configuring NuttX for $(board) $(BOOTLOADER)
+ @$(ECHO) %% Configuring NuttX for $(board) $(configuration)
$(Q) (cd $(NUTTX_SRC) && $(RMDIR) nuttx-export)
$(Q) $(MAKE) -r -j$(J) -C $(NUTTX_SRC) -r $(MQUIET) distclean
- $(Q) (cd $(NUTTX_SRC)/configs && $(COPYDIR) $(PX4_BASE)nuttx-configs/$(board) .)
+ $(Q) (cd $(NUTTX_SRC)configs && $(COPYDIR) $(PX4_BASE)nuttx-configs/$(board) .)
$(Q) (cd $(NUTTX_SRC)tools && ./configure.sh $(board)/$(configuration))
- @$(ECHO) %% Exporting NuttX for $(board) $(BOOTLOADER)
+ @$(ECHO) %% Exporting NuttX for $(board) $(configuration)
$(Q) $(MAKE) -r -j$(J) -C $(NUTTX_SRC) -r $(MQUIET) CONFIG_ARCH_BOARD=$(board) export
- $(Q) $(MKDIR) -p $(dir $@$(BOOTLOADEREXT))
- $(Q) $(COPY) $(NUTTX_SRC)nuttx-export.zip $@$(BOOTLOADEREXT)
+ $(Q) $(MKDIR) -p $(dir $@)
+ $(Q) $(COPY) $(NUTTX_SRC)nuttx-export.zip $@
$(Q) (cd $(NUTTX_SRC)/configs && $(RMDIR) $(board))
NUTTX_PATCHES := $(wildcard $(PX4_NUTTX_PATCH_DIR)*.patch)
diff --git a/makefiles/firmware.mk b/makefiles/firmware.mk
index b0ca58c8f..edd22797c 100644
--- a/makefiles/firmware.mk
+++ b/makefiles/firmware.mk
@@ -145,6 +145,7 @@ endif
export CONFIG
include $(CONFIG_FILE)
$(info % CONFIG = $(CONFIG))
+$(info % NUTTX Config = $(NUTTX_CONFIG))
#
# Sanity-check the BOARD variable and then get the board config.
@@ -217,7 +218,6 @@ define MODULE_SEARCH
$(firstword $(abspath $(wildcard $(1)/module.mk)) \
$(abspath $(foreach search_dir,$(MODULE_SEARCH_DIRS),$(wildcard $(search_dir)/$(1)/module.mk))) \
MISSING_$1)
- $(info MODULE_SEARCH_DIRS=$(MODULE_SEARCH_DIRS))
endef
# make a list of module makefiles and check that we found them all
diff --git a/makefiles/nuttx.mk b/makefiles/nuttx.mk
index 2b5449ea0..578438f22 100644
--- a/makefiles/nuttx.mk
+++ b/makefiles/nuttx.mk
@@ -35,21 +35,11 @@
#
#
-# Are we Building a bootloader
-#
-
-ifneq ($(BOOTLOADER),)
-BOOTLOADEREXT =.$(BOOTLOADER)
-NUTTX_STARTUP = $(NUTTX_EXPORT_DIR)startup/stm32_vectors.o
-endif
-
-
-#
# Check that the NuttX archive for the selected board is available.
#
-NUTTX_ARCHIVE := $(wildcard $(ARCHIVE_DIR)$(BOARD).export$(BOOTLOADEREXT))
+NUTTX_ARCHIVE := $(wildcard $(ARCHIVE_DIR)$(BOARD).$(NUTTX_CONFIG).export)
ifeq ($(NUTTX_ARCHIVE),)
-$(error The NuttX export archive for $(BOARD) is missing from $(ARCHIVE_DIR) - try 'make archives' in $(PX4_BASE))
+$(error The NuttX export archive $(BOARD).$(CONFIG).export for $(BOARD) with configuration $(config) is missing from $(ARCHIVE_DIR) - try 'make archives' in $(PX4_BASE))
endif
#
@@ -62,6 +52,15 @@ NUTTX_CONFIG_HEADER = $(NUTTX_EXPORT_DIR)include/nuttx/config.h
$(info % NUTTX_EXPORT_DIR = $(NUTTX_EXPORT_DIR))
$(info % NUTTX_CONFIG_HEADER = $(NUTTX_CONFIG_HEADER))
+#
+# Are there any start up files not in the nuttx lib
+#
+
+NUTTX_STARTUP := $(wildcard $(NUTTX_EXPORT_DIR)startup/*.o)
+
+
+$(info * NUTTX_STARTUP = $(NUTTX_STARTUP))
+
GLOBAL_DEPS += $(NUTTX_CONFIG_HEADER)
diff --git a/nuttx-configs/px4cannode-v1/src/ostubs.c b/nuttx-configs/px4cannode-v1/src/ostubs.c
new file mode 100644
index 000000000..f39d6aa22
--- /dev/null
+++ b/nuttx-configs/px4cannode-v1/src/ostubs.c
@@ -0,0 +1,120 @@
+
+/************************************************************************************
+ * 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>
+ *
+ * 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 NuttX 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.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <nuttx/init.h>
+#include <nuttx/arch.h>
+
+#include <stdbool.h>
+#include <stdio.h>
+#include <syslog.h>
+#include <errno.h>
+
+#include <nuttx/board.h>
+
+#include "up_internal.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * 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);
+
+
+void os_start(void)
+{
+
+ timer_init();
+
+ /* Initialize the interrupt subsystem */
+
+ up_irqinitialize();
+
+
+#if !defined(CONFIG_SUPPRESS_INTERRUPTS) && !defined(CONFIG_SUPPRESS_TIMER_INTS) && \
+ !defined(CONFIG_SYSTEMTICK_EXTCLK)
+ up_timer_initialize();
+#endif
+
+ while (1)
+ {
+ main(0, 0);
+ }
+}
+
+FAR void *malloc(size_t size)
+{
+ return NULL;
+}
+
+void exit(int status)
+{
+ while (1);
+}
+
+void sched_ufree(FAR void *address)
+{
+
+}
+
+int __wrap_up_svcall(int irq, FAR void *context)
+{
+ return 0;
+}
+volatile dq_queue_t g_readytorun;