From 898292fcdb1be6c20ec735045c8e4386738290ac Mon Sep 17 00:00:00 2001 From: Corvus Corax Date: Sat, 20 Oct 2012 15:22:54 +0200 Subject: [PATCH 01/30] added (fake) firmware version information to simposix --- flight/Modules/FirmwareIAP/firmwareiap.c | 11 +++ flight/PiOS.posix/inc/pios_bl_helper.h | 46 ++++++++++++ flight/PiOS.posix/inc/pios_board_info.h | 24 +++++++ flight/PiOS.posix/inc/pios_iap.h | 45 ++++++++++++ flight/PiOS.posix/inc/pios_sys.h | 85 +++++++++++++---------- flight/PiOS.posix/pios.h | 7 ++ flight/PiOS.posix/posix/pios_bl_helper.c | 53 ++++++++++++++ flight/PiOS.posix/posix/pios_board_info.c | 20 ++++++ flight/PiOS.posix/posix/pios_iap.c | 69 ++++++++++++++++++ flight/PiOS.posix/posix/pios_sys.c | 32 ++++++--- flight/SimPosix/Makefile | 16 ++++- flight/SimPosix/System/inc/pios_config.h | 2 + make/boards/simposix/board-info.mk | 10 +-- 13 files changed, 368 insertions(+), 52 deletions(-) create mode 100644 flight/PiOS.posix/inc/pios_bl_helper.h create mode 100644 flight/PiOS.posix/inc/pios_board_info.h create mode 100644 flight/PiOS.posix/inc/pios_iap.h create mode 100644 flight/PiOS.posix/posix/pios_bl_helper.c create mode 100644 flight/PiOS.posix/posix/pios_board_info.c create mode 100644 flight/PiOS.posix/posix/pios_iap.c diff --git a/flight/Modules/FirmwareIAP/firmwareiap.c b/flight/Modules/FirmwareIAP/firmwareiap.c index 0a88046b8..d0c8d3876 100644 --- a/flight/Modules/FirmwareIAP/firmwareiap.c +++ b/flight/Modules/FirmwareIAP/firmwareiap.c @@ -108,6 +108,17 @@ int32_t FirmwareIAPInitialize() return 0; } +/** + * Initialise the module, called on startup + * \returns 0 on success or -1 if initialisation failed + */ +int32_t FirmwareIAPStart(void) +{ + /* nothing, no running task */ + return 0; +} + + /*! * \brief FirmwareIAPCallback - callback function for firmware IAP requests * \param[in] ev - pointer objevent diff --git a/flight/PiOS.posix/inc/pios_bl_helper.h b/flight/PiOS.posix/inc/pios_bl_helper.h new file mode 100644 index 000000000..e2e9e694e --- /dev/null +++ b/flight/PiOS.posix/inc/pios_bl_helper.h @@ -0,0 +1,46 @@ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_BOOTLOADER Functions + * @brief HAL code to interface to the OpenPilot AHRS module + * @{ + * + * @file pios_bl_helper.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Bootloader Helper Functions + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef PIOS_BL_HELPER_H_ +#define PIOS_BL_HELPER_H_ + +extern uint8_t *PIOS_BL_HELPER_FLASH_If_Read(uint32_t SectorAddress); + +extern uint8_t PIOS_BL_HELPER_FLASH_Ini(); + +extern uint32_t PIOS_BL_HELPER_CRC_Memory_Calc(); + +extern void PIOS_BL_HELPER_FLASH_Read_Description(uint8_t * array, uint8_t size); + +extern uint8_t PIOS_BL_HELPER_FLASH_Start(); + +extern void PIOS_BL_HELPER_CRC_Ini(); + +#endif /* PIOS_BL_HELPER_H_ */ diff --git a/flight/PiOS.posix/inc/pios_board_info.h b/flight/PiOS.posix/inc/pios_board_info.h new file mode 100644 index 000000000..3ff7aa886 --- /dev/null +++ b/flight/PiOS.posix/inc/pios_board_info.h @@ -0,0 +1,24 @@ +#ifndef PIOS_BOARD_INFO_H +#define PIOS_BOARD_INFO_H + +#include /* uint* */ + +#define PIOS_BOARD_INFO_BLOB_MAGIC 0xBDBDBDBD + +struct pios_board_info { + uint32_t magic; + uint8_t board_type; + uint8_t board_rev; + uint8_t bl_rev; + uint8_t hw_type; + uint32_t fw_base; + uint32_t fw_size; + uint32_t desc_base; + uint32_t desc_size; + uint32_t ee_base; + uint32_t ee_size; +} __attribute__((packed)); + +extern const struct pios_board_info pios_board_info_blob; + +#endif /* PIOS_BOARD_INFO_H */ diff --git a/flight/PiOS.posix/inc/pios_iap.h b/flight/PiOS.posix/inc/pios_iap.h new file mode 100644 index 000000000..d9b41170b --- /dev/null +++ b/flight/PiOS.posix/inc/pios_iap.h @@ -0,0 +1,45 @@ +/*! + * @File iap.h + * @Brief Header file for the In-Application-Programming Module + * + * Created on: Sep 6, 2010 + * Author: joe + */ + +#ifndef PIOS_IAP_H_ +#define PIOS_IAP_H_ + + +/**************************************************************************************** + * Header files + ****************************************************************************************/ + +/***************************************************************************************** + * Public Definitions/Macros + ****************************************************************************************/ +#if defined(STM32F4XX) +#define MAGIC_REG_1 RTC_BKP_DR1 +#define MAGIC_REG_2 RTC_BKP_DR2 +#define IAP_BOOTCOUNT RTC_BKP_DR3 +#else +#define MAGIC_REG_1 BKP_DR1 +#define MAGIC_REG_2 BKP_DR2 +#define IAP_BOOTCOUNT BKP_DR3 +#endif + +/**************************************************************************************** + * Public Functions + ****************************************************************************************/ +void PIOS_IAP_Init(void); +uint32_t PIOS_IAP_CheckRequest( void ); +void PIOS_IAP_SetRequest1(void); +void PIOS_IAP_SetRequest2(void); +void PIOS_IAP_ClearRequest(void); +uint16_t PIOS_IAP_ReadBootCount(void); +void PIOS_IAP_WriteBootCount(uint16_t); + +/**************************************************************************************** + * Public Data + ****************************************************************************************/ + +#endif /* PIOS_IAP_H_ */ diff --git a/flight/PiOS.posix/inc/pios_sys.h b/flight/PiOS.posix/inc/pios_sys.h index 4e71b54a0..7f183a892 100644 --- a/flight/PiOS.posix/inc/pios_sys.h +++ b/flight/PiOS.posix/inc/pios_sys.h @@ -1,35 +1,50 @@ -/** - ****************************************************************************** - * - * @file pios_sys.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * Parts by Thorsten Klose (tk@midibox.org) - * @brief System and hardware Init functions header. - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef PIOS_SYS_H -#define PIOS_SYS_H - -/* Public Functions */ -extern void PIOS_SYS_Init(void); -extern int32_t PIOS_SYS_Reset(void); -extern int32_t PIOS_SYS_SerialNumberGet(char *str); - -#endif /* PIOS_SYS_H */ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_SYS System Functions + * @brief PIOS System Initialization code + * @{ + * + * @file pios_sys.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * Parts by Thorsten Klose (tk@midibox.org) + * @brief System and hardware Init functions header. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef PIOS_SYS_H +#define PIOS_SYS_H + +#define PIOS_SYS_SERIAL_NUM_BINARY_LEN 12 +#define PIOS_SYS_SERIAL_NUM_ASCII_LEN (PIOS_SYS_SERIAL_NUM_BINARY_LEN * 2) + +/* Public Functions */ +extern void PIOS_SYS_Init(void); +extern int32_t PIOS_SYS_Reset(void); +extern uint32_t PIOS_SYS_getCPUFlashSize(void); +extern int32_t PIOS_SYS_SerialNumberGetBinary(uint8_t array[PIOS_SYS_SERIAL_NUM_BINARY_LEN]); +extern int32_t PIOS_SYS_SerialNumberGet(char str[PIOS_SYS_SERIAL_NUM_ASCII_LEN+1]); + +#endif /* PIOS_SYS_H */ + +/** + * @} + * @} + */ diff --git a/flight/PiOS.posix/pios.h b/flight/PiOS.posix/pios.h index 8e96fa092..28e896835 100644 --- a/flight/PiOS.posix/pios.h +++ b/flight/PiOS.posix/pios.h @@ -68,6 +68,13 @@ #include #include +#if defined(PIOS_INCLUDE_IAP) +#include +#endif +#if defined(PIOS_INCLUDE_BL_HELPER) +#include +#endif + #define NELEMENTS(x) (sizeof(x) / sizeof(*(x))) #endif /* PIOS_H */ diff --git a/flight/PiOS.posix/posix/pios_bl_helper.c b/flight/PiOS.posix/posix/pios_bl_helper.c new file mode 100644 index 000000000..a7920e5d2 --- /dev/null +++ b/flight/PiOS.posix/posix/pios_bl_helper.c @@ -0,0 +1,53 @@ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_BOOTLOADER Functions + * @brief HAL code to interface to the OpenPilot AHRS module + * @{ + * + * @file pios_bl_helper.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @brief Bootloader Helper Functions + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +/* Project Includes */ +#include "pios.h" +#if defined(PIOS_INCLUDE_BL_HELPER) +#include + +uint32_t PIOS_BL_HELPER_CRC_Memory_Calc() +{ + return 0; +} + +extern const struct fw_version_info fw_version_blob; +void PIOS_BL_HELPER_FLASH_Read_Description(uint8_t * array, uint8_t size) +{ + uint8_t * desc = (uint8_t *) &fw_version_blob; + for (uint32_t i = 0; i < size; i++) { + array[i] = desc[i]; + } +} + +void PIOS_BL_HELPER_CRC_Ini() +{ +} +#endif diff --git a/flight/PiOS.posix/posix/pios_board_info.c b/flight/PiOS.posix/posix/pios_board_info.c new file mode 100644 index 000000000..c273a881d --- /dev/null +++ b/flight/PiOS.posix/posix/pios_board_info.c @@ -0,0 +1,20 @@ +#include +#include + +#include "pios_board_info.h" + +const struct pios_board_info pios_board_info_blob = { + .magic = PIOS_BOARD_INFO_BLOB_MAGIC, + .board_type = BOARD_TYPE, + .board_rev = BOARD_REVISION, + .bl_rev = BOOTLOADER_VERSION, + .hw_type = HW_TYPE, + .fw_base = FW_BANK_BASE, + .fw_size = FW_BANK_SIZE - FW_DESC_SIZE, + .desc_base = FW_BANK_BASE + FW_BANK_SIZE - FW_DESC_SIZE, + .desc_size = FW_DESC_SIZE, +#ifdef EE_BANK_BASE + .ee_base = EE_BANK_BASE, + .ee_size = EE_BANK_SIZE, +#endif +}; diff --git a/flight/PiOS.posix/posix/pios_iap.c b/flight/PiOS.posix/posix/pios_iap.c new file mode 100644 index 000000000..be5b19536 --- /dev/null +++ b/flight/PiOS.posix/posix/pios_iap.c @@ -0,0 +1,69 @@ +/*! + * @File iap.c + * @Brief + * + * Created on: Sep 6, 2010 + * Author: joe + */ + + +/**************************************************************************************** + * Header files + ****************************************************************************************/ +#include + +/*! + * \brief PIOS_IAP_Init - performs required initializations for iap module. + * \param none. + * \return none. + * \retval none. + * + * Created: Sep 8, 2010 10:10:48 PM by joe + */ +void PIOS_IAP_Init( void ) +{ + +} + +/*! + * \brief Determines if an In-Application-Programming request has been made. + * \param *comm - Which communication stream to use for the IAP (USB, Telemetry, I2C, SPI, etc) + * \return TRUE - if correct sequence found, along with 'comm' updated. + * FALSE - Note that 'comm' will have an invalid comm identifier. + * \retval + * + */ +uint32_t PIOS_IAP_CheckRequest( void ) +{ + + return false; +} + + + +/*! + * \brief Sets the 1st word of the request sequence. + * \param n/a + * \return n/a + * \retval + */ +void PIOS_IAP_SetRequest1(void) +{ +} + +void PIOS_IAP_SetRequest2(void) +{ +} + +void PIOS_IAP_ClearRequest(void) +{ +} + +uint16_t PIOS_IAP_ReadBootCount(void) +{ + return 0; +} + +void PIOS_IAP_WriteBootCount (uint16_t boot_count) +{ +} diff --git a/flight/PiOS.posix/posix/pios_sys.c b/flight/PiOS.posix/posix/pios_sys.c index 85cdc9727..6b685f6fe 100644 --- a/flight/PiOS.posix/posix/pios_sys.c +++ b/flight/PiOS.posix/posix/pios_sys.c @@ -110,6 +110,23 @@ int32_t PIOS_SYS_Reset(void) return -1; } +/** +* Returns the serial number as a string +* param[out] uint8_t pointer to a string which can store at least 12 bytes +* (12 bytes returned for STM32) +* return < 0 if feature not supported +*/ +int32_t PIOS_SYS_SerialNumberGetBinary(uint8_t *array) +{ + /* Stored in the so called "electronic signature" */ + for (int i = 0; i < PIOS_SYS_SERIAL_NUM_BINARY_LEN; ++i) { + array[i] = 0xff; + } + + /* No error */ + return 0; +} + /** * Returns the serial number as a string * param[out] str pointer to a string which can store at least 32 digits + zero terminator! @@ -118,19 +135,12 @@ int32_t PIOS_SYS_Reset(void) */ int32_t PIOS_SYS_SerialNumberGet(char *str) { - int i; - /* Stored in the so called "electronic signature" */ - for(i=0; i<24; ++i) { - //uint8_t b = MEM8(0x1ffff7e8 + (i/2)); - //if( !(i & 1) ) - //b >>= 4; - //b &= 0x0f; - - //str[i] = ((b > 9) ? ('A'-10) : '0') + b; - str[i]='6'; + int i; + for (i = 0; i < PIOS_SYS_SERIAL_NUM_ASCII_LEN; ++i) { + str[i] = 'F'; } - str[i] = 0; + str[i] = '\0'; /* No error */ return 0; diff --git a/flight/SimPosix/Makefile b/flight/SimPosix/Makefile index 9e24125ee..2bdbc2066 100644 --- a/flight/SimPosix/Makefile +++ b/flight/SimPosix/Makefile @@ -55,6 +55,7 @@ FLASH_TOOL = OPENOCD MODULES = ManualControl Stabilization GPS MODULES += CameraStab MODULES += Telemetry +MODULES += FirmwareIAP #MODULES += OveroSync PYMODULES = #FlightPlan @@ -242,6 +243,19 @@ EXTRA_LIBS = # 0 = turn off optimization. s = optimize for size. # (Note: 3 is not always the best optimization level. See avr-libc FAQ.) + +BLONLY_CDEFS += -DBOARD_TYPE=$(BOARD_TYPE) +BLONLY_CDEFS += -DBOARD_REVISION=$(BOARD_REVISION) +BLONLY_CDEFS += -DHW_TYPE=$(HW_TYPE) +BLONLY_CDEFS += -DBOOTLOADER_VERSION=$(BOOTLOADER_VERSION) +BLONLY_CDEFS += -DFW_BANK_BASE=$(FW_BANK_BASE) +BLONLY_CDEFS += -DFW_BANK_SIZE=$(FW_BANK_SIZE) +BLONLY_CDEFS += -DFW_DESC_SIZE=$(FW_DESC_SIZE) + +# Since we are simulating all this firmware the code needs to know what the BL would +# normally contain +CFLAGS += $(BLONLY_CDEFS) + ifeq ($(DEBUG),YES) CFLAGS += -O0 CFLAGS += -DGENERAL_COV @@ -370,7 +384,7 @@ ALLSRC = $(ASRCARM) $(ASRC) $(SRCARM) $(SRC) $(CPPSRCARM) $(CPPSRC) ALLSRCBASE = $(notdir $(basename $(ALLSRC))) # Define all object files. -ALLOBJ = $(addprefix $(OUTDIR)/, $(addsuffix .o, $(ALLSRCBASE))) +ALLOBJ = $(addprefix $(OUTDIR)/, $(addsuffix .o, $(ALLSRCBASE) $(TARGET).bin.firmwareinfo )) # Define all listing files (used for make clean). LSTFILES = $(addprefix $(OUTDIR)/, $(addsuffix .lst, $(ALLSRCBASE))) diff --git a/flight/SimPosix/System/inc/pios_config.h b/flight/SimPosix/System/inc/pios_config.h index d4add3666..c2413f6c0 100644 --- a/flight/SimPosix/System/inc/pios_config.h +++ b/flight/SimPosix/System/inc/pios_config.h @@ -84,6 +84,8 @@ #define PIOS_INCLUDE_PPM #define PIOS_INCLUDE_PWM //#define PIOS_INCLUDE_GCSRCVR +#define PIOS_INCLUDE_IAP +#define PIOS_INCLUDE_BL_HELPER #define PIOS_INCLUDE_SETTINGS #define PIOS_INCLUDE_FLASH diff --git a/make/boards/simposix/board-info.mk b/make/boards/simposix/board-info.mk index 4a637a53d..c60452f33 100644 --- a/make/boards/simposix/board-info.mk +++ b/make/boards/simposix/board-info.mk @@ -13,12 +13,12 @@ OPENOCD_JTAG_CONFIG := OPENOCD_CONFIG := # Note: These must match the values in link_$(BOARD)_memory.ld -#BL_BANK_BASE := 0x08000000 # Start of bootloader flash -#BL_BANK_SIZE := 0x00008000 # Should include BD_INFO region -#FW_BANK_BASE := 0x08008000 # Start of firmware flash -#FW_BANK_SIZE := 0x00038000 # Should include FW_DESC_SIZE +BL_BANK_BASE := 0x08000000 # Start of bootloader flash +BL_BANK_SIZE := 0x00008000 # Should include BD_INFO region +FW_BANK_BASE := 0x08008000 # Start of firmware flash +FW_BANK_SIZE := 0x00038000 # Should include FW_DESC_SIZE -#FW_DESC_SIZE := 0x00000064 +FW_DESC_SIZE := 0x00000064 OSCILLATOR_FREQ := 8000000 SYSCLK_FREQ := 168000000 From 1fe41c7a67ed6b8957f3a231646e80e6391a3dd1 Mon Sep 17 00:00:00 2001 From: Corvus Corax Date: Sat, 20 Oct 2012 16:07:16 +0200 Subject: [PATCH 02/30] circular dependency on firmwareinfo due to checksum of firmware required to link firmware - fixed by creating checksum of uavobject inittialization object file instead --- flight/SimPosix/Makefile | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/flight/SimPosix/Makefile b/flight/SimPosix/Makefile index 2bdbc2066..7244068a0 100644 --- a/flight/SimPosix/Makefile +++ b/flight/SimPosix/Makefile @@ -384,7 +384,7 @@ ALLSRC = $(ASRCARM) $(ASRC) $(SRCARM) $(SRC) $(CPPSRCARM) $(CPPSRC) ALLSRCBASE = $(notdir $(basename $(ALLSRC))) # Define all object files. -ALLOBJ = $(addprefix $(OUTDIR)/, $(addsuffix .o, $(ALLSRCBASE) $(TARGET).bin.firmwareinfo )) +ALLOBJ = $(addprefix $(OUTDIR)/, $(addsuffix .o, $(ALLSRCBASE) uavobjectsinit.o.firmwareinfo )) # Define all listing files (used for make clean). LSTFILES = $(addprefix $(OUTDIR)/, $(addsuffix .lst, $(ALLSRCBASE))) @@ -440,6 +440,8 @@ $(OUTDIR)/$(TARGET).bin.o: $(OUTDIR)/$(TARGET).bin $(eval $(call OPFW_TEMPLATE,$(OUTDIR)/$(TARGET).bin,$(BOARD_TYPE),$(BOARD_REVISION))) +$(eval $(call OPFW_TEMPLATE,$(OUTDIR)/uavobjectsinit.o,$(BOARD_TYPE),$(BOARD_REVISION))) + # Add jtag targets (program and wipe) $(eval $(call JTAG_TEMPLATE,$(OUTDIR)/$(TARGET).bin,$(FW_BANK_BASE),$(FW_BANK_SIZE),$(OPENOCD_JTAG_CONFIG),$(OPENOCD_CONFIG))) From 0b6fa7fe6f13aa7c74ffc8c2f1382271865995e6 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Thu, 25 Oct 2012 09:55:54 -0500 Subject: [PATCH 03/30] Sanity Checking: Regardless of DIAG_TASK always populate TaskInfo.Running so we can verify certain modules are running. --- flight/Libraries/taskmonitor.c | 2 -- flight/Modules/System/systemmod.c | 4 ---- 2 files changed, 6 deletions(-) diff --git a/flight/Libraries/taskmonitor.c b/flight/Libraries/taskmonitor.c index fffc6435c..0ea4cbf52 100644 --- a/flight/Libraries/taskmonitor.c +++ b/flight/Libraries/taskmonitor.c @@ -94,7 +94,6 @@ int32_t TaskMonitorRemove(TaskInfoRunningElem task) */ void TaskMonitorUpdateAll(void) { -#if defined(DIAG_TASKS) TaskInfoData data; int n; @@ -145,5 +144,4 @@ void TaskMonitorUpdateAll(void) // Done xSemaphoreGiveRecursive(lock); -#endif } diff --git a/flight/Modules/System/systemmod.c b/flight/Modules/System/systemmod.c index fa3be09e2..470d786f8 100644 --- a/flight/Modules/System/systemmod.c +++ b/flight/Modules/System/systemmod.c @@ -123,9 +123,7 @@ int32_t SystemModInitialize(void) SystemStatsInitialize(); FlightStatusInitialize(); ObjectPersistenceInitialize(); -#if defined(DIAG_TASKS) TaskInfoInitialize(); -#endif #if defined(I2C_WDG_STATS_DIAGNOSTICS) I2CStatsInitialize(); WatchdogStatusInitialize(); @@ -181,10 +179,8 @@ static void systemTask(void *parameters) updateWDGstats(); #endif -#if defined(DIAG_TASKS) // Update the task status object TaskMonitorUpdateAll(); -#endif // Flash the heartbeat LED #if defined(PIOS_LED_HEARTBEAT) From 68ae9f52c955c633db0c995497a8600151c077ad Mon Sep 17 00:00:00 2001 From: James Cotton Date: Thu, 25 Oct 2012 12:31:26 -0500 Subject: [PATCH 04/30] SystemAlarms: Convert to the newer way of listing elements to help merges and added SystemConfiguration --- shared/uavobjectdefinition/systemalarms.xml | 23 +++++++++++++++++++-- 1 file changed, 21 insertions(+), 2 deletions(-) diff --git a/shared/uavobjectdefinition/systemalarms.xml b/shared/uavobjectdefinition/systemalarms.xml index dd185cfa3..62f90d0d1 100644 --- a/shared/uavobjectdefinition/systemalarms.xml +++ b/shared/uavobjectdefinition/systemalarms.xml @@ -1,8 +1,27 @@ Alarms from OpenPilot to indicate failure conditions or warnings. Set by various modules. - + + + OutOfMemory + CPUOverload + StackOverflow + SystemConfiguration + EventSystem + Telemetry + ManualControl + Actuator + Attitude + Sensors + Stabilization + Guidance + Battery + FlightTime + I2C + GPS + BootFault + + From b9ebeb2c2e4ac472331fd29ba43572f8daae6ef9 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Thu, 25 Oct 2012 12:43:56 -0500 Subject: [PATCH 05/30] Sanity Check: For now force the sanity check to run once a second and always set an error --- flight/CopterControl/Makefile | 1 + flight/Libraries/inc/sanitycheck.h | 34 +++++++++++++++++++++ flight/Libraries/sanitycheck.c | 47 ++++++++++++++++++++++++++++++ flight/Modules/System/systemmod.c | 4 +++ 4 files changed, 86 insertions(+) create mode 100644 flight/Libraries/inc/sanitycheck.h create mode 100644 flight/Libraries/sanitycheck.c diff --git a/flight/CopterControl/Makefile b/flight/CopterControl/Makefile index 128968585..6cc41bd69 100644 --- a/flight/CopterControl/Makefile +++ b/flight/CopterControl/Makefile @@ -278,6 +278,7 @@ SRC += $(PIOSCOMMON)/printf-stdarg.c SRC += $(FLIGHTLIB)/fifo_buffer.c SRC += $(FLIGHTLIB)/CoordinateConversions.c SRC += $(FLIGHTLIB)/taskmonitor.c +SRC += $(FLIGHTLIB)/sanitycheck.c SRC += $(MATHLIB)/sin_lookup.c SRC += $(MATHLIB)/pid.c diff --git a/flight/Libraries/inc/sanitycheck.h b/flight/Libraries/inc/sanitycheck.h new file mode 100644 index 000000000..2f201da22 --- /dev/null +++ b/flight/Libraries/inc/sanitycheck.h @@ -0,0 +1,34 @@ +/** + ****************************************************************************** + * @addtogroup OpenPilotSystem OpenPilot System + * @{ + * @addtogroup OpenPilotLibraries OpenPilot System Libraries + * @{ + * @file sanitycheck.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @brief Utilities to validate a flight configuration + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef SANITYCHECK_H +#define SANITYCHECK_H + +extern int32_t configuration_check(); + +#endif /* SANITYCHECK_H */ \ No newline at end of file diff --git a/flight/Libraries/sanitycheck.c b/flight/Libraries/sanitycheck.c new file mode 100644 index 000000000..2b2622186 --- /dev/null +++ b/flight/Libraries/sanitycheck.c @@ -0,0 +1,47 @@ +/** + ****************************************************************************** + * @addtogroup OpenPilot System OpenPilot System + * @{ + * @addtogroup OpenPilot Libraries OpenPilot System Libraries + * @{ + * @file sanitycheck.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @brief Utilities to validate a flight configuration + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#include "openpilot.h" +#include "sanitycheck.h" +#include "hwsettings.h" +#include "taskinfo.h" +#include "manualcontrolsettings.h" +#include "systemalarms.h" + +/** + * Run a preflight check over the hardware configuration + * and currently active modules + */ +int32_t configuration_check() +{ + // TODO: Check manual control settings for any modes that can be accessed without the + // necessary module running + AlarmsSet(SYSTEMALARMS_ALARM_SYSTEMCONFIGURATION, SYSTEMALARMS_ALARM_CRITICAL); + + return 0; +} \ No newline at end of file diff --git a/flight/Modules/System/systemmod.c b/flight/Modules/System/systemmod.c index 470d786f8..bd4382500 100644 --- a/flight/Modules/System/systemmod.c +++ b/flight/Modules/System/systemmod.c @@ -40,6 +40,7 @@ #include "openpilot.h" #include "systemmod.h" +#include "sanitycheck.h" #include "objectpersistence.h" #include "flightstatus.h" #include "systemstats.h" @@ -172,6 +173,9 @@ static void systemTask(void *parameters) // Update the system statistics updateStats(); + // TODO: Make this only be called when configuration settings change + configuration_check(); + // Update the system alarms updateSystemAlarms(); #if defined(I2C_WDG_STATS_DIAGNOSTICS) From 23422d3cd45be80cbc2dec3ec8509543fd4e3f29 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Thu, 25 Oct 2012 14:41:59 -0500 Subject: [PATCH 06/30] Sanity Check. Add the first set of checks: 1. If a flight mode switch allows autotune and autotune module not running 2. If airframe is a multirotor and either manual is available or a stabilization mode uses "none" --- flight/Libraries/sanitycheck.c | 139 ++++++++++++++++++++++++++++++++- 1 file changed, 137 insertions(+), 2 deletions(-) diff --git a/flight/Libraries/sanitycheck.c b/flight/Libraries/sanitycheck.c index 2b2622186..ce3ab3cd3 100644 --- a/flight/Libraries/sanitycheck.c +++ b/flight/Libraries/sanitycheck.c @@ -27,11 +27,22 @@ */ #include "openpilot.h" +#include #include "sanitycheck.h" #include "hwsettings.h" #include "taskinfo.h" #include "manualcontrolsettings.h" #include "systemalarms.h" +#include "systemsettings.h" + +/**************************** + * Current checks: + * 1. If a flight mode switch allows autotune and autotune module not running + * 2. If airframe is a multirotor and either manual is available or a stabilization mode uses "none" + ****************************/ + +//! Check a stabilization mode switch position for safety +static int32_t check_stabilization_settings(int index, bool multirotor); /** * Run a preflight check over the hardware configuration @@ -39,9 +50,133 @@ */ int32_t configuration_check() { - // TODO: Check manual control settings for any modes that can be accessed without the + int32_t status = SYSTEMALARMS_ALARM_OK; + // TODO: Check manual control settings for any modes that can be accessed without the // necessary module running - AlarmsSet(SYSTEMALARMS_ALARM_SYSTEMCONFIGURATION, SYSTEMALARMS_ALARM_CRITICAL); + + // TODO: Get board type + const struct pios_board_info * bdinfo = &pios_board_info_blob; + bool coptercontrol = bdinfo->board_type == 0x04; + + // Classify airframe type + bool multirotor = true; + + uint8_t airframe_type; + SystemSettingsAirframeTypeGet(&airframe_type); + switch(airframe_type) { + case SYSTEMSETTINGS_AIRFRAMETYPE_QUADX: + case SYSTEMSETTINGS_AIRFRAMETYPE_QUADP: + case SYSTEMSETTINGS_AIRFRAMETYPE_HEXA: + case SYSTEMSETTINGS_AIRFRAMETYPE_OCTO: + case SYSTEMSETTINGS_AIRFRAMETYPE_HEXAX: + case SYSTEMSETTINGS_AIRFRAMETYPE_OCTOV: + case SYSTEMSETTINGS_AIRFRAMETYPE_OCTOCOAXP: + case SYSTEMSETTINGS_AIRFRAMETYPE_HEXACOAX: + case SYSTEMSETTINGS_AIRFRAMETYPE_TRI: + multirotor = true; + break; + default: + multirotor = false; + } + + // Get the running modules + uint8_t running[TASKINFO_RUNNING_NUMELEM]; + TaskInfoRunningGet(running); + + // For each available flight mode position sanity check the available + // modes + uint8_t num_modes; + uint8_t modes[MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_NUMELEM]; + ManualControlSettingsFlightModeNumberGet(&num_modes); + ManualControlSettingsFlightModePositionGet(modes); + + for(int i = 0; i < num_modes; i++) { + switch(modes[i]) { + case MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_MANUAL: + if (multirotor) + status = SYSTEMALARMS_ALARM_ERROR; + break; + case MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_STABILIZED1: + status = (status == SYSTEMALARMS_ALARM_OK) ? check_stabilization_settings(1, multirotor) : status; + break; + case MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_STABILIZED2: + status = (status == SYSTEMALARMS_ALARM_OK) ? check_stabilization_settings(2, multirotor) : status; + break; + case MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_STABILIZED3: + status = (status == SYSTEMALARMS_ALARM_OK) ? check_stabilization_settings(3, multirotor) : status; + break; + case MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_AUTOTUNE: + if (running[TASKINFO_RUNNING_AUTOTUNE] != TASKINFO_RUNNING_TRUE) + status = SYSTEMALARMS_ALARM_ERROR; + break; + case MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_ALTITUDEHOLD: + if (coptercontrol) + status = SYSTEMALARMS_ALARM_ERROR; + break; + case MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_VELOCITYCONTROL: + if (coptercontrol) + status = SYSTEMALARMS_ALARM_ERROR; + break; + case MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_POSITIONHOLD: + if (coptercontrol) + status = SYSTEMALARMS_ALARM_ERROR; + break; + default: + // Uncovered modes are automatically an error + status = SYSTEMALARMS_ALARM_ERROR; + } + } + + // TODO: Check on a multirotor no axis supports "None" + if(status != SYSTEMALARMS_ALARM_OK) + AlarmsSet(SYSTEMALARMS_ALARM_SYSTEMCONFIGURATION, status); + else + AlarmsClear(SYSTEMALARMS_ALARM_SYSTEMCONFIGURATION); return 0; +} + +/** + * Checks the stabiliation settings for a paritcular mode and makes + * sure it is appropriate for the airframe + * @param[in] index Which stabilization mode to check + * @returns SYSTEMALARMS_ALARM_OK or SYSTEMALARMS_ALARM_ERROR + */ +static int32_t check_stabilization_settings(int index, bool multirotor) +{ + // Make sure the modes are all similar + if (MANUALCONTROLSETTINGS_STABILIZATION1SETTINGS_NUMELEM != MANUALCONTROLSETTINGS_STABILIZATION2SETTINGS_NUMELEM || + MANUALCONTROLSETTINGS_STABILIZATION1SETTINGS_NUMELEM != MANUALCONTROLSETTINGS_STABILIZATION3SETTINGS_NUMELEM) + return SYSTEMALARMS_ALARM_ERROR; + + uint8_t modes[MANUALCONTROLSETTINGS_STABILIZATION1SETTINGS_NUMELEM]; + + // Get the different axis modes for this switch position + switch(index) { + case 1: + ManualControlSettingsStabilization1SettingsGet(modes); + break; + case 2: + ManualControlSettingsStabilization2SettingsGet(modes); + break; + case 3: + ManualControlSettingsStabilization3SettingsGet(modes); + break; + default: + return SYSTEMALARMS_ALARM_ERROR; + } + + // For multirotors verify that nothing is set to "none" + if (multirotor) { + for(int i = 0; i < NELEMENTS(modes); i++) { + if (modes[i] == MANUALCONTROLSETTINGS_STABILIZATION1SETTINGS_NONE) + return SYSTEMALARMS_ALARM_ERROR; + } + } + + // Warning: This assumes that certain conditions in the XML file are met. That + // MANUALCONTROLSETTINGS_STABILIZATION1SETTINGS_NONE has the same numeric value for each channel + // and is the same for STABILIZATIONDESIRED_STABILIZATIONMODE_NONE + + return SYSTEMALARMS_ALARM_OK; } \ No newline at end of file From 736f96b297afcf118ddced05bb1deede0143f7c9 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Thu, 25 Oct 2012 20:36:21 -0500 Subject: [PATCH 07/30] Sanity check: Add some initial checks for revo that make sure the needed optional modules are running. --- flight/Libraries/sanitycheck.c | 20 ++++++++++++++++---- 1 file changed, 16 insertions(+), 4 deletions(-) diff --git a/flight/Libraries/sanitycheck.c b/flight/Libraries/sanitycheck.c index ce3ab3cd3..b716259ff 100644 --- a/flight/Libraries/sanitycheck.c +++ b/flight/Libraries/sanitycheck.c @@ -51,16 +51,13 @@ static int32_t check_stabilization_settings(int index, bool multirotor); int32_t configuration_check() { int32_t status = SYSTEMALARMS_ALARM_OK; - // TODO: Check manual control settings for any modes that can be accessed without the - // necessary module running - // TODO: Get board type + // Get board type const struct pios_board_info * bdinfo = &pios_board_info_blob; bool coptercontrol = bdinfo->board_type == 0x04; // Classify airframe type bool multirotor = true; - uint8_t airframe_type; SystemSettingsAirframeTypeGet(&airframe_type); switch(airframe_type) { @@ -112,14 +109,29 @@ int32_t configuration_check() case MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_ALTITUDEHOLD: if (coptercontrol) status = SYSTEMALARMS_ALARM_ERROR; + else { + // Revo supports altitude hold + if(running[TASKINFO_RUNNING_ALTITUDEHOLD] != TASKINFO_RUNNING_TRUE) + status = SYSTEMALARMS_ALARM_ERROR; + } break; case MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_VELOCITYCONTROL: if (coptercontrol) status = SYSTEMALARMS_ALARM_ERROR; + else { + // Revo supports altitude hold + if(running[TASKINFO_RUNNING_GUIDANCE] != TASKINFO_RUNNING_TRUE) + status = SYSTEMALARMS_ALARM_ERROR; + } break; case MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_POSITIONHOLD: if (coptercontrol) status = SYSTEMALARMS_ALARM_ERROR; + else { + // Revo supports altitude hold + if(running[TASKINFO_RUNNING_GUIDANCE] != TASKINFO_RUNNING_TRUE) + status = SYSTEMALARMS_ALARM_ERROR; + } break; default: // Uncovered modes are automatically an error From b28cdba46de51c68c2c2f2ad60e8b131a41dc7a9 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Thu, 25 Oct 2012 21:49:53 -0500 Subject: [PATCH 08/30] SanityCheck: Trigger sanity check code on callbacks from the appropriate settings. The only downside is that it needs to update on the TaskInfo object which means since htat updates periodically this code runs more often that really needed since the modules only start at first. However, leaving that connection out means it misses the initial set of modules. --- flight/Libraries/sanitycheck.c | 1 - flight/Modules/System/systemmod.c | 21 ++++++++++++++++++--- 2 files changed, 18 insertions(+), 4 deletions(-) diff --git a/flight/Libraries/sanitycheck.c b/flight/Libraries/sanitycheck.c index b716259ff..87b1e8352 100644 --- a/flight/Libraries/sanitycheck.c +++ b/flight/Libraries/sanitycheck.c @@ -29,7 +29,6 @@ #include "openpilot.h" #include #include "sanitycheck.h" -#include "hwsettings.h" #include "taskinfo.h" #include "manualcontrolsettings.h" #include "systemalarms.h" diff --git a/flight/Modules/System/systemmod.c b/flight/Modules/System/systemmod.c index bd4382500..e85ce85c6 100644 --- a/flight/Modules/System/systemmod.c +++ b/flight/Modules/System/systemmod.c @@ -43,6 +43,7 @@ #include "sanitycheck.h" #include "objectpersistence.h" #include "flightstatus.h" +#include "manualcontrolsettings.h" #include "systemstats.h" #include "systemsettings.h" #include "i2cstats.h" @@ -88,6 +89,7 @@ static bool mallocFailed; // Private functions static void objectUpdatedCb(UAVObjEvent * ev); +static void configurationUpdatedCb(UAVObjEvent * ev); static void updateStats(); static void updateSystemAlarms(); static void systemTask(void *parameters); @@ -168,14 +170,19 @@ static void systemTask(void *parameters) // Listen for SettingPersistance object updates, connect a callback function ObjectPersistenceConnectQueue(objectPersistenceQueue); + // Whenever the configuration changes, make sure it is safe to fly + SystemSettingsConnectCallback(configurationUpdatedCb); + ManualControlSettingsConnectCallback(configurationUpdatedCb); + TaskInfoConnectCallback(configurationUpdatedCb); + + // Run this initially to make sure the configuration is checked + configuration_check(); + // Main system loop while (1) { // Update the system statistics updateStats(); - // TODO: Make this only be called when configuration settings change - configuration_check(); - // Update the system alarms updateSystemAlarms(); #if defined(I2C_WDG_STATS_DIAGNOSTICS) @@ -307,6 +314,14 @@ static void objectUpdatedCb(UAVObjEvent * ev) } } +/** + * Called whenever a critical configuration component changes + */ +static void configurationUpdatedCb(UAVObjEvent * ev) +{ + configuration_check(); +} + /** * Called periodically to update the I2C statistics */ From 32bf63c4362d7109aa4c3911f5413c1416c8e17f Mon Sep 17 00:00:00 2001 From: James Cotton Date: Thu, 25 Oct 2012 22:51:14 -0500 Subject: [PATCH 09/30] Sanity Check: Perform the initial check then attach the callbacks to avoid a case where two threads do the same thing. --- flight/Modules/System/systemmod.c | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/flight/Modules/System/systemmod.c b/flight/Modules/System/systemmod.c index e85ce85c6..4a0be78ef 100644 --- a/flight/Modules/System/systemmod.c +++ b/flight/Modules/System/systemmod.c @@ -170,14 +170,14 @@ static void systemTask(void *parameters) // Listen for SettingPersistance object updates, connect a callback function ObjectPersistenceConnectQueue(objectPersistenceQueue); + // Run this initially to make sure the configuration is checked + configuration_check(); + // Whenever the configuration changes, make sure it is safe to fly SystemSettingsConnectCallback(configurationUpdatedCb); ManualControlSettingsConnectCallback(configurationUpdatedCb); TaskInfoConnectCallback(configurationUpdatedCb); - // Run this initially to make sure the configuration is checked - configuration_check(); - // Main system loop while (1) { // Update the system statistics From 93349e9a5666ac4c9d3a6f9a0f5add721d9e7ba9 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Thu, 25 Oct 2012 22:57:57 -0500 Subject: [PATCH 10/30] Sanity Check: uint32_t for loop indexes instead of int --- flight/Libraries/sanitycheck.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/flight/Libraries/sanitycheck.c b/flight/Libraries/sanitycheck.c index 87b1e8352..0c139c2ac 100644 --- a/flight/Libraries/sanitycheck.c +++ b/flight/Libraries/sanitycheck.c @@ -86,7 +86,7 @@ int32_t configuration_check() ManualControlSettingsFlightModeNumberGet(&num_modes); ManualControlSettingsFlightModePositionGet(modes); - for(int i = 0; i < num_modes; i++) { + for(uint32_t i = 0; i < num_modes; i++) { switch(modes[i]) { case MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_MANUAL: if (multirotor) @@ -179,7 +179,7 @@ static int32_t check_stabilization_settings(int index, bool multirotor) // For multirotors verify that nothing is set to "none" if (multirotor) { - for(int i = 0; i < NELEMENTS(modes); i++) { + for(uint32_t i = 0; i < NELEMENTS(modes); i++) { if (modes[i] == MANUALCONTROLSETTINGS_STABILIZATION1SETTINGS_NONE) return SYSTEMALARMS_ALARM_ERROR; } From 07a08c327c8fde91f9e01b5cd1a2e7e8c97209a2 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Thu, 25 Oct 2012 23:01:35 -0500 Subject: [PATCH 11/30] Sanity Check: Fix comment --- flight/Libraries/sanitycheck.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/flight/Libraries/sanitycheck.c b/flight/Libraries/sanitycheck.c index 0c139c2ac..50120343e 100644 --- a/flight/Libraries/sanitycheck.c +++ b/flight/Libraries/sanitycheck.c @@ -155,7 +155,7 @@ int32_t configuration_check() */ static int32_t check_stabilization_settings(int index, bool multirotor) { - // Make sure the modes are all similar + // Make sure the modes have identical sizes if (MANUALCONTROLSETTINGS_STABILIZATION1SETTINGS_NUMELEM != MANUALCONTROLSETTINGS_STABILIZATION2SETTINGS_NUMELEM || MANUALCONTROLSETTINGS_STABILIZATION1SETTINGS_NUMELEM != MANUALCONTROLSETTINGS_STABILIZATION3SETTINGS_NUMELEM) return SYSTEMALARMS_ALARM_ERROR; From 11630b7f7e4b33ff1545c2235f8a6c9a2f91cf2f Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 27 Oct 2012 13:43:41 -0500 Subject: [PATCH 12/30] SanityCheck: Directly query the task monitor --- flight/Libraries/inc/taskmonitor.h | 1 + flight/Libraries/sanitycheck.c | 14 +++++--------- flight/Libraries/taskmonitor.c | 10 ++++++++++ 3 files changed, 16 insertions(+), 9 deletions(-) diff --git a/flight/Libraries/inc/taskmonitor.h b/flight/Libraries/inc/taskmonitor.h index 112598f1b..6492cee06 100644 --- a/flight/Libraries/inc/taskmonitor.h +++ b/flight/Libraries/inc/taskmonitor.h @@ -33,6 +33,7 @@ int32_t TaskMonitorInitialize(void); int32_t TaskMonitorAdd(TaskInfoRunningElem task, xTaskHandle handle); int32_t TaskMonitorRemove(TaskInfoRunningElem task); +bool TaskMonitorQueryRunning(TaskInfoRunningElem task); void TaskMonitorUpdateAll(void); #endif // TASKMONITOR_H diff --git a/flight/Libraries/sanitycheck.c b/flight/Libraries/sanitycheck.c index 50120343e..d94d94cb2 100644 --- a/flight/Libraries/sanitycheck.c +++ b/flight/Libraries/sanitycheck.c @@ -27,9 +27,9 @@ */ #include "openpilot.h" +#include "taskmonitor.h" #include #include "sanitycheck.h" -#include "taskinfo.h" #include "manualcontrolsettings.h" #include "systemalarms.h" #include "systemsettings.h" @@ -75,10 +75,6 @@ int32_t configuration_check() multirotor = false; } - // Get the running modules - uint8_t running[TASKINFO_RUNNING_NUMELEM]; - TaskInfoRunningGet(running); - // For each available flight mode position sanity check the available // modes uint8_t num_modes; @@ -102,7 +98,7 @@ int32_t configuration_check() status = (status == SYSTEMALARMS_ALARM_OK) ? check_stabilization_settings(3, multirotor) : status; break; case MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_AUTOTUNE: - if (running[TASKINFO_RUNNING_AUTOTUNE] != TASKINFO_RUNNING_TRUE) + if (!TaskMonitorQueryRunning(TASKINFO_RUNNING_AUTOTUNE)) status = SYSTEMALARMS_ALARM_ERROR; break; case MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_ALTITUDEHOLD: @@ -110,7 +106,7 @@ int32_t configuration_check() status = SYSTEMALARMS_ALARM_ERROR; else { // Revo supports altitude hold - if(running[TASKINFO_RUNNING_ALTITUDEHOLD] != TASKINFO_RUNNING_TRUE) + if (!TaskMonitorQueryRunning(TASKINFO_RUNNING_ALTITUDEHOLD)) status = SYSTEMALARMS_ALARM_ERROR; } break; @@ -119,7 +115,7 @@ int32_t configuration_check() status = SYSTEMALARMS_ALARM_ERROR; else { // Revo supports altitude hold - if(running[TASKINFO_RUNNING_GUIDANCE] != TASKINFO_RUNNING_TRUE) + if (!TaskMonitorQueryRunning(TASKINFO_RUNNING_GUIDANCE)) status = SYSTEMALARMS_ALARM_ERROR; } break; @@ -128,7 +124,7 @@ int32_t configuration_check() status = SYSTEMALARMS_ALARM_ERROR; else { // Revo supports altitude hold - if(running[TASKINFO_RUNNING_GUIDANCE] != TASKINFO_RUNNING_TRUE) + if (!TaskMonitorQueryRunning(TASKINFO_RUNNING_GUIDANCE)) status = SYSTEMALARMS_ALARM_ERROR; } break; diff --git a/flight/Libraries/taskmonitor.c b/flight/Libraries/taskmonitor.c index 0ea4cbf52..6fc1c4dc3 100644 --- a/flight/Libraries/taskmonitor.c +++ b/flight/Libraries/taskmonitor.c @@ -89,6 +89,16 @@ int32_t TaskMonitorRemove(TaskInfoRunningElem task) } } +/** + * Query if a task is running + */ +bool TaskMonitorQueryRunning(TaskInfoRunningElem task) +{ + if (task < TASKINFO_RUNNING_NUMELEM && handles[task] != 0) + return true; + return false; +} + /** * Update the status of all tasks */ From 8864b545ae8e71271b2068464b7912455f17c8e0 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 27 Oct 2012 13:43:59 -0500 Subject: [PATCH 13/30] Revert "Sanity Checking: Regardless of DIAG_TASK always populate TaskInfo.Running" This reverts commit 0b6fa7fe6f13aa7c74ffc8c2f1382271865995e6. --- flight/Libraries/taskmonitor.c | 2 ++ flight/Modules/System/systemmod.c | 4 ++++ 2 files changed, 6 insertions(+) diff --git a/flight/Libraries/taskmonitor.c b/flight/Libraries/taskmonitor.c index 6fc1c4dc3..d8be06264 100644 --- a/flight/Libraries/taskmonitor.c +++ b/flight/Libraries/taskmonitor.c @@ -104,6 +104,7 @@ bool TaskMonitorQueryRunning(TaskInfoRunningElem task) */ void TaskMonitorUpdateAll(void) { +#if defined(DIAG_TASKS) TaskInfoData data; int n; @@ -154,4 +155,5 @@ void TaskMonitorUpdateAll(void) // Done xSemaphoreGiveRecursive(lock); +#endif } diff --git a/flight/Modules/System/systemmod.c b/flight/Modules/System/systemmod.c index 4a0be78ef..d6fa9aeb2 100644 --- a/flight/Modules/System/systemmod.c +++ b/flight/Modules/System/systemmod.c @@ -126,7 +126,9 @@ int32_t SystemModInitialize(void) SystemStatsInitialize(); FlightStatusInitialize(); ObjectPersistenceInitialize(); +#if defined(DIAG_TASKS) TaskInfoInitialize(); +#endif #if defined(I2C_WDG_STATS_DIAGNOSTICS) I2CStatsInitialize(); WatchdogStatusInitialize(); @@ -190,8 +192,10 @@ static void systemTask(void *parameters) updateWDGstats(); #endif +#if defined(DIAG_TASKS) // Update the task status object TaskMonitorUpdateAll(); +#endif // Flash the heartbeat LED #if defined(PIOS_LED_HEARTBEAT) From a5c743d7386b5e60b9b45ad54231aedbad2146c7 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 27 Oct 2012 13:47:31 -0500 Subject: [PATCH 14/30] Sanity Check: Cannot connect callback to TaskInfo now it isn't always used. --- flight/Modules/System/systemmod.c | 1 - 1 file changed, 1 deletion(-) diff --git a/flight/Modules/System/systemmod.c b/flight/Modules/System/systemmod.c index d6fa9aeb2..f477c6042 100644 --- a/flight/Modules/System/systemmod.c +++ b/flight/Modules/System/systemmod.c @@ -178,7 +178,6 @@ static void systemTask(void *parameters) // Whenever the configuration changes, make sure it is safe to fly SystemSettingsConnectCallback(configurationUpdatedCb); ManualControlSettingsConnectCallback(configurationUpdatedCb); - TaskInfoConnectCallback(configurationUpdatedCb); // Main system loop while (1) { From 9151e5cded51bbece0ffac9f3084e8546bcce30b Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sun, 28 Oct 2012 20:00:03 -0500 Subject: [PATCH 15/30] Sanity Check: Fix indentation --- flight/Libraries/sanitycheck.c | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/flight/Libraries/sanitycheck.c b/flight/Libraries/sanitycheck.c index d94d94cb2..aa6c294b9 100644 --- a/flight/Libraries/sanitycheck.c +++ b/flight/Libraries/sanitycheck.c @@ -89,13 +89,13 @@ int32_t configuration_check() status = SYSTEMALARMS_ALARM_ERROR; break; case MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_STABILIZED1: - status = (status == SYSTEMALARMS_ALARM_OK) ? check_stabilization_settings(1, multirotor) : status; + status = (status == SYSTEMALARMS_ALARM_OK) ? check_stabilization_settings(1, multirotor) : status; break; case MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_STABILIZED2: - status = (status == SYSTEMALARMS_ALARM_OK) ? check_stabilization_settings(2, multirotor) : status; + status = (status == SYSTEMALARMS_ALARM_OK) ? check_stabilization_settings(2, multirotor) : status; break; case MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_STABILIZED3: - status = (status == SYSTEMALARMS_ALARM_OK) ? check_stabilization_settings(3, multirotor) : status; + status = (status == SYSTEMALARMS_ALARM_OK) ? check_stabilization_settings(3, multirotor) : status; break; case MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_AUTOTUNE: if (!TaskMonitorQueryRunning(TASKINFO_RUNNING_AUTOTUNE)) From d1447ca3f8140fc3b78afbb5649dcf650f8eade3 Mon Sep 17 00:00:00 2001 From: Corvus Corax Date: Sun, 11 Nov 2012 17:23:07 +0100 Subject: [PATCH 16/30] Rise Botfault error whenever hwsettings has been changed but no reboot took place yet --- flight/Modules/System/systemmod.c | 11 +++++++++++ 1 file changed, 11 insertions(+) diff --git a/flight/Modules/System/systemmod.c b/flight/Modules/System/systemmod.c index f477c6042..8f5193c14 100644 --- a/flight/Modules/System/systemmod.c +++ b/flight/Modules/System/systemmod.c @@ -50,6 +50,7 @@ #include "taskinfo.h" #include "watchdogstatus.h" #include "taskmonitor.h" +#include "hwsettings.h" //#define DEBUG_THIS_FILE @@ -90,6 +91,7 @@ static bool mallocFailed; // Private functions static void objectUpdatedCb(UAVObjEvent * ev); static void configurationUpdatedCb(UAVObjEvent * ev); +static void hwSettingsUpdatedCb(UAVObjEvent * ev); static void updateStats(); static void updateSystemAlarms(); static void systemTask(void *parameters); @@ -178,6 +180,7 @@ static void systemTask(void *parameters) // Whenever the configuration changes, make sure it is safe to fly SystemSettingsConnectCallback(configurationUpdatedCb); ManualControlSettingsConnectCallback(configurationUpdatedCb); + HwSettingsConnectCallback(hwSettingsUpdatedCb); // Main system loop while (1) { @@ -325,6 +328,14 @@ static void configurationUpdatedCb(UAVObjEvent * ev) configuration_check(); } +/** + * Called whenever hardware settings changed + */ +static void hwSettingsUpdatedCb(UAVObjEvent * ev) +{ + AlarmsSet(SYSTEMALARMS_ALARM_BOOTFAULT,SYSTEMALARMS_ALARM_ERROR); +} + /** * Called periodically to update the I2C statistics */ From 112a3fe7e5e622033bc541c868e44f4b77a642e7 Mon Sep 17 00:00:00 2001 From: Corvus Corax Date: Sun, 11 Nov 2012 17:39:37 +0100 Subject: [PATCH 17/30] do not do configuration check on SimPosix architecture, its not ported yet --- flight/Modules/System/systemmod.c | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/flight/Modules/System/systemmod.c b/flight/Modules/System/systemmod.c index 8f5193c14..e1a6120a5 100644 --- a/flight/Modules/System/systemmod.c +++ b/flight/Modules/System/systemmod.c @@ -174,8 +174,11 @@ static void systemTask(void *parameters) // Listen for SettingPersistance object updates, connect a callback function ObjectPersistenceConnectQueue(objectPersistenceQueue); +#if defined(ARCH_POSIX) || defined(ARCH_WIN32) +#else // Run this initially to make sure the configuration is checked configuration_check(); +#endif // Whenever the configuration changes, make sure it is safe to fly SystemSettingsConnectCallback(configurationUpdatedCb); @@ -325,7 +328,12 @@ static void objectUpdatedCb(UAVObjEvent * ev) */ static void configurationUpdatedCb(UAVObjEvent * ev) { +#if defined(ARCH_POSIX) || defined(ARCH_WIN32) + // configuration_check requires board_info blobs and other structures + // that are not present on all architectures +#else configuration_check(); +#endif } /** From ec5f9d232fce5543477817f3d4d64ece9a034a6a Mon Sep 17 00:00:00 2001 From: Corvus Corax Date: Sun, 11 Nov 2012 18:05:46 +0100 Subject: [PATCH 18/30] Revert "do not do configuration check on SimPosix architecture, its not ported yet" This reverts commit 112a3fe7e5e622033bc541c868e44f4b77a642e7. --- flight/Modules/System/systemmod.c | 8 -------- 1 file changed, 8 deletions(-) diff --git a/flight/Modules/System/systemmod.c b/flight/Modules/System/systemmod.c index e1a6120a5..8f5193c14 100644 --- a/flight/Modules/System/systemmod.c +++ b/flight/Modules/System/systemmod.c @@ -174,11 +174,8 @@ static void systemTask(void *parameters) // Listen for SettingPersistance object updates, connect a callback function ObjectPersistenceConnectQueue(objectPersistenceQueue); -#if defined(ARCH_POSIX) || defined(ARCH_WIN32) -#else // Run this initially to make sure the configuration is checked configuration_check(); -#endif // Whenever the configuration changes, make sure it is safe to fly SystemSettingsConnectCallback(configurationUpdatedCb); @@ -328,12 +325,7 @@ static void objectUpdatedCb(UAVObjEvent * ev) */ static void configurationUpdatedCb(UAVObjEvent * ev) { -#if defined(ARCH_POSIX) || defined(ARCH_WIN32) - // configuration_check requires board_info blobs and other structures - // that are not present on all architectures -#else configuration_check(); -#endif } /** From 40381d98aede0acb796b0759fbe6700abb0c1305 Mon Sep 17 00:00:00 2001 From: Corvus Corax Date: Sun, 11 Nov 2012 18:22:01 +0100 Subject: [PATCH 19/30] compile sanitycheck into simposix --- flight/SimPosix/Makefile | 1 + 1 file changed, 1 insertion(+) diff --git a/flight/SimPosix/Makefile b/flight/SimPosix/Makefile index 7244068a0..5253b7262 100644 --- a/flight/SimPosix/Makefile +++ b/flight/SimPosix/Makefile @@ -134,6 +134,7 @@ SRC += $(FLIGHTLIB)/fifo_buffer.c SRC += $(FLIGHTLIB)/WorldMagModel.c SRC += $(FLIGHTLIB)/insgps13state.c SRC += $(FLIGHTLIB)/taskmonitor.c +SRC += $(FLIGHTLIB)/sanitycheck.c SRC += $(MATHLIB)/sin_lookup.c SRC += $(MATHLIB)/pid.c From 35509ee977411c112ea82f149fabe051419c91c5 Mon Sep 17 00:00:00 2001 From: Corvus Corax Date: Mon, 12 Nov 2012 10:03:30 +0100 Subject: [PATCH 20/30] moved sanitycheck from system to manualcontrol to not break OSD and PipX targets Conflicts: flight/Modules/ManualControl/manualcontrol.c --- flight/Modules/ManualControl/manualcontrol.c | 23 ++++++++++++++++++++ flight/Modules/System/systemmod.c | 16 -------------- 2 files changed, 23 insertions(+), 16 deletions(-) diff --git a/flight/Modules/ManualControl/manualcontrol.c b/flight/Modules/ManualControl/manualcontrol.c index 2c7a68575..f696162f1 100644 --- a/flight/Modules/ManualControl/manualcontrol.c +++ b/flight/Modules/ManualControl/manualcontrol.c @@ -34,6 +34,7 @@ */ #include "openpilot.h" +#include "sanitycheck.h" #include "manualcontrol.h" #include "manualcontrolsettings.h" #include "stabilizationsettings.h" @@ -47,6 +48,7 @@ #include "altitudeholddesired.h" #include "positionactual.h" #include "baroaltitude.h" +#include "systemsettings.h" #if defined(PIOS_INCLUDE_USB_RCTX) #include "pios_usb_rctx.h" @@ -89,6 +91,7 @@ static void altitudeHoldDesired(ManualControlCommandData * cmd); static void processFlightMode(ManualControlSettingsData * settings, float flightMode); static void processArm(ManualControlCommandData * cmd, ManualControlSettingsData * settings); static void setArmedIfChanged(uint8_t val); +static void configurationUpdatedCb(UAVObjEvent * ev); static void manualControlTask(void *parameters); static float scaleChannel(int16_t value, int16_t max, int16_t min, int16_t neutral); @@ -163,6 +166,15 @@ static void manualControlTask(void *parameters) AccessoryDesiredCreateInstance(); AccessoryDesiredCreateInstance(); + // Run this initially to make sure the configuration is checked + configuration_check(); + + // Whenever the configuration changes, make sure it is safe to fly + SystemSettingsConnectCallback(configurationUpdatedCb); + ManualControlSettingsConnectCallback(configurationUpdatedCb); + + // Whenever the configuration changes, make sure it is safe to fly + // Make sure unarmed on power up ManualControlCommandGet(&cmd); FlightStatusGet(&flightStatus); @@ -924,6 +936,17 @@ static void applyDeadband(float *value, float deadband) *value += deadband; } + +/** + * Called whenever a critical configuration component changes + */ +static void configurationUpdatedCb(UAVObjEvent * ev) +{ + configuration_check(); +} + + + /** * @} * @} diff --git a/flight/Modules/System/systemmod.c b/flight/Modules/System/systemmod.c index 8f5193c14..638af30ed 100644 --- a/flight/Modules/System/systemmod.c +++ b/flight/Modules/System/systemmod.c @@ -40,10 +40,8 @@ #include "openpilot.h" #include "systemmod.h" -#include "sanitycheck.h" #include "objectpersistence.h" #include "flightstatus.h" -#include "manualcontrolsettings.h" #include "systemstats.h" #include "systemsettings.h" #include "i2cstats.h" @@ -90,7 +88,6 @@ static bool mallocFailed; // Private functions static void objectUpdatedCb(UAVObjEvent * ev); -static void configurationUpdatedCb(UAVObjEvent * ev); static void hwSettingsUpdatedCb(UAVObjEvent * ev); static void updateStats(); static void updateSystemAlarms(); @@ -174,12 +171,7 @@ static void systemTask(void *parameters) // Listen for SettingPersistance object updates, connect a callback function ObjectPersistenceConnectQueue(objectPersistenceQueue); - // Run this initially to make sure the configuration is checked - configuration_check(); - // Whenever the configuration changes, make sure it is safe to fly - SystemSettingsConnectCallback(configurationUpdatedCb); - ManualControlSettingsConnectCallback(configurationUpdatedCb); HwSettingsConnectCallback(hwSettingsUpdatedCb); // Main system loop @@ -320,14 +312,6 @@ static void objectUpdatedCb(UAVObjEvent * ev) } } -/** - * Called whenever a critical configuration component changes - */ -static void configurationUpdatedCb(UAVObjEvent * ev) -{ - configuration_check(); -} - /** * Called whenever hardware settings changed */ From 69a2691bc2817457bbe01d153a44a878d6f58b56 Mon Sep 17 00:00:00 2001 From: Stacey Sheldon Date: Tue, 27 Nov 2012 01:23:44 -0500 Subject: [PATCH 21/30] rename: move board-specific dirs into flight/targets Conflicts: flight/targets/Bootloaders/Revolution/Makefile flight/targets/CopterControl/Makefile --- Makefile | 12 +- flight/OpenPilot/System/pios_usb_board_data.c | 120 ------------------ .../Bootloaders/BootloaderUpdater/Makefile | 14 +- .../BootloaderUpdater/inc/pios_config.h | 0 .../Bootloaders/BootloaderUpdater/main.c | 0 .../BootloaderUpdater/pios_board.c | 0 .../Bootloaders/CopterControl/Makefile | 14 +- .../Bootloaders/CopterControl/inc/common.h | 0 .../Bootloaders/CopterControl/inc/op_dfu.h | 0 .../CopterControl/inc/pios_config.h | 0 .../CopterControl/inc/pios_usb_board_data.h | 0 .../Bootloaders/CopterControl/main.c | 0 .../Bootloaders/CopterControl/op_dfu.c | 0 .../Bootloaders/CopterControl/pios_board.c | 0 .../CopterControl/pios_usb_board_data.c | 0 flight/{ => targets}/Bootloaders/OSD/Makefile | 8 +- .../Bootloaders/OSD/inc/common.h | 0 .../Bootloaders/OSD/inc/op_dfu.h | 0 .../Bootloaders/OSD/inc/pios_config.h | 0 .../Bootloaders/OSD/inc/pios_usb_board_data.h | 0 flight/{ => targets}/Bootloaders/OSD/main.c | 0 flight/{ => targets}/Bootloaders/OSD/op_dfu.c | 0 .../Bootloaders/OSD/pios_board.c | 0 .../Bootloaders/OSD/pios_usb_board_data.c | 0 .../Bootloaders/PipXtreme/Makefile | 14 +- .../Bootloaders/PipXtreme/inc/common.h | 0 .../Bootloaders/PipXtreme/inc/op_dfu.h | 0 .../Bootloaders/PipXtreme/inc/pios_config.h | 0 .../PipXtreme/inc/pios_usb_board_data.h | 0 .../Bootloaders/PipXtreme/main.c | 0 .../Bootloaders/PipXtreme/op_dfu.c | 0 .../Bootloaders/PipXtreme/pios_board.c | 0 .../PipXtreme/pios_usb_board_data.c | 0 .../Bootloaders/RevoMini/Makefile | 8 +- .../Bootloaders/RevoMini/inc/common.h | 0 .../Bootloaders/RevoMini/inc/op_dfu.h | 0 .../Bootloaders/RevoMini/inc/pios_config.h | 0 .../RevoMini/inc/pios_usb_board_data.h | 0 .../{ => targets}/Bootloaders/RevoMini/main.c | 0 .../Bootloaders/RevoMini/op_dfu.c | 0 .../Bootloaders/RevoMini/pios_board.c | 0 .../RevoMini/pios_usb_board_data.c | 0 .../Bootloaders/Revolution/Makefile | 8 +- .../Bootloaders/Revolution/inc/common.h | 0 .../Bootloaders/Revolution/inc/op_dfu.h | 0 .../Bootloaders/Revolution/inc/pios_config.h | 0 .../Revolution/inc/pios_usb_board_data.h | 0 .../Bootloaders/Revolution/main.c | 0 .../Bootloaders/Revolution/op_dfu.c | 0 .../Bootloaders/Revolution/pios_board.c | 0 .../Revolution/pios_usb_board_data.c | 0 flight/{ => targets}/CopterControl/Makefile | 16 +-- .../CopterControl/System/alarms.c | 0 .../CopterControl/System/coptercontrol.c | 0 .../CopterControl/System/inc/FreeRTOSConfig.h | 0 .../CopterControl/System/inc/alarms.h | 0 .../CopterControl/System/inc/op_config.h | 0 .../CopterControl/System/inc/openpilot.h | 0 .../System/inc/pios_board_posix.h | 0 .../CopterControl/System/inc/pios_config.h | 0 .../System/inc/pios_config_posix.h | 0 .../System/inc/pios_usb_board_data.h | 0 .../CopterControl/System/pios_board.c | 0 .../CopterControl/System/pios_board_posix.c | 0 .../System/pios_usb_board_data.c | 0 flight/{ => targets}/EntireFlash/Makefile | 2 +- flight/{ => targets}/OSD/Makefile | 14 +- flight/{ => targets}/OSD/System/alarms.c | 0 .../OSD/System/cm3_fault_handlers.c | 0 flight/{ => targets}/OSD/System/dcc_stdio.c | 0 .../OSD/System/font_outlined8x14.c | 0 .../OSD/System/font_outlined8x14.h | 0 .../OSD/System/font_outlined8x8.c | 0 .../OSD/System/font_outlined8x8.h | 0 flight/{ => targets}/OSD/System/fonts.c | 0 flight/{ => targets}/OSD/System/fonts.h | 0 .../OSD/System/inc/FreeRTOSConfig.h | 0 flight/{ => targets}/OSD/System/inc/alarms.h | 0 .../{ => targets}/OSD/System/inc/dcc_stdio.h | 0 .../{ => targets}/OSD/System/inc/font12x18.h | 0 .../{ => targets}/OSD/System/inc/font8x10.h | 0 .../{ => targets}/OSD/System/inc/op_config.h | 0 .../{ => targets}/OSD/System/inc/openpilot.h | 0 .../OSD/System/inc/pios_config.h | 0 .../OSD/System/inc/pios_usb_board_data.h | 0 flight/{ => targets}/OSD/System/inc/splash.h | 0 flight/{ => targets}/OSD/System/osd.c | 0 flight/{ => targets}/OSD/System/pios_board.c | 0 .../OSD/System/pios_usb_board_data.c | 0 flight/{ => targets}/PipXtreme/Makefile | 12 +- .../{ => targets}/PipXtreme/System/alarms.c | 0 .../PipXtreme/System/inc/FreeRTOSConfig.h | 0 .../PipXtreme/System/inc/alarms.h | 0 .../PipXtreme/System/inc/op_config.h | 0 .../PipXtreme/System/inc/openpilot.h | 0 .../PipXtreme/System/inc/pios_board_posix.h | 0 .../PipXtreme/System/inc/pios_config.h | 0 .../PipXtreme/System/inc/pios_config_posix.h | 0 .../System/inc/pios_usb_board_data.h | 0 .../PipXtreme/System/pios_board.c | 0 .../PipXtreme/System/pios_board_posix.c | 0 .../PipXtreme/System/pios_usb_board_data.c | 0 .../PipXtreme/System/pipxtreme.c | 0 flight/{ => targets}/RevoMini/Makefile | 20 +-- flight/{ => targets}/RevoMini/Makefile.osx | 0 flight/{ => targets}/RevoMini/System/alarms.c | 0 .../RevoMini/System/cm3_fault_handlers.c | 0 .../{ => targets}/RevoMini/System/dcc_stdio.c | 0 .../RevoMini/System/inc/FreeRTOSConfig.h | 0 .../RevoMini/System/inc/alarms.h | 0 .../RevoMini/System/inc/dcc_stdio.h | 0 .../RevoMini/System/inc/op_config.h | 0 .../RevoMini/System/inc/openpilot.h | 0 .../RevoMini/System/inc/pios_board_sim.h | 0 .../RevoMini/System/inc/pios_config.h | 0 .../RevoMini/System/inc/pios_config_sim.h | 0 .../RevoMini/System/inc/pios_usb_board_data.h | 0 .../RevoMini/System/pios_board.c | 0 .../RevoMini/System/pios_board_sim.c | 0 .../RevoMini/System/pios_usb_board_data.c | 0 .../RevoMini/System/revolution.c | 0 flight/{ => targets}/RevoMini/UAVObjects.inc | 0 flight/{ => targets}/Revolution/Makefile | 24 ++-- flight/{ => targets}/Revolution/Makefile.osx | 0 .../{ => targets}/Revolution/System/alarms.c | 0 .../Revolution/System/cm3_fault_handlers.c | 0 .../Revolution/System/dcc_stdio.c | 0 .../Revolution/System/inc/FreeRTOSConfig.h | 0 .../Revolution/System/inc/alarms.h | 0 .../Revolution/System/inc/dcc_stdio.h | 0 .../Revolution/System/inc/op_config.h | 0 .../Revolution/System/inc/openpilot.h | 0 .../Revolution/System/inc/pios_board_sim.h | 0 .../Revolution/System/inc/pios_config.h | 0 .../Revolution/System/inc/pios_config_sim.h | 0 .../System/inc/pios_usb_board_data.h | 0 .../Revolution/System/pios_board.c | 0 .../Revolution/System/pios_board_sim.c | 0 .../Revolution/System/pios_usb_board_data.c | 0 .../Revolution/System/revolution.c | 0 .../{ => targets}/Revolution/UAVObjects.inc | 0 flight/{ => targets}/SimPosix/Makefile | 20 +-- flight/{ => targets}/SimPosix/System/alarms.c | 0 .../SimPosix/System/inc/FreeRTOSConfig.h | 0 .../SimPosix/System/inc/alarms.h | 0 .../SimPosix/System/inc/dcc_stdio.h | 0 .../SimPosix/System/inc/op_config.h | 0 .../SimPosix/System/inc/openpilot.h | 0 .../SimPosix/System/inc/pios_config.h | 0 .../SimPosix/System/pios_board.c | 0 .../{ => targets}/SimPosix/System/simposix.c | 0 flight/{ => targets}/SimPosix/UAVObjects.inc | 0 .../coptercontrol/board_hw_defs.c | 0 .../board_hw_defs/osd/board_hw_defs.c | 0 .../board_hw_defs/pipxtreme/board_hw_defs.c | 0 .../board_hw_defs/revolution/board_hw_defs.c | 0 .../board_hw_defs/revomini/board_hw_defs.c | 0 .../board_hw_defs/simposix/board_hw_defs.c | 0 158 files changed, 83 insertions(+), 223 deletions(-) delete mode 100644 flight/OpenPilot/System/pios_usb_board_data.c rename flight/{ => targets}/Bootloaders/BootloaderUpdater/Makefile (97%) rename flight/{ => targets}/Bootloaders/BootloaderUpdater/inc/pios_config.h (100%) rename flight/{ => targets}/Bootloaders/BootloaderUpdater/main.c (100%) rename flight/{ => targets}/Bootloaders/BootloaderUpdater/pios_board.c (100%) rename flight/{ => targets}/Bootloaders/CopterControl/Makefile (98%) rename flight/{ => targets}/Bootloaders/CopterControl/inc/common.h (100%) rename flight/{ => targets}/Bootloaders/CopterControl/inc/op_dfu.h (100%) rename flight/{ => targets}/Bootloaders/CopterControl/inc/pios_config.h (100%) rename flight/{ => targets}/Bootloaders/CopterControl/inc/pios_usb_board_data.h (100%) rename flight/{ => targets}/Bootloaders/CopterControl/main.c (100%) rename flight/{ => targets}/Bootloaders/CopterControl/op_dfu.c (100%) rename flight/{ => targets}/Bootloaders/CopterControl/pios_board.c (100%) rename flight/{ => targets}/Bootloaders/CopterControl/pios_usb_board_data.c (100%) rename flight/{ => targets}/Bootloaders/OSD/Makefile (98%) rename flight/{ => targets}/Bootloaders/OSD/inc/common.h (100%) rename flight/{ => targets}/Bootloaders/OSD/inc/op_dfu.h (100%) rename flight/{ => targets}/Bootloaders/OSD/inc/pios_config.h (100%) rename flight/{ => targets}/Bootloaders/OSD/inc/pios_usb_board_data.h (100%) rename flight/{ => targets}/Bootloaders/OSD/main.c (100%) rename flight/{ => targets}/Bootloaders/OSD/op_dfu.c (100%) rename flight/{ => targets}/Bootloaders/OSD/pios_board.c (100%) rename flight/{ => targets}/Bootloaders/OSD/pios_usb_board_data.c (100%) rename flight/{ => targets}/Bootloaders/PipXtreme/Makefile (98%) rename flight/{ => targets}/Bootloaders/PipXtreme/inc/common.h (100%) rename flight/{ => targets}/Bootloaders/PipXtreme/inc/op_dfu.h (100%) rename flight/{ => targets}/Bootloaders/PipXtreme/inc/pios_config.h (100%) rename flight/{ => targets}/Bootloaders/PipXtreme/inc/pios_usb_board_data.h (100%) rename flight/{ => targets}/Bootloaders/PipXtreme/main.c (100%) rename flight/{ => targets}/Bootloaders/PipXtreme/op_dfu.c (100%) rename flight/{ => targets}/Bootloaders/PipXtreme/pios_board.c (100%) rename flight/{ => targets}/Bootloaders/PipXtreme/pios_usb_board_data.c (100%) rename flight/{ => targets}/Bootloaders/RevoMini/Makefile (98%) rename flight/{ => targets}/Bootloaders/RevoMini/inc/common.h (100%) rename flight/{ => targets}/Bootloaders/RevoMini/inc/op_dfu.h (100%) rename flight/{ => targets}/Bootloaders/RevoMini/inc/pios_config.h (100%) rename flight/{ => targets}/Bootloaders/RevoMini/inc/pios_usb_board_data.h (100%) rename flight/{ => targets}/Bootloaders/RevoMini/main.c (100%) rename flight/{ => targets}/Bootloaders/RevoMini/op_dfu.c (100%) rename flight/{ => targets}/Bootloaders/RevoMini/pios_board.c (100%) rename flight/{ => targets}/Bootloaders/RevoMini/pios_usb_board_data.c (100%) rename flight/{ => targets}/Bootloaders/Revolution/Makefile (98%) rename flight/{ => targets}/Bootloaders/Revolution/inc/common.h (100%) rename flight/{ => targets}/Bootloaders/Revolution/inc/op_dfu.h (100%) rename flight/{ => targets}/Bootloaders/Revolution/inc/pios_config.h (100%) rename flight/{ => targets}/Bootloaders/Revolution/inc/pios_usb_board_data.h (100%) rename flight/{ => targets}/Bootloaders/Revolution/main.c (100%) rename flight/{ => targets}/Bootloaders/Revolution/op_dfu.c (100%) rename flight/{ => targets}/Bootloaders/Revolution/pios_board.c (100%) rename flight/{ => targets}/Bootloaders/Revolution/pios_usb_board_data.c (100%) rename flight/{ => targets}/CopterControl/Makefile (98%) rename flight/{ => targets}/CopterControl/System/alarms.c (100%) rename flight/{ => targets}/CopterControl/System/coptercontrol.c (100%) rename flight/{ => targets}/CopterControl/System/inc/FreeRTOSConfig.h (100%) rename flight/{ => targets}/CopterControl/System/inc/alarms.h (100%) rename flight/{ => targets}/CopterControl/System/inc/op_config.h (100%) rename flight/{ => targets}/CopterControl/System/inc/openpilot.h (100%) rename flight/{ => targets}/CopterControl/System/inc/pios_board_posix.h (100%) rename flight/{ => targets}/CopterControl/System/inc/pios_config.h (100%) rename flight/{ => targets}/CopterControl/System/inc/pios_config_posix.h (100%) rename flight/{ => targets}/CopterControl/System/inc/pios_usb_board_data.h (100%) rename flight/{ => targets}/CopterControl/System/pios_board.c (100%) rename flight/{ => targets}/CopterControl/System/pios_board_posix.c (100%) rename flight/{ => targets}/CopterControl/System/pios_usb_board_data.c (100%) rename flight/{ => targets}/EntireFlash/Makefile (98%) rename flight/{ => targets}/OSD/Makefile (98%) rename flight/{ => targets}/OSD/System/alarms.c (100%) rename flight/{ => targets}/OSD/System/cm3_fault_handlers.c (100%) rename flight/{ => targets}/OSD/System/dcc_stdio.c (100%) rename flight/{ => targets}/OSD/System/font_outlined8x14.c (100%) rename flight/{ => targets}/OSD/System/font_outlined8x14.h (100%) rename flight/{ => targets}/OSD/System/font_outlined8x8.c (100%) rename flight/{ => targets}/OSD/System/font_outlined8x8.h (100%) rename flight/{ => targets}/OSD/System/fonts.c (100%) rename flight/{ => targets}/OSD/System/fonts.h (100%) rename flight/{ => targets}/OSD/System/inc/FreeRTOSConfig.h (100%) rename flight/{ => targets}/OSD/System/inc/alarms.h (100%) rename flight/{ => targets}/OSD/System/inc/dcc_stdio.h (100%) rename flight/{ => targets}/OSD/System/inc/font12x18.h (100%) rename flight/{ => targets}/OSD/System/inc/font8x10.h (100%) rename flight/{ => targets}/OSD/System/inc/op_config.h (100%) rename flight/{ => targets}/OSD/System/inc/openpilot.h (100%) rename flight/{ => targets}/OSD/System/inc/pios_config.h (100%) rename flight/{ => targets}/OSD/System/inc/pios_usb_board_data.h (100%) rename flight/{ => targets}/OSD/System/inc/splash.h (100%) rename flight/{ => targets}/OSD/System/osd.c (100%) rename flight/{ => targets}/OSD/System/pios_board.c (100%) rename flight/{ => targets}/OSD/System/pios_usb_board_data.c (100%) rename flight/{ => targets}/PipXtreme/Makefile (99%) rename flight/{ => targets}/PipXtreme/System/alarms.c (100%) rename flight/{ => targets}/PipXtreme/System/inc/FreeRTOSConfig.h (100%) rename flight/{ => targets}/PipXtreme/System/inc/alarms.h (100%) rename flight/{ => targets}/PipXtreme/System/inc/op_config.h (100%) rename flight/{ => targets}/PipXtreme/System/inc/openpilot.h (100%) rename flight/{ => targets}/PipXtreme/System/inc/pios_board_posix.h (100%) rename flight/{ => targets}/PipXtreme/System/inc/pios_config.h (100%) rename flight/{ => targets}/PipXtreme/System/inc/pios_config_posix.h (100%) rename flight/{ => targets}/PipXtreme/System/inc/pios_usb_board_data.h (100%) rename flight/{ => targets}/PipXtreme/System/pios_board.c (100%) rename flight/{ => targets}/PipXtreme/System/pios_board_posix.c (100%) rename flight/{ => targets}/PipXtreme/System/pios_usb_board_data.c (100%) rename flight/{ => targets}/PipXtreme/System/pipxtreme.c (100%) rename flight/{ => targets}/RevoMini/Makefile (98%) rename flight/{ => targets}/RevoMini/Makefile.osx (100%) rename flight/{ => targets}/RevoMini/System/alarms.c (100%) rename flight/{ => targets}/RevoMini/System/cm3_fault_handlers.c (100%) rename flight/{ => targets}/RevoMini/System/dcc_stdio.c (100%) rename flight/{ => targets}/RevoMini/System/inc/FreeRTOSConfig.h (100%) rename flight/{ => targets}/RevoMini/System/inc/alarms.h (100%) rename flight/{ => targets}/RevoMini/System/inc/dcc_stdio.h (100%) rename flight/{ => targets}/RevoMini/System/inc/op_config.h (100%) rename flight/{ => targets}/RevoMini/System/inc/openpilot.h (100%) rename flight/{ => targets}/RevoMini/System/inc/pios_board_sim.h (100%) rename flight/{ => targets}/RevoMini/System/inc/pios_config.h (100%) rename flight/{ => targets}/RevoMini/System/inc/pios_config_sim.h (100%) rename flight/{ => targets}/RevoMini/System/inc/pios_usb_board_data.h (100%) rename flight/{ => targets}/RevoMini/System/pios_board.c (100%) rename flight/{ => targets}/RevoMini/System/pios_board_sim.c (100%) rename flight/{ => targets}/RevoMini/System/pios_usb_board_data.c (100%) rename flight/{ => targets}/RevoMini/System/revolution.c (100%) rename flight/{ => targets}/RevoMini/UAVObjects.inc (100%) rename flight/{ => targets}/Revolution/Makefile (97%) rename flight/{ => targets}/Revolution/Makefile.osx (100%) rename flight/{ => targets}/Revolution/System/alarms.c (100%) rename flight/{ => targets}/Revolution/System/cm3_fault_handlers.c (100%) rename flight/{ => targets}/Revolution/System/dcc_stdio.c (100%) rename flight/{ => targets}/Revolution/System/inc/FreeRTOSConfig.h (100%) rename flight/{ => targets}/Revolution/System/inc/alarms.h (100%) rename flight/{ => targets}/Revolution/System/inc/dcc_stdio.h (100%) rename flight/{ => targets}/Revolution/System/inc/op_config.h (100%) rename flight/{ => targets}/Revolution/System/inc/openpilot.h (100%) rename flight/{ => targets}/Revolution/System/inc/pios_board_sim.h (100%) rename flight/{ => targets}/Revolution/System/inc/pios_config.h (100%) rename flight/{ => targets}/Revolution/System/inc/pios_config_sim.h (100%) rename flight/{ => targets}/Revolution/System/inc/pios_usb_board_data.h (100%) rename flight/{ => targets}/Revolution/System/pios_board.c (100%) rename flight/{ => targets}/Revolution/System/pios_board_sim.c (100%) rename flight/{ => targets}/Revolution/System/pios_usb_board_data.c (100%) rename flight/{ => targets}/Revolution/System/revolution.c (100%) rename flight/{ => targets}/Revolution/UAVObjects.inc (100%) rename flight/{ => targets}/SimPosix/Makefile (98%) rename flight/{ => targets}/SimPosix/System/alarms.c (100%) rename flight/{ => targets}/SimPosix/System/inc/FreeRTOSConfig.h (100%) rename flight/{ => targets}/SimPosix/System/inc/alarms.h (100%) rename flight/{ => targets}/SimPosix/System/inc/dcc_stdio.h (100%) rename flight/{ => targets}/SimPosix/System/inc/op_config.h (100%) rename flight/{ => targets}/SimPosix/System/inc/openpilot.h (100%) rename flight/{ => targets}/SimPosix/System/inc/pios_config.h (100%) rename flight/{ => targets}/SimPosix/System/pios_board.c (100%) rename flight/{ => targets}/SimPosix/System/simposix.c (100%) rename flight/{ => targets}/SimPosix/UAVObjects.inc (100%) rename flight/{ => targets}/board_hw_defs/coptercontrol/board_hw_defs.c (100%) rename flight/{ => targets}/board_hw_defs/osd/board_hw_defs.c (100%) rename flight/{ => targets}/board_hw_defs/pipxtreme/board_hw_defs.c (100%) rename flight/{ => targets}/board_hw_defs/revolution/board_hw_defs.c (100%) rename flight/{ => targets}/board_hw_defs/revomini/board_hw_defs.c (100%) rename flight/{ => targets}/board_hw_defs/simposix/board_hw_defs.c (100%) diff --git a/Makefile b/Makefile index cd826704a..ee03ff066 100644 --- a/Makefile +++ b/Makefile @@ -737,7 +737,7 @@ fw_$(1): fw_$(1)_opfw fw_$(1)_%: uavobjects_flight $(V1) mkdir -p $(BUILD_DIR)/fw_$(1)/dep - $(V1) cd $(ROOT_DIR)/flight/$(2) && \ + $(V1) cd $(ROOT_DIR)/flight/targets/$(2) && \ $$(MAKE) -r --no-print-directory \ BOARD_NAME=$(1) \ BOARD_SHORT_NAME=$(3) \ @@ -762,7 +762,7 @@ bl_$(1)_bino: bl_$(1)_bin bl_$(1)_%: $(V1) mkdir -p $(BUILD_DIR)/bl_$(1)/dep - $(V1) cd $(ROOT_DIR)/flight/Bootloaders/$(2) && \ + $(V1) cd $(ROOT_DIR)/flight/targets/Bootloaders/$(2) && \ $$(MAKE) -r --no-print-directory \ BOARD_NAME=$(1) \ BOARD_SHORT_NAME=$(3) \ @@ -798,7 +798,7 @@ bu_$(1): bu_$(1)_opfw bu_$(1)_%: bl_$(1)_bino $(V1) mkdir -p $(BUILD_DIR)/bu_$(1)/dep - $(V1) cd $(ROOT_DIR)/flight/Bootloaders/BootloaderUpdater && \ + $(V1) cd $(ROOT_DIR)/flight/targets/Bootloaders/BootloaderUpdater && \ $$(MAKE) -r --no-print-directory \ BOARD_NAME=$(1) \ BOARD_SHORT_NAME=$(3) \ @@ -820,7 +820,7 @@ ef_$(1): ef_$(1)_bin ef_$(1)_%: bl_$(1)_bin fw_$(1)_opfw $(V1) mkdir -p $(BUILD_DIR)/ef_$(1)/dep - $(V1) cd $(ROOT_DIR)/flight/EntireFlash && \ + $(V1) cd $(ROOT_DIR)/flight/targets/EntireFlash && \ $$(MAKE) -r --no-print-directory \ BOARD_NAME=$(1) \ BOARD_SHORT_NAME=$(3) \ @@ -958,7 +958,7 @@ sim_win32: sim_win32_exe sim_win32_%: uavobjects_flight $(V1) mkdir -p $(BUILD_DIR)/sitl_win32 $(V1) $(MAKE) --no-print-directory \ - -C $(ROOT_DIR)/flight/OpenPilot --file=$(ROOT_DIR)/flight/OpenPilot/Makefile.win32 $* + -C $(ROOT_DIR)/flight/targets/OpenPilot --file=$(ROOT_DIR)/flight/targets/OpenPilot/Makefile.win32 $* .PHONY: sim_osx sim_osx: sim_osx_elf @@ -966,7 +966,7 @@ sim_osx: sim_osx_elf sim_osx_%: uavobjects_flight $(V1) mkdir -p $(BUILD_DIR)/sim_osx $(V1) $(MAKE) --no-print-directory \ - -C $(ROOT_DIR)/flight/Revolution --file=$(ROOT_DIR)/flight/Revolution/Makefile.osx $* + -C $(ROOT_DIR)/flight/targets/Revolution --file=$(ROOT_DIR)/flight/targets/Revolution/Makefile.osx $* ############################## # # Packaging components diff --git a/flight/OpenPilot/System/pios_usb_board_data.c b/flight/OpenPilot/System/pios_usb_board_data.c deleted file mode 100644 index a6fa67abe..000000000 --- a/flight/OpenPilot/System/pios_usb_board_data.c +++ /dev/null @@ -1,120 +0,0 @@ -/** - ****************************************************************************** - * @addtogroup PIOS PIOS Core hardware abstraction layer - * @{ - * @addtogroup PIOS_USB_BOARD Board specific USB definitions - * @brief Board specific USB definitions - * @{ - * - * @file pios_usb_board_data.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Board specific USB definitions - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#include "pios_usb_board_data.h" /* struct usb_*, USB_* */ -#include "pios_sys.h" /* PIOS_SYS_SerialNumberGet */ -#include "pios_usbhook.h" /* PIOS_USBHOOK_* */ - -static const uint8_t usb_product_id[20] = { - sizeof(usb_product_id), - USB_DESC_TYPE_STRING, - 'O', 0, - 'p', 0, - 'e', 0, - 'n', 0, - 'P', 0, - 'i', 0, - 'l', 0, - 'o', 0, - 't', 0, -}; - -static uint8_t usb_serial_number[52] = { - sizeof(usb_serial_number), - USB_DESC_TYPE_STRING, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0 -}; - -static const struct usb_string_langid usb_lang_id = { - .bLength = sizeof(usb_lang_id), - .bDescriptorType = USB_DESC_TYPE_STRING, - .bLangID = htousbs(USB_LANGID_ENGLISH_UK), -}; - -static const uint8_t usb_vendor_id[28] = { - sizeof(usb_vendor_id), - USB_DESC_TYPE_STRING, - 'o', 0, - 'p', 0, - 'e', 0, - 'n', 0, - 'p', 0, - 'i', 0, - 'l', 0, - 'o', 0, - 't', 0, - '.', 0, - 'o', 0, - 'r', 0, - 'g', 0 -}; - -int32_t PIOS_USB_BOARD_DATA_Init(void) -{ - /* Load device serial number into serial number string */ - uint8_t sn[25]; - PIOS_SYS_SerialNumberGet((char *)sn); - for (uint8_t i = 0; sn[i] != '\0' && (2 * i) < usb_serial_number[0]; i++) { - usb_serial_number[2 + 2 * i] = sn[i]; - } - - PIOS_USBHOOK_RegisterString(USB_STRING_DESC_PRODUCT, (uint8_t *)&usb_product_id, sizeof(usb_product_id)); - PIOS_USBHOOK_RegisterString(USB_STRING_DESC_SERIAL, (uint8_t *)&usb_serial_number, sizeof(usb_serial_number)); - - PIOS_USBHOOK_RegisterString(USB_STRING_DESC_LANG, (uint8_t *)&usb_lang_id, sizeof(usb_lang_id)); - PIOS_USBHOOK_RegisterString(USB_STRING_DESC_VENDOR, (uint8_t *)&usb_vendor_id, sizeof(usb_vendor_id)); - - return 0; -} - diff --git a/flight/Bootloaders/BootloaderUpdater/Makefile b/flight/targets/Bootloaders/BootloaderUpdater/Makefile similarity index 97% rename from flight/Bootloaders/BootloaderUpdater/Makefile rename to flight/targets/Bootloaders/BootloaderUpdater/Makefile index 62fc2c056..9dbbd6ae0 100644 --- a/flight/Bootloaders/BootloaderUpdater/Makefile +++ b/flight/targets/Bootloaders/BootloaderUpdater/Makefile @@ -23,7 +23,7 @@ ##### WHEREAMI := $(dir $(lastword $(MAKEFILE_LIST))) -TOP := $(realpath $(WHEREAMI)/../../../) +TOP := $(realpath $(WHEREAMI)/../../../../) include $(TOP)/make/firmware-defs.mk include $(TOP)/make/boards/$(BOARD_NAME)/board-info.mk @@ -61,15 +61,7 @@ FLASH_TOOL = OPENOCD # Paths OPSYSTEM = . OPSYSTEMINC = $(OPSYSTEM)/inc -OPUAVTALK = ./UAVTalk -OPUAVTALKINC = $(OPUAVTALK)/inc -OPUAVOBJ = ./UAVObjects -OPUAVOBJINC = $(OPUAVOBJ)/inc -OPTESTS = ./Tests -OPMODULEDIR = ./Modules -FLIGHTLIB = ../../Libraries -FLIGHTLIBINC = ../../Libraries/inc -PIOS = ../../PiOS +PIOS = ../../../PiOS PIOSINC = $(PIOS)/inc PIOSSTM32F10X = $(PIOS)/STM32F10x PIOSCOMMON = $(PIOS)/Common @@ -89,7 +81,7 @@ RTOSDIR = $(APPLIBDIR)/FreeRTOS RTOSSRCDIR = $(RTOSDIR)/Source RTOSINCDIR = $(RTOSSRCDIR)/include DOXYGENDIR = ../Doc/Doxygen -HWDEFSINC = $(TOP)/flight/board_hw_defs/$(BOARD_NAME) +HWDEFSINC = $(TOP)/flight/targets/board_hw_defs/$(BOARD_NAME) # List C source files here. (C dependencies are automatically generated.) # use file-extension c for "c-only"-files diff --git a/flight/Bootloaders/BootloaderUpdater/inc/pios_config.h b/flight/targets/Bootloaders/BootloaderUpdater/inc/pios_config.h similarity index 100% rename from flight/Bootloaders/BootloaderUpdater/inc/pios_config.h rename to flight/targets/Bootloaders/BootloaderUpdater/inc/pios_config.h diff --git a/flight/Bootloaders/BootloaderUpdater/main.c b/flight/targets/Bootloaders/BootloaderUpdater/main.c similarity index 100% rename from flight/Bootloaders/BootloaderUpdater/main.c rename to flight/targets/Bootloaders/BootloaderUpdater/main.c diff --git a/flight/Bootloaders/BootloaderUpdater/pios_board.c b/flight/targets/Bootloaders/BootloaderUpdater/pios_board.c similarity index 100% rename from flight/Bootloaders/BootloaderUpdater/pios_board.c rename to flight/targets/Bootloaders/BootloaderUpdater/pios_board.c diff --git a/flight/Bootloaders/CopterControl/Makefile b/flight/targets/Bootloaders/CopterControl/Makefile similarity index 98% rename from flight/Bootloaders/CopterControl/Makefile rename to flight/targets/Bootloaders/CopterControl/Makefile index 8c22d37a7..c8b017285 100644 --- a/flight/Bootloaders/CopterControl/Makefile +++ b/flight/targets/Bootloaders/CopterControl/Makefile @@ -23,7 +23,7 @@ ##### WHEREAMI := $(dir $(lastword $(MAKEFILE_LIST))) -TOP := $(realpath $(WHEREAMI)/../../../) +TOP := $(realpath $(WHEREAMI)/../../../../) include $(TOP)/make/firmware-defs.mk include $(TOP)/make/boards/$(BOARD_NAME)/board-info.mk @@ -58,15 +58,9 @@ FLASH_TOOL = OPENOCD # Paths OPSYSTEM = . OPSYSTEMINC = $(OPSYSTEM)/inc -OPUAVTALK = ./UAVTalk -OPUAVTALKINC = $(OPUAVTALK)/inc -OPUAVOBJ = ./UAVObjects -OPUAVOBJINC = $(OPUAVOBJ)/inc -OPTESTS = ./Tests -OPMODULEDIR = ./Modules -FLIGHTLIB = ../../Libraries -FLIGHTLIBINC = ../../Libraries/inc -PIOS = ../../PiOS +FLIGHTLIB = ../../../Libraries +FLIGHTLIBINC = $(FLIGHTLIB)/inc +PIOS = ../../../PiOS PIOSINC = $(PIOS)/inc PIOSSTM32F10X = $(PIOS)/STM32F10x PIOSCOMMON = $(PIOS)/Common diff --git a/flight/Bootloaders/CopterControl/inc/common.h b/flight/targets/Bootloaders/CopterControl/inc/common.h similarity index 100% rename from flight/Bootloaders/CopterControl/inc/common.h rename to flight/targets/Bootloaders/CopterControl/inc/common.h diff --git a/flight/Bootloaders/CopterControl/inc/op_dfu.h b/flight/targets/Bootloaders/CopterControl/inc/op_dfu.h similarity index 100% rename from flight/Bootloaders/CopterControl/inc/op_dfu.h rename to flight/targets/Bootloaders/CopterControl/inc/op_dfu.h diff --git a/flight/Bootloaders/CopterControl/inc/pios_config.h b/flight/targets/Bootloaders/CopterControl/inc/pios_config.h similarity index 100% rename from flight/Bootloaders/CopterControl/inc/pios_config.h rename to flight/targets/Bootloaders/CopterControl/inc/pios_config.h diff --git a/flight/Bootloaders/CopterControl/inc/pios_usb_board_data.h b/flight/targets/Bootloaders/CopterControl/inc/pios_usb_board_data.h similarity index 100% rename from flight/Bootloaders/CopterControl/inc/pios_usb_board_data.h rename to flight/targets/Bootloaders/CopterControl/inc/pios_usb_board_data.h diff --git a/flight/Bootloaders/CopterControl/main.c b/flight/targets/Bootloaders/CopterControl/main.c similarity index 100% rename from flight/Bootloaders/CopterControl/main.c rename to flight/targets/Bootloaders/CopterControl/main.c diff --git a/flight/Bootloaders/CopterControl/op_dfu.c b/flight/targets/Bootloaders/CopterControl/op_dfu.c similarity index 100% rename from flight/Bootloaders/CopterControl/op_dfu.c rename to flight/targets/Bootloaders/CopterControl/op_dfu.c diff --git a/flight/Bootloaders/CopterControl/pios_board.c b/flight/targets/Bootloaders/CopterControl/pios_board.c similarity index 100% rename from flight/Bootloaders/CopterControl/pios_board.c rename to flight/targets/Bootloaders/CopterControl/pios_board.c diff --git a/flight/Bootloaders/CopterControl/pios_usb_board_data.c b/flight/targets/Bootloaders/CopterControl/pios_usb_board_data.c similarity index 100% rename from flight/Bootloaders/CopterControl/pios_usb_board_data.c rename to flight/targets/Bootloaders/CopterControl/pios_usb_board_data.c diff --git a/flight/Bootloaders/OSD/Makefile b/flight/targets/Bootloaders/OSD/Makefile similarity index 98% rename from flight/Bootloaders/OSD/Makefile rename to flight/targets/Bootloaders/OSD/Makefile index 3742a7f24..5705adf61 100644 --- a/flight/Bootloaders/OSD/Makefile +++ b/flight/targets/Bootloaders/OSD/Makefile @@ -23,7 +23,7 @@ ##### WHEREAMI := $(dir $(lastword $(MAKEFILE_LIST))) -TOP := $(realpath $(WHEREAMI)/../../../) +TOP := $(realpath $(WHEREAMI)/../../../../) include $(TOP)/make/firmware-defs.mk include $(TOP)/make/boards/$(BOARD_NAME)/board-info.mk @@ -49,10 +49,10 @@ endif # Paths OSD_BL = $(WHEREAMI) OSD_BLINC = $(OSD_BL)/inc -PIOS = ../../PiOS +PIOS = ../../../PiOS PIOSINC = $(PIOS)/inc -FLIGHTLIB = ../../Libraries -FLIGHTLIBINC = ../../Libraries/inc +FLIGHTLIB = ../../../Libraries +FLIGHTLIBINC = $(FLIGHTLIB)/inc PIOSSTM32F4XX = $(PIOS)/STM32F4xx PIOSCOMMON = $(PIOS)/Common PIOSBOARDS = $(PIOS)/Boards diff --git a/flight/Bootloaders/OSD/inc/common.h b/flight/targets/Bootloaders/OSD/inc/common.h similarity index 100% rename from flight/Bootloaders/OSD/inc/common.h rename to flight/targets/Bootloaders/OSD/inc/common.h diff --git a/flight/Bootloaders/OSD/inc/op_dfu.h b/flight/targets/Bootloaders/OSD/inc/op_dfu.h similarity index 100% rename from flight/Bootloaders/OSD/inc/op_dfu.h rename to flight/targets/Bootloaders/OSD/inc/op_dfu.h diff --git a/flight/Bootloaders/OSD/inc/pios_config.h b/flight/targets/Bootloaders/OSD/inc/pios_config.h similarity index 100% rename from flight/Bootloaders/OSD/inc/pios_config.h rename to flight/targets/Bootloaders/OSD/inc/pios_config.h diff --git a/flight/Bootloaders/OSD/inc/pios_usb_board_data.h b/flight/targets/Bootloaders/OSD/inc/pios_usb_board_data.h similarity index 100% rename from flight/Bootloaders/OSD/inc/pios_usb_board_data.h rename to flight/targets/Bootloaders/OSD/inc/pios_usb_board_data.h diff --git a/flight/Bootloaders/OSD/main.c b/flight/targets/Bootloaders/OSD/main.c similarity index 100% rename from flight/Bootloaders/OSD/main.c rename to flight/targets/Bootloaders/OSD/main.c diff --git a/flight/Bootloaders/OSD/op_dfu.c b/flight/targets/Bootloaders/OSD/op_dfu.c similarity index 100% rename from flight/Bootloaders/OSD/op_dfu.c rename to flight/targets/Bootloaders/OSD/op_dfu.c diff --git a/flight/Bootloaders/OSD/pios_board.c b/flight/targets/Bootloaders/OSD/pios_board.c similarity index 100% rename from flight/Bootloaders/OSD/pios_board.c rename to flight/targets/Bootloaders/OSD/pios_board.c diff --git a/flight/Bootloaders/OSD/pios_usb_board_data.c b/flight/targets/Bootloaders/OSD/pios_usb_board_data.c similarity index 100% rename from flight/Bootloaders/OSD/pios_usb_board_data.c rename to flight/targets/Bootloaders/OSD/pios_usb_board_data.c diff --git a/flight/Bootloaders/PipXtreme/Makefile b/flight/targets/Bootloaders/PipXtreme/Makefile similarity index 98% rename from flight/Bootloaders/PipXtreme/Makefile rename to flight/targets/Bootloaders/PipXtreme/Makefile index 5747a0511..8cd3af69e 100644 --- a/flight/Bootloaders/PipXtreme/Makefile +++ b/flight/targets/Bootloaders/PipXtreme/Makefile @@ -23,7 +23,7 @@ ##### WHEREAMI := $(dir $(lastword $(MAKEFILE_LIST))) -TOP := $(realpath $(WHEREAMI)/../../../) +TOP := $(realpath $(WHEREAMI)/../../../../) include $(TOP)/make/firmware-defs.mk include $(TOP)/make/boards/$(BOARD_NAME)/board-info.mk @@ -58,15 +58,9 @@ FLASH_TOOL = OPENOCD # Paths OPSYSTEM = . OPSYSTEMINC = $(OPSYSTEM)/inc -OPUAVTALK = ./UAVTalk -OPUAVTALKINC = $(OPUAVTALK)/inc -OPUAVOBJ = ./UAVObjects -OPUAVOBJINC = $(OPUAVOBJ)/inc -OPTESTS = ./Tests -OPMODULEDIR = ./Modules -FLIGHTLIB = ../../Libraries -FLIGHTLIBINC = ../../Libraries/inc -PIOS = ../../PiOS +FLIGHTLIB = ../../../Libraries +FLIGHTLIBINC = $(FLIGHTLIB)/inc +PIOS = ../../../PiOS PIOSINC = $(PIOS)/inc PIOSSTM32F10X = $(PIOS)/STM32F10x PIOSCOMMON = $(PIOS)/Common diff --git a/flight/Bootloaders/PipXtreme/inc/common.h b/flight/targets/Bootloaders/PipXtreme/inc/common.h similarity index 100% rename from flight/Bootloaders/PipXtreme/inc/common.h rename to flight/targets/Bootloaders/PipXtreme/inc/common.h diff --git a/flight/Bootloaders/PipXtreme/inc/op_dfu.h b/flight/targets/Bootloaders/PipXtreme/inc/op_dfu.h similarity index 100% rename from flight/Bootloaders/PipXtreme/inc/op_dfu.h rename to flight/targets/Bootloaders/PipXtreme/inc/op_dfu.h diff --git a/flight/Bootloaders/PipXtreme/inc/pios_config.h b/flight/targets/Bootloaders/PipXtreme/inc/pios_config.h similarity index 100% rename from flight/Bootloaders/PipXtreme/inc/pios_config.h rename to flight/targets/Bootloaders/PipXtreme/inc/pios_config.h diff --git a/flight/Bootloaders/PipXtreme/inc/pios_usb_board_data.h b/flight/targets/Bootloaders/PipXtreme/inc/pios_usb_board_data.h similarity index 100% rename from flight/Bootloaders/PipXtreme/inc/pios_usb_board_data.h rename to flight/targets/Bootloaders/PipXtreme/inc/pios_usb_board_data.h diff --git a/flight/Bootloaders/PipXtreme/main.c b/flight/targets/Bootloaders/PipXtreme/main.c similarity index 100% rename from flight/Bootloaders/PipXtreme/main.c rename to flight/targets/Bootloaders/PipXtreme/main.c diff --git a/flight/Bootloaders/PipXtreme/op_dfu.c b/flight/targets/Bootloaders/PipXtreme/op_dfu.c similarity index 100% rename from flight/Bootloaders/PipXtreme/op_dfu.c rename to flight/targets/Bootloaders/PipXtreme/op_dfu.c diff --git a/flight/Bootloaders/PipXtreme/pios_board.c b/flight/targets/Bootloaders/PipXtreme/pios_board.c similarity index 100% rename from flight/Bootloaders/PipXtreme/pios_board.c rename to flight/targets/Bootloaders/PipXtreme/pios_board.c diff --git a/flight/Bootloaders/PipXtreme/pios_usb_board_data.c b/flight/targets/Bootloaders/PipXtreme/pios_usb_board_data.c similarity index 100% rename from flight/Bootloaders/PipXtreme/pios_usb_board_data.c rename to flight/targets/Bootloaders/PipXtreme/pios_usb_board_data.c diff --git a/flight/Bootloaders/RevoMini/Makefile b/flight/targets/Bootloaders/RevoMini/Makefile similarity index 98% rename from flight/Bootloaders/RevoMini/Makefile rename to flight/targets/Bootloaders/RevoMini/Makefile index d708a6c82..142daa56e 100644 --- a/flight/Bootloaders/RevoMini/Makefile +++ b/flight/targets/Bootloaders/RevoMini/Makefile @@ -23,7 +23,7 @@ ##### WHEREAMI := $(dir $(lastword $(MAKEFILE_LIST))) -TOP := $(realpath $(WHEREAMI)/../../../) +TOP := $(realpath $(WHEREAMI)/../../../../) include $(TOP)/make/firmware-defs.mk include $(TOP)/make/boards/$(BOARD_NAME)/board-info.mk @@ -49,10 +49,10 @@ endif # Paths REVO_BL = $(WHEREAMI) REVO_BLINC = $(REVO_BL)/inc -PIOS = ../../PiOS +PIOS = ../../../PiOS PIOSINC = $(PIOS)/inc -FLIGHTLIB = ../../Libraries -FLIGHTLIBINC = ../../Libraries/inc +FLIGHTLIB = ../../../Libraries +FLIGHTLIBINC = $(FLIGHTLIB)/inc PIOSSTM32F4XX = $(PIOS)/STM32F4xx PIOSCOMMON = $(PIOS)/Common PIOSBOARDS = $(PIOS)/Boards diff --git a/flight/Bootloaders/RevoMini/inc/common.h b/flight/targets/Bootloaders/RevoMini/inc/common.h similarity index 100% rename from flight/Bootloaders/RevoMini/inc/common.h rename to flight/targets/Bootloaders/RevoMini/inc/common.h diff --git a/flight/Bootloaders/RevoMini/inc/op_dfu.h b/flight/targets/Bootloaders/RevoMini/inc/op_dfu.h similarity index 100% rename from flight/Bootloaders/RevoMini/inc/op_dfu.h rename to flight/targets/Bootloaders/RevoMini/inc/op_dfu.h diff --git a/flight/Bootloaders/RevoMini/inc/pios_config.h b/flight/targets/Bootloaders/RevoMini/inc/pios_config.h similarity index 100% rename from flight/Bootloaders/RevoMini/inc/pios_config.h rename to flight/targets/Bootloaders/RevoMini/inc/pios_config.h diff --git a/flight/Bootloaders/RevoMini/inc/pios_usb_board_data.h b/flight/targets/Bootloaders/RevoMini/inc/pios_usb_board_data.h similarity index 100% rename from flight/Bootloaders/RevoMini/inc/pios_usb_board_data.h rename to flight/targets/Bootloaders/RevoMini/inc/pios_usb_board_data.h diff --git a/flight/Bootloaders/RevoMini/main.c b/flight/targets/Bootloaders/RevoMini/main.c similarity index 100% rename from flight/Bootloaders/RevoMini/main.c rename to flight/targets/Bootloaders/RevoMini/main.c diff --git a/flight/Bootloaders/RevoMini/op_dfu.c b/flight/targets/Bootloaders/RevoMini/op_dfu.c similarity index 100% rename from flight/Bootloaders/RevoMini/op_dfu.c rename to flight/targets/Bootloaders/RevoMini/op_dfu.c diff --git a/flight/Bootloaders/RevoMini/pios_board.c b/flight/targets/Bootloaders/RevoMini/pios_board.c similarity index 100% rename from flight/Bootloaders/RevoMini/pios_board.c rename to flight/targets/Bootloaders/RevoMini/pios_board.c diff --git a/flight/Bootloaders/RevoMini/pios_usb_board_data.c b/flight/targets/Bootloaders/RevoMini/pios_usb_board_data.c similarity index 100% rename from flight/Bootloaders/RevoMini/pios_usb_board_data.c rename to flight/targets/Bootloaders/RevoMini/pios_usb_board_data.c diff --git a/flight/Bootloaders/Revolution/Makefile b/flight/targets/Bootloaders/Revolution/Makefile similarity index 98% rename from flight/Bootloaders/Revolution/Makefile rename to flight/targets/Bootloaders/Revolution/Makefile index d708a6c82..142daa56e 100644 --- a/flight/Bootloaders/Revolution/Makefile +++ b/flight/targets/Bootloaders/Revolution/Makefile @@ -23,7 +23,7 @@ ##### WHEREAMI := $(dir $(lastword $(MAKEFILE_LIST))) -TOP := $(realpath $(WHEREAMI)/../../../) +TOP := $(realpath $(WHEREAMI)/../../../../) include $(TOP)/make/firmware-defs.mk include $(TOP)/make/boards/$(BOARD_NAME)/board-info.mk @@ -49,10 +49,10 @@ endif # Paths REVO_BL = $(WHEREAMI) REVO_BLINC = $(REVO_BL)/inc -PIOS = ../../PiOS +PIOS = ../../../PiOS PIOSINC = $(PIOS)/inc -FLIGHTLIB = ../../Libraries -FLIGHTLIBINC = ../../Libraries/inc +FLIGHTLIB = ../../../Libraries +FLIGHTLIBINC = $(FLIGHTLIB)/inc PIOSSTM32F4XX = $(PIOS)/STM32F4xx PIOSCOMMON = $(PIOS)/Common PIOSBOARDS = $(PIOS)/Boards diff --git a/flight/Bootloaders/Revolution/inc/common.h b/flight/targets/Bootloaders/Revolution/inc/common.h similarity index 100% rename from flight/Bootloaders/Revolution/inc/common.h rename to flight/targets/Bootloaders/Revolution/inc/common.h diff --git a/flight/Bootloaders/Revolution/inc/op_dfu.h b/flight/targets/Bootloaders/Revolution/inc/op_dfu.h similarity index 100% rename from flight/Bootloaders/Revolution/inc/op_dfu.h rename to flight/targets/Bootloaders/Revolution/inc/op_dfu.h diff --git a/flight/Bootloaders/Revolution/inc/pios_config.h b/flight/targets/Bootloaders/Revolution/inc/pios_config.h similarity index 100% rename from flight/Bootloaders/Revolution/inc/pios_config.h rename to flight/targets/Bootloaders/Revolution/inc/pios_config.h diff --git a/flight/Bootloaders/Revolution/inc/pios_usb_board_data.h b/flight/targets/Bootloaders/Revolution/inc/pios_usb_board_data.h similarity index 100% rename from flight/Bootloaders/Revolution/inc/pios_usb_board_data.h rename to flight/targets/Bootloaders/Revolution/inc/pios_usb_board_data.h diff --git a/flight/Bootloaders/Revolution/main.c b/flight/targets/Bootloaders/Revolution/main.c similarity index 100% rename from flight/Bootloaders/Revolution/main.c rename to flight/targets/Bootloaders/Revolution/main.c diff --git a/flight/Bootloaders/Revolution/op_dfu.c b/flight/targets/Bootloaders/Revolution/op_dfu.c similarity index 100% rename from flight/Bootloaders/Revolution/op_dfu.c rename to flight/targets/Bootloaders/Revolution/op_dfu.c diff --git a/flight/Bootloaders/Revolution/pios_board.c b/flight/targets/Bootloaders/Revolution/pios_board.c similarity index 100% rename from flight/Bootloaders/Revolution/pios_board.c rename to flight/targets/Bootloaders/Revolution/pios_board.c diff --git a/flight/Bootloaders/Revolution/pios_usb_board_data.c b/flight/targets/Bootloaders/Revolution/pios_usb_board_data.c similarity index 100% rename from flight/Bootloaders/Revolution/pios_usb_board_data.c rename to flight/targets/Bootloaders/Revolution/pios_usb_board_data.c diff --git a/flight/CopterControl/Makefile b/flight/targets/CopterControl/Makefile similarity index 98% rename from flight/CopterControl/Makefile rename to flight/targets/CopterControl/Makefile index c6a7e3f78..a6c39b7c3 100644 --- a/flight/CopterControl/Makefile +++ b/flight/targets/CopterControl/Makefile @@ -23,7 +23,7 @@ ##### WHEREAMI := $(dir $(lastword $(MAKEFILE_LIST))) -TOP := $(realpath $(WHEREAMI)/../../) +TOP := $(realpath $(WHEREAMI)/../../../) include $(TOP)/make/firmware-defs.mk include $(TOP)/make/boards/$(BOARD_NAME)/board-info.mk @@ -118,17 +118,17 @@ MODULES += Telemetry # Paths OPSYSTEM = ./System OPSYSTEMINC = $(OPSYSTEM)/inc -OPUAVTALK = ../UAVTalk +OPUAVTALK = ../../UAVTalk OPUAVTALKINC = $(OPUAVTALK)/inc -OPUAVOBJ = ../UAVObjects +OPUAVOBJ = ../../UAVObjects OPUAVOBJINC = $(OPUAVOBJ)/inc OPTESTS = ./Tests -OPMODULEDIR = ../Modules -FLIGHTLIB = ../Libraries +OPMODULEDIR = ../../Modules +FLIGHTLIB = ../../Libraries FLIGHTLIBINC = $(FLIGHTLIB)/inc -MATHLIB = ../Libraries/math -MATHLIBINC = ../Libraries/math -PIOS = ../PiOS +MATHLIB = ../../Libraries/math +MATHLIBINC = ../../Libraries/math +PIOS = ../../PiOS PIOSINC = $(PIOS)/inc PIOSSTM32F10X = $(PIOS)/STM32F10x PIOSCOMMON = $(PIOS)/Common diff --git a/flight/CopterControl/System/alarms.c b/flight/targets/CopterControl/System/alarms.c similarity index 100% rename from flight/CopterControl/System/alarms.c rename to flight/targets/CopterControl/System/alarms.c diff --git a/flight/CopterControl/System/coptercontrol.c b/flight/targets/CopterControl/System/coptercontrol.c similarity index 100% rename from flight/CopterControl/System/coptercontrol.c rename to flight/targets/CopterControl/System/coptercontrol.c diff --git a/flight/CopterControl/System/inc/FreeRTOSConfig.h b/flight/targets/CopterControl/System/inc/FreeRTOSConfig.h similarity index 100% rename from flight/CopterControl/System/inc/FreeRTOSConfig.h rename to flight/targets/CopterControl/System/inc/FreeRTOSConfig.h diff --git a/flight/CopterControl/System/inc/alarms.h b/flight/targets/CopterControl/System/inc/alarms.h similarity index 100% rename from flight/CopterControl/System/inc/alarms.h rename to flight/targets/CopterControl/System/inc/alarms.h diff --git a/flight/CopterControl/System/inc/op_config.h b/flight/targets/CopterControl/System/inc/op_config.h similarity index 100% rename from flight/CopterControl/System/inc/op_config.h rename to flight/targets/CopterControl/System/inc/op_config.h diff --git a/flight/CopterControl/System/inc/openpilot.h b/flight/targets/CopterControl/System/inc/openpilot.h similarity index 100% rename from flight/CopterControl/System/inc/openpilot.h rename to flight/targets/CopterControl/System/inc/openpilot.h diff --git a/flight/CopterControl/System/inc/pios_board_posix.h b/flight/targets/CopterControl/System/inc/pios_board_posix.h similarity index 100% rename from flight/CopterControl/System/inc/pios_board_posix.h rename to flight/targets/CopterControl/System/inc/pios_board_posix.h diff --git a/flight/CopterControl/System/inc/pios_config.h b/flight/targets/CopterControl/System/inc/pios_config.h similarity index 100% rename from flight/CopterControl/System/inc/pios_config.h rename to flight/targets/CopterControl/System/inc/pios_config.h diff --git a/flight/CopterControl/System/inc/pios_config_posix.h b/flight/targets/CopterControl/System/inc/pios_config_posix.h similarity index 100% rename from flight/CopterControl/System/inc/pios_config_posix.h rename to flight/targets/CopterControl/System/inc/pios_config_posix.h diff --git a/flight/CopterControl/System/inc/pios_usb_board_data.h b/flight/targets/CopterControl/System/inc/pios_usb_board_data.h similarity index 100% rename from flight/CopterControl/System/inc/pios_usb_board_data.h rename to flight/targets/CopterControl/System/inc/pios_usb_board_data.h diff --git a/flight/CopterControl/System/pios_board.c b/flight/targets/CopterControl/System/pios_board.c similarity index 100% rename from flight/CopterControl/System/pios_board.c rename to flight/targets/CopterControl/System/pios_board.c diff --git a/flight/CopterControl/System/pios_board_posix.c b/flight/targets/CopterControl/System/pios_board_posix.c similarity index 100% rename from flight/CopterControl/System/pios_board_posix.c rename to flight/targets/CopterControl/System/pios_board_posix.c diff --git a/flight/CopterControl/System/pios_usb_board_data.c b/flight/targets/CopterControl/System/pios_usb_board_data.c similarity index 100% rename from flight/CopterControl/System/pios_usb_board_data.c rename to flight/targets/CopterControl/System/pios_usb_board_data.c diff --git a/flight/EntireFlash/Makefile b/flight/targets/EntireFlash/Makefile similarity index 98% rename from flight/EntireFlash/Makefile rename to flight/targets/EntireFlash/Makefile index 13aae597d..9d18979dd 100644 --- a/flight/EntireFlash/Makefile +++ b/flight/targets/EntireFlash/Makefile @@ -20,7 +20,7 @@ ##### WHEREAMI := $(dir $(lastword $(MAKEFILE_LIST))) -TOP := $(realpath $(WHEREAMI)/../../) +TOP := $(realpath $(WHEREAMI)/../../../) include $(TOP)/make/firmware-defs.mk include $(TOP)/make/boards/$(BOARD_NAME)/board-info.mk diff --git a/flight/OSD/Makefile b/flight/targets/OSD/Makefile similarity index 98% rename from flight/OSD/Makefile rename to flight/targets/OSD/Makefile index 93b7d2861..4bc4309ba 100644 --- a/flight/OSD/Makefile +++ b/flight/targets/OSD/Makefile @@ -23,7 +23,7 @@ ##### WHEREAMI := $(dir $(lastword $(MAKEFILE_LIST))) -TOP := $(realpath $(WHEREAMI)/../../) +TOP := $(realpath $(WHEREAMI)/../../../) include $(TOP)/make/firmware-defs.mk include $(TOP)/make/boards/$(BOARD_NAME)/board-info.mk @@ -102,13 +102,13 @@ MODULES += FirmwareIAP # Paths OPSYSTEM = ./System OPSYSTEMINC = $(OPSYSTEM)/inc -OPUAVTALK = ../UAVTalk +OPUAVTALK = ../../UAVTalk OPUAVTALKINC = $(OPUAVTALK)/inc -OPMODULEDIR = ../Modules -PIOS = ../PiOS +OPMODULEDIR = ../../Modules +PIOS = ../../PiOS PIOSINC = $(PIOS)/inc -FLIGHTLIB = ../Libraries -FLIGHTLIBINC = ../Libraries/inc +FLIGHTLIB = ../../Libraries +FLIGHTLIBINC = $(FLIGHTLIB)/inc PIOSSTM32F4XX = $(PIOS)/STM32F4xx PIOSCOMMON = $(PIOS)/Common PIOSBOARDS = $(PIOS)/Boards @@ -125,7 +125,7 @@ RTOSDIR = $(PIOSCOMMONLIB)/FreeRTOS RTOSSRCDIR = $(RTOSDIR)/Source RTOSINCDIR = $(RTOSSRCDIR)/include OPDIR = ../OSD -OPUAVOBJ = ../UAVObjects +OPUAVOBJ = ../../UAVObjects OPUAVOBJINC = $(OPUAVOBJ)/inc OPSYSINC = $(OPDIR)/System/inc BOOT = ../Bootloaders/OSD diff --git a/flight/OSD/System/alarms.c b/flight/targets/OSD/System/alarms.c similarity index 100% rename from flight/OSD/System/alarms.c rename to flight/targets/OSD/System/alarms.c diff --git a/flight/OSD/System/cm3_fault_handlers.c b/flight/targets/OSD/System/cm3_fault_handlers.c similarity index 100% rename from flight/OSD/System/cm3_fault_handlers.c rename to flight/targets/OSD/System/cm3_fault_handlers.c diff --git a/flight/OSD/System/dcc_stdio.c b/flight/targets/OSD/System/dcc_stdio.c similarity index 100% rename from flight/OSD/System/dcc_stdio.c rename to flight/targets/OSD/System/dcc_stdio.c diff --git a/flight/OSD/System/font_outlined8x14.c b/flight/targets/OSD/System/font_outlined8x14.c similarity index 100% rename from flight/OSD/System/font_outlined8x14.c rename to flight/targets/OSD/System/font_outlined8x14.c diff --git a/flight/OSD/System/font_outlined8x14.h b/flight/targets/OSD/System/font_outlined8x14.h similarity index 100% rename from flight/OSD/System/font_outlined8x14.h rename to flight/targets/OSD/System/font_outlined8x14.h diff --git a/flight/OSD/System/font_outlined8x8.c b/flight/targets/OSD/System/font_outlined8x8.c similarity index 100% rename from flight/OSD/System/font_outlined8x8.c rename to flight/targets/OSD/System/font_outlined8x8.c diff --git a/flight/OSD/System/font_outlined8x8.h b/flight/targets/OSD/System/font_outlined8x8.h similarity index 100% rename from flight/OSD/System/font_outlined8x8.h rename to flight/targets/OSD/System/font_outlined8x8.h diff --git a/flight/OSD/System/fonts.c b/flight/targets/OSD/System/fonts.c similarity index 100% rename from flight/OSD/System/fonts.c rename to flight/targets/OSD/System/fonts.c diff --git a/flight/OSD/System/fonts.h b/flight/targets/OSD/System/fonts.h similarity index 100% rename from flight/OSD/System/fonts.h rename to flight/targets/OSD/System/fonts.h diff --git a/flight/OSD/System/inc/FreeRTOSConfig.h b/flight/targets/OSD/System/inc/FreeRTOSConfig.h similarity index 100% rename from flight/OSD/System/inc/FreeRTOSConfig.h rename to flight/targets/OSD/System/inc/FreeRTOSConfig.h diff --git a/flight/OSD/System/inc/alarms.h b/flight/targets/OSD/System/inc/alarms.h similarity index 100% rename from flight/OSD/System/inc/alarms.h rename to flight/targets/OSD/System/inc/alarms.h diff --git a/flight/OSD/System/inc/dcc_stdio.h b/flight/targets/OSD/System/inc/dcc_stdio.h similarity index 100% rename from flight/OSD/System/inc/dcc_stdio.h rename to flight/targets/OSD/System/inc/dcc_stdio.h diff --git a/flight/OSD/System/inc/font12x18.h b/flight/targets/OSD/System/inc/font12x18.h similarity index 100% rename from flight/OSD/System/inc/font12x18.h rename to flight/targets/OSD/System/inc/font12x18.h diff --git a/flight/OSD/System/inc/font8x10.h b/flight/targets/OSD/System/inc/font8x10.h similarity index 100% rename from flight/OSD/System/inc/font8x10.h rename to flight/targets/OSD/System/inc/font8x10.h diff --git a/flight/OSD/System/inc/op_config.h b/flight/targets/OSD/System/inc/op_config.h similarity index 100% rename from flight/OSD/System/inc/op_config.h rename to flight/targets/OSD/System/inc/op_config.h diff --git a/flight/OSD/System/inc/openpilot.h b/flight/targets/OSD/System/inc/openpilot.h similarity index 100% rename from flight/OSD/System/inc/openpilot.h rename to flight/targets/OSD/System/inc/openpilot.h diff --git a/flight/OSD/System/inc/pios_config.h b/flight/targets/OSD/System/inc/pios_config.h similarity index 100% rename from flight/OSD/System/inc/pios_config.h rename to flight/targets/OSD/System/inc/pios_config.h diff --git a/flight/OSD/System/inc/pios_usb_board_data.h b/flight/targets/OSD/System/inc/pios_usb_board_data.h similarity index 100% rename from flight/OSD/System/inc/pios_usb_board_data.h rename to flight/targets/OSD/System/inc/pios_usb_board_data.h diff --git a/flight/OSD/System/inc/splash.h b/flight/targets/OSD/System/inc/splash.h similarity index 100% rename from flight/OSD/System/inc/splash.h rename to flight/targets/OSD/System/inc/splash.h diff --git a/flight/OSD/System/osd.c b/flight/targets/OSD/System/osd.c similarity index 100% rename from flight/OSD/System/osd.c rename to flight/targets/OSD/System/osd.c diff --git a/flight/OSD/System/pios_board.c b/flight/targets/OSD/System/pios_board.c similarity index 100% rename from flight/OSD/System/pios_board.c rename to flight/targets/OSD/System/pios_board.c diff --git a/flight/OSD/System/pios_usb_board_data.c b/flight/targets/OSD/System/pios_usb_board_data.c similarity index 100% rename from flight/OSD/System/pios_usb_board_data.c rename to flight/targets/OSD/System/pios_usb_board_data.c diff --git a/flight/PipXtreme/Makefile b/flight/targets/PipXtreme/Makefile similarity index 99% rename from flight/PipXtreme/Makefile rename to flight/targets/PipXtreme/Makefile index 07954d3b2..064997bcb 100644 --- a/flight/PipXtreme/Makefile +++ b/flight/targets/PipXtreme/Makefile @@ -23,7 +23,7 @@ ##### WHEREAMI := $(dir $(lastword $(MAKEFILE_LIST))) -TOP := $(realpath $(WHEREAMI)/../../) +TOP := $(realpath $(WHEREAMI)/../../../) include $(TOP)/make/firmware-defs.mk include $(TOP)/make/boards/$(BOARD_NAME)/board-info.mk @@ -78,16 +78,16 @@ MODULES = Radio RadioComBridge # Paths OPSYSTEM = ./System OPSYSTEMINC = $(OPSYSTEM)/inc -OPUAVTALK = ../UAVTalk +OPUAVTALK = ../../UAVTalk OPUAVTALKINC = $(OPUAVTALK)/inc -OPUAVOBJ = ../UAVObjects +OPUAVOBJ = ../../UAVObjects OPUAVOBJINC = $(OPUAVOBJ)/inc OPTESTS = ./Tests -OPMODULEDIR = ../Modules -FLIGHTLIB = ../Libraries +OPMODULEDIR = ../../Modules +FLIGHTLIB = ../../Libraries FLIGHTLIBINC = $(FLIGHTLIB)/inc RSCODEINC = $(FLIGHTLIB)/rscode -PIOS = ../PiOS +PIOS = ../../PiOS PIOSINC = $(PIOS)/inc PIOSSTM32F10X = $(PIOS)/STM32F10x PIOSCOMMON = $(PIOS)/Common diff --git a/flight/PipXtreme/System/alarms.c b/flight/targets/PipXtreme/System/alarms.c similarity index 100% rename from flight/PipXtreme/System/alarms.c rename to flight/targets/PipXtreme/System/alarms.c diff --git a/flight/PipXtreme/System/inc/FreeRTOSConfig.h b/flight/targets/PipXtreme/System/inc/FreeRTOSConfig.h similarity index 100% rename from flight/PipXtreme/System/inc/FreeRTOSConfig.h rename to flight/targets/PipXtreme/System/inc/FreeRTOSConfig.h diff --git a/flight/PipXtreme/System/inc/alarms.h b/flight/targets/PipXtreme/System/inc/alarms.h similarity index 100% rename from flight/PipXtreme/System/inc/alarms.h rename to flight/targets/PipXtreme/System/inc/alarms.h diff --git a/flight/PipXtreme/System/inc/op_config.h b/flight/targets/PipXtreme/System/inc/op_config.h similarity index 100% rename from flight/PipXtreme/System/inc/op_config.h rename to flight/targets/PipXtreme/System/inc/op_config.h diff --git a/flight/PipXtreme/System/inc/openpilot.h b/flight/targets/PipXtreme/System/inc/openpilot.h similarity index 100% rename from flight/PipXtreme/System/inc/openpilot.h rename to flight/targets/PipXtreme/System/inc/openpilot.h diff --git a/flight/PipXtreme/System/inc/pios_board_posix.h b/flight/targets/PipXtreme/System/inc/pios_board_posix.h similarity index 100% rename from flight/PipXtreme/System/inc/pios_board_posix.h rename to flight/targets/PipXtreme/System/inc/pios_board_posix.h diff --git a/flight/PipXtreme/System/inc/pios_config.h b/flight/targets/PipXtreme/System/inc/pios_config.h similarity index 100% rename from flight/PipXtreme/System/inc/pios_config.h rename to flight/targets/PipXtreme/System/inc/pios_config.h diff --git a/flight/PipXtreme/System/inc/pios_config_posix.h b/flight/targets/PipXtreme/System/inc/pios_config_posix.h similarity index 100% rename from flight/PipXtreme/System/inc/pios_config_posix.h rename to flight/targets/PipXtreme/System/inc/pios_config_posix.h diff --git a/flight/PipXtreme/System/inc/pios_usb_board_data.h b/flight/targets/PipXtreme/System/inc/pios_usb_board_data.h similarity index 100% rename from flight/PipXtreme/System/inc/pios_usb_board_data.h rename to flight/targets/PipXtreme/System/inc/pios_usb_board_data.h diff --git a/flight/PipXtreme/System/pios_board.c b/flight/targets/PipXtreme/System/pios_board.c similarity index 100% rename from flight/PipXtreme/System/pios_board.c rename to flight/targets/PipXtreme/System/pios_board.c diff --git a/flight/PipXtreme/System/pios_board_posix.c b/flight/targets/PipXtreme/System/pios_board_posix.c similarity index 100% rename from flight/PipXtreme/System/pios_board_posix.c rename to flight/targets/PipXtreme/System/pios_board_posix.c diff --git a/flight/PipXtreme/System/pios_usb_board_data.c b/flight/targets/PipXtreme/System/pios_usb_board_data.c similarity index 100% rename from flight/PipXtreme/System/pios_usb_board_data.c rename to flight/targets/PipXtreme/System/pios_usb_board_data.c diff --git a/flight/PipXtreme/System/pipxtreme.c b/flight/targets/PipXtreme/System/pipxtreme.c similarity index 100% rename from flight/PipXtreme/System/pipxtreme.c rename to flight/targets/PipXtreme/System/pipxtreme.c diff --git a/flight/RevoMini/Makefile b/flight/targets/RevoMini/Makefile similarity index 98% rename from flight/RevoMini/Makefile rename to flight/targets/RevoMini/Makefile index f3960411e..46c8006bb 100644 --- a/flight/RevoMini/Makefile +++ b/flight/targets/RevoMini/Makefile @@ -23,7 +23,7 @@ ##### WHEREAMI := $(dir $(lastword $(MAKEFILE_LIST))) -TOP := $(realpath $(WHEREAMI)/../../) +TOP := $(realpath $(WHEREAMI)/../../../) include $(TOP)/make/firmware-defs.mk include $(TOP)/make/boards/$(BOARD_NAME)/board-info.mk @@ -68,17 +68,17 @@ PYMODULES = # Paths OPSYSTEM = ./System OPSYSTEMINC = $(OPSYSTEM)/inc -OPUAVTALK = ../UAVTalk +OPUAVTALK = ../../UAVTalk OPUAVTALKINC = $(OPUAVTALK)/inc -OPUAVOBJ = ../UAVObjects +OPUAVOBJ = ../../UAVObjects OPUAVOBJINC = $(OPUAVOBJ)/inc -PIOS = ../PiOS +PIOS = ../../PiOS PIOSINC = $(PIOS)/inc -OPMODULEDIR = ../Modules -FLIGHTLIB = ../Libraries -FLIGHTLIBINC = ../Libraries/inc -MATHLIB = ../Libraries/math -MATHLIBINC = ../Libraries/math +OPMODULEDIR = ../../Modules +FLIGHTLIB = ../../Libraries +FLIGHTLIBINC = $(FLIGHTLIB)/inc +MATHLIB = $(FLIGHTLIB)/math +MATHLIBINC = $(FLIGHTLIB)/math RSCODE = $(FLIGHTLIB)/rscode RSCODEINC = $(FLIGHTLIB)/rscode PIOSSTM32F4XX = $(PIOS)/STM32F4xx @@ -90,7 +90,7 @@ STMLIBDIR = $(APPLIBDIR) STMSPDDIR = $(STMLIBDIR)/STM32F4xx_StdPeriph_Driver STMSPDSRCDIR = $(STMSPDDIR)/src STMSPDINCDIR = $(STMSPDDIR)/inc -OPUAVOBJ = ../UAVObjects +OPUAVOBJ = ../../UAVObjects OPUAVOBJINC = $(OPUAVOBJ)/inc PYMITE = $(FLIGHTLIB)/PyMite PYMITELIB = $(PYMITE)/lib diff --git a/flight/RevoMini/Makefile.osx b/flight/targets/RevoMini/Makefile.osx similarity index 100% rename from flight/RevoMini/Makefile.osx rename to flight/targets/RevoMini/Makefile.osx diff --git a/flight/RevoMini/System/alarms.c b/flight/targets/RevoMini/System/alarms.c similarity index 100% rename from flight/RevoMini/System/alarms.c rename to flight/targets/RevoMini/System/alarms.c diff --git a/flight/RevoMini/System/cm3_fault_handlers.c b/flight/targets/RevoMini/System/cm3_fault_handlers.c similarity index 100% rename from flight/RevoMini/System/cm3_fault_handlers.c rename to flight/targets/RevoMini/System/cm3_fault_handlers.c diff --git a/flight/RevoMini/System/dcc_stdio.c b/flight/targets/RevoMini/System/dcc_stdio.c similarity index 100% rename from flight/RevoMini/System/dcc_stdio.c rename to flight/targets/RevoMini/System/dcc_stdio.c diff --git a/flight/RevoMini/System/inc/FreeRTOSConfig.h b/flight/targets/RevoMini/System/inc/FreeRTOSConfig.h similarity index 100% rename from flight/RevoMini/System/inc/FreeRTOSConfig.h rename to flight/targets/RevoMini/System/inc/FreeRTOSConfig.h diff --git a/flight/RevoMini/System/inc/alarms.h b/flight/targets/RevoMini/System/inc/alarms.h similarity index 100% rename from flight/RevoMini/System/inc/alarms.h rename to flight/targets/RevoMini/System/inc/alarms.h diff --git a/flight/RevoMini/System/inc/dcc_stdio.h b/flight/targets/RevoMini/System/inc/dcc_stdio.h similarity index 100% rename from flight/RevoMini/System/inc/dcc_stdio.h rename to flight/targets/RevoMini/System/inc/dcc_stdio.h diff --git a/flight/RevoMini/System/inc/op_config.h b/flight/targets/RevoMini/System/inc/op_config.h similarity index 100% rename from flight/RevoMini/System/inc/op_config.h rename to flight/targets/RevoMini/System/inc/op_config.h diff --git a/flight/RevoMini/System/inc/openpilot.h b/flight/targets/RevoMini/System/inc/openpilot.h similarity index 100% rename from flight/RevoMini/System/inc/openpilot.h rename to flight/targets/RevoMini/System/inc/openpilot.h diff --git a/flight/RevoMini/System/inc/pios_board_sim.h b/flight/targets/RevoMini/System/inc/pios_board_sim.h similarity index 100% rename from flight/RevoMini/System/inc/pios_board_sim.h rename to flight/targets/RevoMini/System/inc/pios_board_sim.h diff --git a/flight/RevoMini/System/inc/pios_config.h b/flight/targets/RevoMini/System/inc/pios_config.h similarity index 100% rename from flight/RevoMini/System/inc/pios_config.h rename to flight/targets/RevoMini/System/inc/pios_config.h diff --git a/flight/RevoMini/System/inc/pios_config_sim.h b/flight/targets/RevoMini/System/inc/pios_config_sim.h similarity index 100% rename from flight/RevoMini/System/inc/pios_config_sim.h rename to flight/targets/RevoMini/System/inc/pios_config_sim.h diff --git a/flight/RevoMini/System/inc/pios_usb_board_data.h b/flight/targets/RevoMini/System/inc/pios_usb_board_data.h similarity index 100% rename from flight/RevoMini/System/inc/pios_usb_board_data.h rename to flight/targets/RevoMini/System/inc/pios_usb_board_data.h diff --git a/flight/RevoMini/System/pios_board.c b/flight/targets/RevoMini/System/pios_board.c similarity index 100% rename from flight/RevoMini/System/pios_board.c rename to flight/targets/RevoMini/System/pios_board.c diff --git a/flight/RevoMini/System/pios_board_sim.c b/flight/targets/RevoMini/System/pios_board_sim.c similarity index 100% rename from flight/RevoMini/System/pios_board_sim.c rename to flight/targets/RevoMini/System/pios_board_sim.c diff --git a/flight/RevoMini/System/pios_usb_board_data.c b/flight/targets/RevoMini/System/pios_usb_board_data.c similarity index 100% rename from flight/RevoMini/System/pios_usb_board_data.c rename to flight/targets/RevoMini/System/pios_usb_board_data.c diff --git a/flight/RevoMini/System/revolution.c b/flight/targets/RevoMini/System/revolution.c similarity index 100% rename from flight/RevoMini/System/revolution.c rename to flight/targets/RevoMini/System/revolution.c diff --git a/flight/RevoMini/UAVObjects.inc b/flight/targets/RevoMini/UAVObjects.inc similarity index 100% rename from flight/RevoMini/UAVObjects.inc rename to flight/targets/RevoMini/UAVObjects.inc diff --git a/flight/Revolution/Makefile b/flight/targets/Revolution/Makefile similarity index 97% rename from flight/Revolution/Makefile rename to flight/targets/Revolution/Makefile index 452de3053..8bebedc62 100644 --- a/flight/Revolution/Makefile +++ b/flight/targets/Revolution/Makefile @@ -23,7 +23,7 @@ ##### WHEREAMI := $(dir $(lastword $(MAKEFILE_LIST))) -TOP := $(realpath $(WHEREAMI)/../../) +TOP := $(realpath $(WHEREAMI)/../../../) include $(TOP)/make/firmware-defs.mk include $(TOP)/make/boards/$(BOARD_NAME)/board-info.mk @@ -90,17 +90,17 @@ PYMODULES = # Paths OPSYSTEM = ./System OPSYSTEMINC = $(OPSYSTEM)/inc -OPUAVTALK = ../UAVTalk +OPUAVTALK = ../../UAVTalk OPUAVTALKINC = $(OPUAVTALK)/inc -OPUAVOBJ = ../UAVObjects +OPUAVOBJ = ../../UAVObjects OPUAVOBJINC = $(OPUAVOBJ)/inc -PIOS = ../PiOS +PIOS = ../../PiOS PIOSINC = $(PIOS)/inc -OPMODULEDIR = ../Modules -FLIGHTLIB = ../Libraries -FLIGHTLIBINC = ../Libraries/inc -MATHLIB = ../Libraries/math -MATHLIBINC = ../Libraries/math +OPMODULEDIR = ../../Modules +FLIGHTLIB = ../../Libraries +FLIGHTLIBINC = $(FLIGHTLIB)/inc +MATHLIB = $(FLIGHTLIB)/math +MATHLIBINC = $(FLIGHTLIB)/math PIOSSTM32F4XX = $(PIOS)/STM32F4xx PIOSCOMMON = $(PIOS)/Common PIOSBOARDS = $(PIOS)/Boards @@ -110,10 +110,10 @@ STMLIBDIR = $(APPLIBDIR) STMSPDDIR = $(STMLIBDIR)/STM32F4xx_StdPeriph_Driver STMSPDSRCDIR = $(STMSPDDIR)/src STMSPDINCDIR = $(STMSPDDIR)/inc -OPUAVOBJ = ../UAVObjects +OPUAVOBJ = ../../UAVObjects OPUAVOBJINC = $(OPUAVOBJ)/inc -BOOT = ../Bootloaders/INS -BOOTINC = $(BOOT)/inc +#BOOT = ../../Bootloaders/INS +#BOOTINC = $(BOOT)/inc PYMITE = $(FLIGHTLIB)/PyMite PYMITELIB = $(PYMITE)/lib PYMITEPLAT = $(PYMITE)/platform/openpilot diff --git a/flight/Revolution/Makefile.osx b/flight/targets/Revolution/Makefile.osx similarity index 100% rename from flight/Revolution/Makefile.osx rename to flight/targets/Revolution/Makefile.osx diff --git a/flight/Revolution/System/alarms.c b/flight/targets/Revolution/System/alarms.c similarity index 100% rename from flight/Revolution/System/alarms.c rename to flight/targets/Revolution/System/alarms.c diff --git a/flight/Revolution/System/cm3_fault_handlers.c b/flight/targets/Revolution/System/cm3_fault_handlers.c similarity index 100% rename from flight/Revolution/System/cm3_fault_handlers.c rename to flight/targets/Revolution/System/cm3_fault_handlers.c diff --git a/flight/Revolution/System/dcc_stdio.c b/flight/targets/Revolution/System/dcc_stdio.c similarity index 100% rename from flight/Revolution/System/dcc_stdio.c rename to flight/targets/Revolution/System/dcc_stdio.c diff --git a/flight/Revolution/System/inc/FreeRTOSConfig.h b/flight/targets/Revolution/System/inc/FreeRTOSConfig.h similarity index 100% rename from flight/Revolution/System/inc/FreeRTOSConfig.h rename to flight/targets/Revolution/System/inc/FreeRTOSConfig.h diff --git a/flight/Revolution/System/inc/alarms.h b/flight/targets/Revolution/System/inc/alarms.h similarity index 100% rename from flight/Revolution/System/inc/alarms.h rename to flight/targets/Revolution/System/inc/alarms.h diff --git a/flight/Revolution/System/inc/dcc_stdio.h b/flight/targets/Revolution/System/inc/dcc_stdio.h similarity index 100% rename from flight/Revolution/System/inc/dcc_stdio.h rename to flight/targets/Revolution/System/inc/dcc_stdio.h diff --git a/flight/Revolution/System/inc/op_config.h b/flight/targets/Revolution/System/inc/op_config.h similarity index 100% rename from flight/Revolution/System/inc/op_config.h rename to flight/targets/Revolution/System/inc/op_config.h diff --git a/flight/Revolution/System/inc/openpilot.h b/flight/targets/Revolution/System/inc/openpilot.h similarity index 100% rename from flight/Revolution/System/inc/openpilot.h rename to flight/targets/Revolution/System/inc/openpilot.h diff --git a/flight/Revolution/System/inc/pios_board_sim.h b/flight/targets/Revolution/System/inc/pios_board_sim.h similarity index 100% rename from flight/Revolution/System/inc/pios_board_sim.h rename to flight/targets/Revolution/System/inc/pios_board_sim.h diff --git a/flight/Revolution/System/inc/pios_config.h b/flight/targets/Revolution/System/inc/pios_config.h similarity index 100% rename from flight/Revolution/System/inc/pios_config.h rename to flight/targets/Revolution/System/inc/pios_config.h diff --git a/flight/Revolution/System/inc/pios_config_sim.h b/flight/targets/Revolution/System/inc/pios_config_sim.h similarity index 100% rename from flight/Revolution/System/inc/pios_config_sim.h rename to flight/targets/Revolution/System/inc/pios_config_sim.h diff --git a/flight/Revolution/System/inc/pios_usb_board_data.h b/flight/targets/Revolution/System/inc/pios_usb_board_data.h similarity index 100% rename from flight/Revolution/System/inc/pios_usb_board_data.h rename to flight/targets/Revolution/System/inc/pios_usb_board_data.h diff --git a/flight/Revolution/System/pios_board.c b/flight/targets/Revolution/System/pios_board.c similarity index 100% rename from flight/Revolution/System/pios_board.c rename to flight/targets/Revolution/System/pios_board.c diff --git a/flight/Revolution/System/pios_board_sim.c b/flight/targets/Revolution/System/pios_board_sim.c similarity index 100% rename from flight/Revolution/System/pios_board_sim.c rename to flight/targets/Revolution/System/pios_board_sim.c diff --git a/flight/Revolution/System/pios_usb_board_data.c b/flight/targets/Revolution/System/pios_usb_board_data.c similarity index 100% rename from flight/Revolution/System/pios_usb_board_data.c rename to flight/targets/Revolution/System/pios_usb_board_data.c diff --git a/flight/Revolution/System/revolution.c b/flight/targets/Revolution/System/revolution.c similarity index 100% rename from flight/Revolution/System/revolution.c rename to flight/targets/Revolution/System/revolution.c diff --git a/flight/Revolution/UAVObjects.inc b/flight/targets/Revolution/UAVObjects.inc similarity index 100% rename from flight/Revolution/UAVObjects.inc rename to flight/targets/Revolution/UAVObjects.inc diff --git a/flight/SimPosix/Makefile b/flight/targets/SimPosix/Makefile similarity index 98% rename from flight/SimPosix/Makefile rename to flight/targets/SimPosix/Makefile index 3d0e8d710..9e3fc9f60 100644 --- a/flight/SimPosix/Makefile +++ b/flight/targets/SimPosix/Makefile @@ -23,7 +23,7 @@ ##### WHEREAMI := $(dir $(lastword $(MAKEFILE_LIST))) -TOP := $(realpath $(WHEREAMI)/../../) +TOP := $(realpath $(WHEREAMI)/../../../) override TCHAIN_PREFIX := override THUMB := @@ -65,23 +65,23 @@ PYMODULES = # Paths OPSYSTEM = ./System OPSYSTEMINC = $(OPSYSTEM)/inc -OPUAVTALK = ../UAVTalk +OPUAVTALK = ../../UAVTalk OPUAVTALKINC = $(OPUAVTALK)/inc -OPUAVOBJ = ../UAVObjects +OPUAVOBJ = ../../UAVObjects OPUAVOBJINC = $(OPUAVOBJ)/inc -PIOS = ../PiOS.posix +PIOS = ../../PiOS.posix PIOSINC = $(PIOS)/inc -OPMODULEDIR = ../Modules -FLIGHTLIB = ../Libraries -FLIGHTLIBINC = ../Libraries/inc -MATHLIB = ../Libraries/math -MATHLIBINC = ../Libraries/math +OPMODULEDIR = ../../Modules +FLIGHTLIB = ../../Libraries +FLIGHTLIBINC = $(FLIGHTLIB)/inc +MATHLIB = $(FLIGHTLIB)/math +MATHLIBINC = $(FLIGHTLIB)/math PIOSPOSIX = $(PIOS)/posix PIOSCOMMON = $(PIOS)/posix PIOSBOARDS = $(PIOS)/Boards PIOSCOMMONLIB = $(PIOSCOMMON)/Libraries #APPLIBDIR = $(PIOSSTM32F4XX)/Libraries -OPUAVOBJ = ../UAVObjects +OPUAVOBJ = ../../UAVObjects OPUAVOBJINC = $(OPUAVOBJ)/inc BOOT = BOOTINC = diff --git a/flight/SimPosix/System/alarms.c b/flight/targets/SimPosix/System/alarms.c similarity index 100% rename from flight/SimPosix/System/alarms.c rename to flight/targets/SimPosix/System/alarms.c diff --git a/flight/SimPosix/System/inc/FreeRTOSConfig.h b/flight/targets/SimPosix/System/inc/FreeRTOSConfig.h similarity index 100% rename from flight/SimPosix/System/inc/FreeRTOSConfig.h rename to flight/targets/SimPosix/System/inc/FreeRTOSConfig.h diff --git a/flight/SimPosix/System/inc/alarms.h b/flight/targets/SimPosix/System/inc/alarms.h similarity index 100% rename from flight/SimPosix/System/inc/alarms.h rename to flight/targets/SimPosix/System/inc/alarms.h diff --git a/flight/SimPosix/System/inc/dcc_stdio.h b/flight/targets/SimPosix/System/inc/dcc_stdio.h similarity index 100% rename from flight/SimPosix/System/inc/dcc_stdio.h rename to flight/targets/SimPosix/System/inc/dcc_stdio.h diff --git a/flight/SimPosix/System/inc/op_config.h b/flight/targets/SimPosix/System/inc/op_config.h similarity index 100% rename from flight/SimPosix/System/inc/op_config.h rename to flight/targets/SimPosix/System/inc/op_config.h diff --git a/flight/SimPosix/System/inc/openpilot.h b/flight/targets/SimPosix/System/inc/openpilot.h similarity index 100% rename from flight/SimPosix/System/inc/openpilot.h rename to flight/targets/SimPosix/System/inc/openpilot.h diff --git a/flight/SimPosix/System/inc/pios_config.h b/flight/targets/SimPosix/System/inc/pios_config.h similarity index 100% rename from flight/SimPosix/System/inc/pios_config.h rename to flight/targets/SimPosix/System/inc/pios_config.h diff --git a/flight/SimPosix/System/pios_board.c b/flight/targets/SimPosix/System/pios_board.c similarity index 100% rename from flight/SimPosix/System/pios_board.c rename to flight/targets/SimPosix/System/pios_board.c diff --git a/flight/SimPosix/System/simposix.c b/flight/targets/SimPosix/System/simposix.c similarity index 100% rename from flight/SimPosix/System/simposix.c rename to flight/targets/SimPosix/System/simposix.c diff --git a/flight/SimPosix/UAVObjects.inc b/flight/targets/SimPosix/UAVObjects.inc similarity index 100% rename from flight/SimPosix/UAVObjects.inc rename to flight/targets/SimPosix/UAVObjects.inc diff --git a/flight/board_hw_defs/coptercontrol/board_hw_defs.c b/flight/targets/board_hw_defs/coptercontrol/board_hw_defs.c similarity index 100% rename from flight/board_hw_defs/coptercontrol/board_hw_defs.c rename to flight/targets/board_hw_defs/coptercontrol/board_hw_defs.c diff --git a/flight/board_hw_defs/osd/board_hw_defs.c b/flight/targets/board_hw_defs/osd/board_hw_defs.c similarity index 100% rename from flight/board_hw_defs/osd/board_hw_defs.c rename to flight/targets/board_hw_defs/osd/board_hw_defs.c diff --git a/flight/board_hw_defs/pipxtreme/board_hw_defs.c b/flight/targets/board_hw_defs/pipxtreme/board_hw_defs.c similarity index 100% rename from flight/board_hw_defs/pipxtreme/board_hw_defs.c rename to flight/targets/board_hw_defs/pipxtreme/board_hw_defs.c diff --git a/flight/board_hw_defs/revolution/board_hw_defs.c b/flight/targets/board_hw_defs/revolution/board_hw_defs.c similarity index 100% rename from flight/board_hw_defs/revolution/board_hw_defs.c rename to flight/targets/board_hw_defs/revolution/board_hw_defs.c diff --git a/flight/board_hw_defs/revomini/board_hw_defs.c b/flight/targets/board_hw_defs/revomini/board_hw_defs.c similarity index 100% rename from flight/board_hw_defs/revomini/board_hw_defs.c rename to flight/targets/board_hw_defs/revomini/board_hw_defs.c diff --git a/flight/board_hw_defs/simposix/board_hw_defs.c b/flight/targets/board_hw_defs/simposix/board_hw_defs.c similarity index 100% rename from flight/board_hw_defs/simposix/board_hw_defs.c rename to flight/targets/board_hw_defs/simposix/board_hw_defs.c From 833b730870c2b49e0bdec999d37cb923a6a80da9 Mon Sep 17 00:00:00 2001 From: Stacey Sheldon Date: Tue, 27 Nov 2012 01:26:42 -0500 Subject: [PATCH 22/30] makefile: remove duplicate definitions --- Makefile | 6 ------ 1 file changed, 6 deletions(-) diff --git a/Makefile b/Makefile index ee03ff066..37748834b 100644 --- a/Makefile +++ b/Makefile @@ -905,12 +905,6 @@ BL_BOARDS := $(filter-out simposix, $(BL_BOARDS)) BU_BOARDS := $(filter-out simposix, $(BU_BOARDS)) EF_BOARDS := $(filter-out simposix, $(EF_BOARDS)) -# SimPosix doesn't have a BL, BU or EF target so we need to -# filter them out to prevent errors on the all_flight target. -BL_BOARDS := $(filter-out simposix, $(BL_BOARDS)) -BU_BOARDS := $(filter-out simposix, $(BU_BOARDS)) -EF_BOARDS := $(filter-out simposix, $(EF_BOARDS)) - # Generate the targets for whatever boards are left in each list FW_TARGETS := $(addprefix fw_, $(FW_BOARDS)) BL_TARGETS := $(addprefix bl_, $(BL_BOARDS)) From dbcf440bb944331860525bfbe23fcb8d5c23ce57 Mon Sep 17 00:00:00 2001 From: Stacey Sheldon Date: Tue, 27 Nov 2012 22:32:51 -0500 Subject: [PATCH 23/30] makefile: factor out paths for major flight components Conflicts: flight/targets/CopterControl/Makefile --- Makefile | 54 +++++++++++++++++++ .../Bootloaders/BootloaderUpdater/Makefile | 9 ---- .../Bootloaders/CopterControl/Makefile | 10 ---- flight/targets/Bootloaders/OSD/Makefile | 9 ---- flight/targets/Bootloaders/PipXtreme/Makefile | 10 ---- flight/targets/Bootloaders/RevoMini/Makefile | 9 ---- .../targets/Bootloaders/Revolution/Makefile | 9 ---- flight/targets/CopterControl/Makefile | 20 +------ flight/targets/EntireFlash/Makefile | 6 --- flight/targets/OSD/Makefile | 19 ------- flight/targets/PipXtreme/Makefile | 18 ------- flight/targets/RevoMini/Makefile | 14 ----- flight/targets/RevoMini/UAVObjects.inc | 2 +- flight/targets/Revolution/Makefile | 20 +------ flight/targets/Revolution/UAVObjects.inc | 2 +- 15 files changed, 59 insertions(+), 152 deletions(-) diff --git a/Makefile b/Makefile index 37748834b..495937046 100644 --- a/Makefile +++ b/Makefile @@ -727,6 +727,17 @@ uavo-collections_clean: # ############################## +# Define some pointers to the various important pieces of the flight code +# to prevent these being repeated in every sub makefile +PIOS := $(ROOT_DIR)/flight/PiOS +FLIGHTLIB := $(ROOT_DIR)/flight/Libraries +OPMODULEDIR := $(ROOT_DIR)/flight/Modules +OPUAVOBJ := $(ROOT_DIR)/flight/UAVObjects +OPUAVTALK := $(ROOT_DIR)/flight/UAVTalk +HWDEFS := $(ROOT_DIR)/flight/targets/board_hw_defs +DOXYGENDIR := $(ROOT_DIR)/flight/Doc/Doxygen +OPUAVSYNTHDIR := $(BUILD_DIR)/uavobject-synthetics/flight + # $(1) = Canonical board name all in lower case (e.g. coptercontrol) # $(2) = Name of board used in source tree (e.g. CopterControl) # $(3) = Short name for board (e.g CC) @@ -744,6 +755,19 @@ fw_$(1)_%: uavobjects_flight BUILD_TYPE=fw \ TCHAIN_PREFIX="$(ARM_SDK_PREFIX)" \ REMOVE_CMD="$(RM)" OOCD_EXE="$(OPENOCD)" \ + \ + TARGET=fw_$(1) \ + OUTDIR=$(BUILD_DIR)/fw_$(1) \ + \ + PIOS=$(PIOS) \ + FLIGHTLIB=$(FLIGHTLIB) \ + OPMODULEDIR=$(OPMODULEDIR) \ + OPUAVOBJ=$(OPUAVOBJ) \ + OPUAVTALK=$(OPUAVTALK) \ + HWDEFSINC=$(HWDEFS)/$(1) \ + DOXYGENDIR=$(DOXYGENDIR) \ + OPUAVSYNTHDIR=$(OPUAVSYNTHDIR) \ + \ $$* .PHONY: $(1)_clean @@ -769,6 +793,19 @@ bl_$(1)_%: BUILD_TYPE=bl \ TCHAIN_PREFIX="$(ARM_SDK_PREFIX)" \ REMOVE_CMD="$(RM)" OOCD_EXE="$(OPENOCD)" \ + \ + TARGET=bl_$(1) \ + OUTDIR=$(BUILD_DIR)/bl_$(1) \ + \ + PIOS=$(PIOS) \ + FLIGHTLIB=$(FLIGHTLIB) \ + OPMODULEDIR=$(OPMODULEDIR) \ + OPUAVOBJ=$(OPUAVOBJ) \ + OPUAVTALK=$(OPUAVTALK) \ + HWDEFSINC=$(HWDEFS)/$(1) \ + OPUAVSYNTHDIR=$(OPUAVSYNTHDIR) \ + DOXYGENDIR=$(DOXYGENDIR) \ + \ $$* .PHONY: unbrick_$(1) @@ -805,6 +842,19 @@ bu_$(1)_%: bl_$(1)_bino BUILD_TYPE=bu \ TCHAIN_PREFIX="$(ARM_SDK_PREFIX)" \ REMOVE_CMD="$(RM)" OOCD_EXE="$(OPENOCD)" \ + \ + TARGET=bu_$(1) \ + OUTDIR=$(BUILD_DIR)/bu_$(1) \ + \ + PIOS=$(PIOS) \ + FLIGHTLIB=$(FLIGHTLIB) \ + OPMODULEDIR=$(OPMODULEDIR) \ + OPUAVOBJ=$(OPUAVOBJ) \ + OPUAVTALK=$(OPUAVTALK) \ + HWDEFSINC=$(HWDEFS)/$(1) \ + OPUAVSYNTHDIR=$(OPUAVSYNTHDIR) \ + DOXYGENDIR=$(DOXYGENDIR) \ + \ $$* .PHONY: bu_$(1)_clean @@ -827,6 +877,10 @@ ef_$(1)_%: bl_$(1)_bin fw_$(1)_opfw BUILD_TYPE=ef \ TCHAIN_PREFIX="$(ARM_SDK_PREFIX)" \ DFU_CMD="$(DFUUTIL_DIR)/bin/dfu-util" \ + \ + TARGET=ef_$(1) \ + OUTDIR=$(BUILD_DIR)/ef_$(1) \ + \ $$* .PHONY: ef_$(1)_clean diff --git a/flight/targets/Bootloaders/BootloaderUpdater/Makefile b/flight/targets/Bootloaders/BootloaderUpdater/Makefile index 9dbbd6ae0..ed1e9a871 100644 --- a/flight/targets/Bootloaders/BootloaderUpdater/Makefile +++ b/flight/targets/Bootloaders/BootloaderUpdater/Makefile @@ -27,12 +27,6 @@ TOP := $(realpath $(WHEREAMI)/../../../../) include $(TOP)/make/firmware-defs.mk include $(TOP)/make/boards/$(BOARD_NAME)/board-info.mk -# Target file name (without extension). -TARGET = bu_$(BOARD_NAME) - -# Directory for output files (lst, obj, dep, elf, sym, map, hex, bin etc.) -OUTDIR := $(TOP)/build/$(TARGET) - # Set developer code and compile options # Set to YES to compile for debugging DEBUG ?= NO @@ -61,7 +55,6 @@ FLASH_TOOL = OPENOCD # Paths OPSYSTEM = . OPSYSTEMINC = $(OPSYSTEM)/inc -PIOS = ../../../PiOS PIOSINC = $(PIOS)/inc PIOSSTM32F10X = $(PIOS)/STM32F10x PIOSCOMMON = $(PIOS)/Common @@ -80,8 +73,6 @@ MSDDIR = $(APPLIBDIR)/msd RTOSDIR = $(APPLIBDIR)/FreeRTOS RTOSSRCDIR = $(RTOSDIR)/Source RTOSINCDIR = $(RTOSSRCDIR)/include -DOXYGENDIR = ../Doc/Doxygen -HWDEFSINC = $(TOP)/flight/targets/board_hw_defs/$(BOARD_NAME) # List C source files here. (C dependencies are automatically generated.) # use file-extension c for "c-only"-files diff --git a/flight/targets/Bootloaders/CopterControl/Makefile b/flight/targets/Bootloaders/CopterControl/Makefile index c8b017285..30084ad20 100644 --- a/flight/targets/Bootloaders/CopterControl/Makefile +++ b/flight/targets/Bootloaders/CopterControl/Makefile @@ -27,12 +27,6 @@ TOP := $(realpath $(WHEREAMI)/../../../../) include $(TOP)/make/firmware-defs.mk include $(TOP)/make/boards/$(BOARD_NAME)/board-info.mk -# Target file name (without extension). -TARGET := bl_$(BOARD_NAME) - -# Directory for output files (lst, obj, dep, elf, sym, map, hex, bin etc.) -OUTDIR := $(TOP)/build/$(TARGET) - # Set developer code and compile options # Set to YES to compile for debugging DEBUG ?= NO @@ -58,9 +52,7 @@ FLASH_TOOL = OPENOCD # Paths OPSYSTEM = . OPSYSTEMINC = $(OPSYSTEM)/inc -FLIGHTLIB = ../../../Libraries FLIGHTLIBINC = $(FLIGHTLIB)/inc -PIOS = ../../../PiOS PIOSINC = $(PIOS)/inc PIOSSTM32F10X = $(PIOS)/STM32F10x PIOSCOMMON = $(PIOS)/Common @@ -79,8 +71,6 @@ MSDDIR = $(APPLIBDIR)/msd RTOSDIR = $(APPLIBDIR)/FreeRTOS RTOSSRCDIR = $(RTOSDIR)/Source RTOSINCDIR = $(RTOSSRCDIR)/include -DOXYGENDIR = ../Doc/Doxygen -HWDEFSINC = ../../board_hw_defs/$(BOARD_NAME) # List C source files here. (C dependencies are automatically generated.) # use file-extension c for "c-only"-files diff --git a/flight/targets/Bootloaders/OSD/Makefile b/flight/targets/Bootloaders/OSD/Makefile index 5705adf61..190dcd047 100644 --- a/flight/targets/Bootloaders/OSD/Makefile +++ b/flight/targets/Bootloaders/OSD/Makefile @@ -27,12 +27,6 @@ TOP := $(realpath $(WHEREAMI)/../../../../) include $(TOP)/make/firmware-defs.mk include $(TOP)/make/boards/$(BOARD_NAME)/board-info.mk -# Target file name (without extension). -TARGET := bl_$(BOARD_NAME) - -# Directory for output files (lst, obj, dep, elf, sym, map, hex, bin etc.) -OUTDIR := $(TOP)/build/$(TARGET) - # Set developer code and compile options # Set to YES for debugging DEBUG ?= NO @@ -49,9 +43,7 @@ endif # Paths OSD_BL = $(WHEREAMI) OSD_BLINC = $(OSD_BL)/inc -PIOS = ../../../PiOS PIOSINC = $(PIOS)/inc -FLIGHTLIB = ../../../Libraries FLIGHTLIBINC = $(FLIGHTLIB)/inc PIOSSTM32F4XX = $(PIOS)/STM32F4xx PIOSCOMMON = $(PIOS)/Common @@ -62,7 +54,6 @@ STMLIBDIR = $(APPLIBDIR) STMSPDDIR = $(STMLIBDIR)/STM32F4xx_StdPeriph_Driver STMSPDSRCDIR = $(STMSPDDIR)/src STMSPDINCDIR = $(STMSPDDIR)/inc -HWDEFSINC = ../../board_hw_defs/$(BOARD_NAME) # List C source files here. (C dependencies are automatically generated.) # use file-extension c for "c-only"-files diff --git a/flight/targets/Bootloaders/PipXtreme/Makefile b/flight/targets/Bootloaders/PipXtreme/Makefile index 8cd3af69e..373efe5ef 100644 --- a/flight/targets/Bootloaders/PipXtreme/Makefile +++ b/flight/targets/Bootloaders/PipXtreme/Makefile @@ -27,12 +27,6 @@ TOP := $(realpath $(WHEREAMI)/../../../../) include $(TOP)/make/firmware-defs.mk include $(TOP)/make/boards/$(BOARD_NAME)/board-info.mk -# Target file name (without extension). -TARGET := bl_$(BOARD_NAME) - -# Directory for output files (lst, obj, dep, elf, sym, map, hex, bin etc.) -OUTDIR := $(TOP)/build/$(TARGET) - # Set developer code and compile options # Set to YES to compile for debugging DEBUG ?= NO @@ -58,9 +52,7 @@ FLASH_TOOL = OPENOCD # Paths OPSYSTEM = . OPSYSTEMINC = $(OPSYSTEM)/inc -FLIGHTLIB = ../../../Libraries FLIGHTLIBINC = $(FLIGHTLIB)/inc -PIOS = ../../../PiOS PIOSINC = $(PIOS)/inc PIOSSTM32F10X = $(PIOS)/STM32F10x PIOSCOMMON = $(PIOS)/Common @@ -79,8 +71,6 @@ MSDDIR = $(APPLIBDIR)/msd RTOSDIR = $(APPLIBDIR)/FreeRTOS RTOSSRCDIR = $(RTOSDIR)/Source RTOSINCDIR = $(RTOSSRCDIR)/include -DOXYGENDIR = ../Doc/Doxygen -HWDEFSINC = ../../board_hw_defs/$(BOARD_NAME) # List C source files here. (C dependencies are automatically generated.) # use file-extension c for "c-only"-files diff --git a/flight/targets/Bootloaders/RevoMini/Makefile b/flight/targets/Bootloaders/RevoMini/Makefile index 142daa56e..4f4fb1a2e 100644 --- a/flight/targets/Bootloaders/RevoMini/Makefile +++ b/flight/targets/Bootloaders/RevoMini/Makefile @@ -27,12 +27,6 @@ TOP := $(realpath $(WHEREAMI)/../../../../) include $(TOP)/make/firmware-defs.mk include $(TOP)/make/boards/$(BOARD_NAME)/board-info.mk -# Target file name (without extension). -TARGET := bl_$(BOARD_NAME) - -# Directory for output files (lst, obj, dep, elf, sym, map, hex, bin etc.) -OUTDIR := $(TOP)/build/$(TARGET) - # Set developer code and compile options # Set to YES for debugging DEBUG ?= NO @@ -49,9 +43,7 @@ endif # Paths REVO_BL = $(WHEREAMI) REVO_BLINC = $(REVO_BL)/inc -PIOS = ../../../PiOS PIOSINC = $(PIOS)/inc -FLIGHTLIB = ../../../Libraries FLIGHTLIBINC = $(FLIGHTLIB)/inc PIOSSTM32F4XX = $(PIOS)/STM32F4xx PIOSCOMMON = $(PIOS)/Common @@ -62,7 +54,6 @@ STMLIBDIR = $(APPLIBDIR) STMSPDDIR = $(STMLIBDIR)/STM32F4xx_StdPeriph_Driver STMSPDSRCDIR = $(STMSPDDIR)/src STMSPDINCDIR = $(STMSPDDIR)/inc -HWDEFSINC = ../../board_hw_defs/$(BOARD_NAME) # List C source files here. (C dependencies are automatically generated.) # use file-extension c for "c-only"-files diff --git a/flight/targets/Bootloaders/Revolution/Makefile b/flight/targets/Bootloaders/Revolution/Makefile index 142daa56e..4f4fb1a2e 100644 --- a/flight/targets/Bootloaders/Revolution/Makefile +++ b/flight/targets/Bootloaders/Revolution/Makefile @@ -27,12 +27,6 @@ TOP := $(realpath $(WHEREAMI)/../../../../) include $(TOP)/make/firmware-defs.mk include $(TOP)/make/boards/$(BOARD_NAME)/board-info.mk -# Target file name (without extension). -TARGET := bl_$(BOARD_NAME) - -# Directory for output files (lst, obj, dep, elf, sym, map, hex, bin etc.) -OUTDIR := $(TOP)/build/$(TARGET) - # Set developer code and compile options # Set to YES for debugging DEBUG ?= NO @@ -49,9 +43,7 @@ endif # Paths REVO_BL = $(WHEREAMI) REVO_BLINC = $(REVO_BL)/inc -PIOS = ../../../PiOS PIOSINC = $(PIOS)/inc -FLIGHTLIB = ../../../Libraries FLIGHTLIBINC = $(FLIGHTLIB)/inc PIOSSTM32F4XX = $(PIOS)/STM32F4xx PIOSCOMMON = $(PIOS)/Common @@ -62,7 +54,6 @@ STMLIBDIR = $(APPLIBDIR) STMSPDDIR = $(STMLIBDIR)/STM32F4xx_StdPeriph_Driver STMSPDSRCDIR = $(STMSPDDIR)/src STMSPDINCDIR = $(STMSPDDIR)/inc -HWDEFSINC = ../../board_hw_defs/$(BOARD_NAME) # List C source files here. (C dependencies are automatically generated.) # use file-extension c for "c-only"-files diff --git a/flight/targets/CopterControl/Makefile b/flight/targets/CopterControl/Makefile index a6c39b7c3..f90155771 100644 --- a/flight/targets/CopterControl/Makefile +++ b/flight/targets/CopterControl/Makefile @@ -27,12 +27,6 @@ TOP := $(realpath $(WHEREAMI)/../../../) include $(TOP)/make/firmware-defs.mk include $(TOP)/make/boards/$(BOARD_NAME)/board-info.mk -# Target file name (without extension). -TARGET := fw_$(BOARD_NAME) - -# Directory for output files (lst, obj, dep, elf, sym, map, hex, bin etc.) -OUTDIR := $(TOP)/build/$(TARGET) - # Set developer code and compile options # Set to YES to compile for debugging DEBUG ?= NO @@ -118,17 +112,12 @@ MODULES += Telemetry # Paths OPSYSTEM = ./System OPSYSTEMINC = $(OPSYSTEM)/inc -OPUAVTALK = ../../UAVTalk OPUAVTALKINC = $(OPUAVTALK)/inc -OPUAVOBJ = ../../UAVObjects OPUAVOBJINC = $(OPUAVOBJ)/inc OPTESTS = ./Tests -OPMODULEDIR = ../../Modules -FLIGHTLIB = ../../Libraries FLIGHTLIBINC = $(FLIGHTLIB)/inc -MATHLIB = ../../Libraries/math -MATHLIBINC = ../../Libraries/math -PIOS = ../../PiOS +MATHLIB = $(FLIGHTLIB)/math +MATHLIBINC = $(FLIGHTLIB)/math PIOSINC = $(PIOS)/inc PIOSSTM32F10X = $(PIOS)/STM32F10x PIOSCOMMON = $(PIOS)/Common @@ -149,8 +138,6 @@ RTOSSRCDIR = $(RTOSDIR)/Source RTOSINCDIR = $(RTOSSRCDIR)/include RTOSPORTDIR = $(APPLIBDIR)/FreeRTOS/Source DOXYGENDIR = ../Doc/Doxygen -AHRSBOOTLOADER = ../Bootloaders/AHRS/ -AHRSBOOTLOADERINC = $(AHRSBOOTLOADER)/inc PYMITE = $(FLIGHTLIB)/PyMite PYMITELIB = $(PYMITE)/lib PYMITEPLAT = $(PYMITE)/platform/openpilot @@ -161,9 +148,6 @@ PYMITEINC += $(PYMITEPLAT) PYMITEINC += $(OUTDIR) FLIGHTPLANLIB = $(OPMODULEDIR)/FlightPlan/lib FLIGHTPLANS = $(OPMODULEDIR)/FlightPlan/flightplans -HWDEFSINC = ../board_hw_defs/$(BOARD_NAME) - -OPUAVSYNTHDIR = $(OUTDIR)/../uavobject-synthetics/flight # List C source files here. (C dependencies are automatically generated.) # use file-extension c for "c-only"-files diff --git a/flight/targets/EntireFlash/Makefile b/flight/targets/EntireFlash/Makefile index 9d18979dd..24d86a92d 100644 --- a/flight/targets/EntireFlash/Makefile +++ b/flight/targets/EntireFlash/Makefile @@ -24,12 +24,6 @@ TOP := $(realpath $(WHEREAMI)/../../../) include $(TOP)/make/firmware-defs.mk include $(TOP)/make/boards/$(BOARD_NAME)/board-info.mk -# Target file name (without extension). -TARGET := ef_$(BOARD_NAME) - -# Directory for output files (lst, obj, dep, elf, sym, map, hex, bin etc.) -OUTDIR := $(TOP)/build/$(TARGET) - .PHONY: bin bin: $(OUTDIR)/$(TARGET).bin diff --git a/flight/targets/OSD/Makefile b/flight/targets/OSD/Makefile index 4bc4309ba..2c15a4be2 100644 --- a/flight/targets/OSD/Makefile +++ b/flight/targets/OSD/Makefile @@ -27,12 +27,6 @@ TOP := $(realpath $(WHEREAMI)/../../../) include $(TOP)/make/firmware-defs.mk include $(TOP)/make/boards/$(BOARD_NAME)/board-info.mk -# Target file name (without extension). -TARGET := fw_$(BOARD_NAME) - -# Directory for output files (lst, obj, dep, elf, sym, map, hex, bin etc.) -OUTDIR := $(TOP)/build/$(TARGET) - # Set developer code and compile options # Set to YES for debugging DEBUG ?= NO @@ -102,12 +96,8 @@ MODULES += FirmwareIAP # Paths OPSYSTEM = ./System OPSYSTEMINC = $(OPSYSTEM)/inc -OPUAVTALK = ../../UAVTalk OPUAVTALKINC = $(OPUAVTALK)/inc -OPMODULEDIR = ../../Modules -PIOS = ../../PiOS PIOSINC = $(PIOS)/inc -FLIGHTLIB = ../../Libraries FLIGHTLIBINC = $(FLIGHTLIB)/inc PIOSSTM32F4XX = $(PIOS)/STM32F4xx PIOSCOMMON = $(PIOS)/Common @@ -124,15 +114,7 @@ CMSISDIR = $(STMLIBDIR)/CMSIS/Core/CM3 RTOSDIR = $(PIOSCOMMONLIB)/FreeRTOS RTOSSRCDIR = $(RTOSDIR)/Source RTOSINCDIR = $(RTOSSRCDIR)/include -OPDIR = ../OSD -OPUAVOBJ = ../../UAVObjects OPUAVOBJINC = $(OPUAVOBJ)/inc -OPSYSINC = $(OPDIR)/System/inc -BOOT = ../Bootloaders/OSD -BOOTINC = $(BOOT)/inc -HWDEFSINC = ../board_hw_defs/$(BOARD_NAME) - -OPUAVSYNTHDIR = $(OUTDIR)/../uavobject-synthetics/flight # List C source files here. (C dependencies are automatically generated.) # use file-extension c for "c-only"-files @@ -274,7 +256,6 @@ EXTRAINCDIRS += $(RTOSINCDIR) EXTRAINCDIRS += $(APPLIBDIR) EXTRAINCDIRS += $(RTOSSRCDIR)/portable/GCC/ARM_CM3 EXTRAINCDIRS += $(OPUAVSYNTHDIR) -EXTRAINCDIRS += $(BOOTINC) EXTRAINCDIRS += $(HWDEFSINC) EXTRAINCDIRS += ${foreach MOD, ${OPTMODULES} ${MODULES}, ${OPMODULEDIR}/${MOD}/inc} ${OPMODULEDIR}/System/inc diff --git a/flight/targets/PipXtreme/Makefile b/flight/targets/PipXtreme/Makefile index 064997bcb..1ffcb438d 100644 --- a/flight/targets/PipXtreme/Makefile +++ b/flight/targets/PipXtreme/Makefile @@ -27,12 +27,6 @@ TOP := $(realpath $(WHEREAMI)/../../../) include $(TOP)/make/firmware-defs.mk include $(TOP)/make/boards/$(BOARD_NAME)/board-info.mk -# Target file name (without extension). -TARGET := fw_$(BOARD_NAME) - -# Directory for output files (lst, obj, dep, elf, sym, map, hex, bin etc.) -OUTDIR := $(TOP)/build/$(TARGET) - # Set developer code and compile options # Set to YES to compile for debugging DEBUG ?= NO @@ -78,16 +72,11 @@ MODULES = Radio RadioComBridge # Paths OPSYSTEM = ./System OPSYSTEMINC = $(OPSYSTEM)/inc -OPUAVTALK = ../../UAVTalk OPUAVTALKINC = $(OPUAVTALK)/inc -OPUAVOBJ = ../../UAVObjects OPUAVOBJINC = $(OPUAVOBJ)/inc OPTESTS = ./Tests -OPMODULEDIR = ../../Modules -FLIGHTLIB = ../../Libraries FLIGHTLIBINC = $(FLIGHTLIB)/inc RSCODEINC = $(FLIGHTLIB)/rscode -PIOS = ../../PiOS PIOSINC = $(PIOS)/inc PIOSSTM32F10X = $(PIOS)/STM32F10x PIOSCOMMON = $(PIOS)/Common @@ -107,9 +96,6 @@ RTOSDIR = $(PIOSCOMMON)/Libraries/FreeRTOS RTOSSRCDIR = $(RTOSDIR)/Source RTOSINCDIR = $(RTOSSRCDIR)/include RTOSPORTDIR = $(APPLIBDIR)/FreeRTOS/Source -DOXYGENDIR = ../Doc/Doxygen -AHRSBOOTLOADER = ../Bootloaders/AHRS/ -AHRSBOOTLOADERINC = $(AHRSBOOTLOADER)/inc PYMITE = $(FLIGHTLIB)/PyMite PYMITELIB = $(PYMITE)/lib PYMITEPLAT = $(PYMITE)/platform/openpilot @@ -120,9 +106,6 @@ PYMITEINC += $(PYMITEPLAT) PYMITEINC += $(OUTDIR) FLIGHTPLANLIB = $(OPMODULEDIR)/FlightPlan/lib FLIGHTPLANS = $(OPMODULEDIR)/FlightPlan/flightplans -HWDEFSINC = ../board_hw_defs/$(BOARD_NAME) - -OPUAVSYNTHDIR = $(OUTDIR)/../uavobject-synthetics/flight # List C source files here. (C dependencies are automatically generated.) # use file-extension c for "c-only"-files @@ -290,7 +273,6 @@ EXTRAINCDIRS += $(MSDDIR) EXTRAINCDIRS += $(RTOSINCDIR) EXTRAINCDIRS += $(APPLIBDIR) EXTRAINCDIRS += $(RTOSPORTDIR)/portable/GCC/ARM_CM3 -EXTRAINCDIRS += $(AHRSBOOTLOADERINC) EXTRAINCDIRS += $(PYMITEINC) EXTRAINCDIRS += $(HWDEFSINC) diff --git a/flight/targets/RevoMini/Makefile b/flight/targets/RevoMini/Makefile index 46c8006bb..398573fbc 100644 --- a/flight/targets/RevoMini/Makefile +++ b/flight/targets/RevoMini/Makefile @@ -27,12 +27,6 @@ TOP := $(realpath $(WHEREAMI)/../../../) include $(TOP)/make/firmware-defs.mk include $(TOP)/make/boards/$(BOARD_NAME)/board-info.mk -# Target file name (without extension). -TARGET := fw_$(BOARD_NAME) - -# Directory for output files (lst, obj, dep, elf, sym, map, hex, bin etc.) -OUTDIR := $(TOP)/build/$(TARGET) - # Set developer code and compile options # Set to YES for debugging DEBUG ?= NO @@ -68,14 +62,9 @@ PYMODULES = # Paths OPSYSTEM = ./System OPSYSTEMINC = $(OPSYSTEM)/inc -OPUAVTALK = ../../UAVTalk OPUAVTALKINC = $(OPUAVTALK)/inc -OPUAVOBJ = ../../UAVObjects OPUAVOBJINC = $(OPUAVOBJ)/inc -PIOS = ../../PiOS PIOSINC = $(PIOS)/inc -OPMODULEDIR = ../../Modules -FLIGHTLIB = ../../Libraries FLIGHTLIBINC = $(FLIGHTLIB)/inc MATHLIB = $(FLIGHTLIB)/math MATHLIBINC = $(FLIGHTLIB)/math @@ -90,7 +79,6 @@ STMLIBDIR = $(APPLIBDIR) STMSPDDIR = $(STMLIBDIR)/STM32F4xx_StdPeriph_Driver STMSPDSRCDIR = $(STMSPDDIR)/src STMSPDINCDIR = $(STMSPDDIR)/inc -OPUAVOBJ = ../../UAVObjects OPUAVOBJINC = $(OPUAVOBJ)/inc PYMITE = $(FLIGHTLIB)/PyMite PYMITELIB = $(PYMITE)/lib @@ -102,8 +90,6 @@ PYMITEINC += $(PYMITEPLAT) PYMITEINC += $(OUTDIR) FLIGHTPLANLIB = $(OPMODULEDIR)/FlightPlan/lib FLIGHTPLANS = $(OPMODULEDIR)/FlightPlan/flightplans -HWDEFSINC = ../board_hw_defs/$(BOARD_NAME) -UAVOBJSYNTHDIR = $(OUTDIR)/../uavobject-synthetics/flight SRC = # optional component libraries diff --git a/flight/targets/RevoMini/UAVObjects.inc b/flight/targets/RevoMini/UAVObjects.inc index 468d40d75..e0034e5aa 100644 --- a/flight/targets/RevoMini/UAVObjects.inc +++ b/flight/targets/RevoMini/UAVObjects.inc @@ -103,5 +103,5 @@ UAVOBJSRCFILENAMES += pipxsettings -UAVOBJSRC = $(foreach UAVOBJSRCFILE,$(UAVOBJSRCFILENAMES),$(UAVOBJSYNTHDIR)/$(UAVOBJSRCFILE).c ) +UAVOBJSRC = $(foreach UAVOBJSRCFILE,$(UAVOBJSRCFILENAMES),$(OPUAVSYNTHDIR)/$(UAVOBJSRCFILE).c ) UAVOBJDEFINE = $(foreach UAVOBJSRCFILE,$(UAVOBJSRCFILENAMES),-DUAVOBJ_INIT_$(UAVOBJSRCFILE) ) diff --git a/flight/targets/Revolution/Makefile b/flight/targets/Revolution/Makefile index 8bebedc62..59b179144 100644 --- a/flight/targets/Revolution/Makefile +++ b/flight/targets/Revolution/Makefile @@ -27,12 +27,6 @@ TOP := $(realpath $(WHEREAMI)/../../../) include $(TOP)/make/firmware-defs.mk include $(TOP)/make/boards/$(BOARD_NAME)/board-info.mk -# Target file name (without extension). -TARGET := fw_$(BOARD_NAME) - -# Directory for output files (lst, obj, dep, elf, sym, map, hex, bin etc.) -OUTDIR := $(TOP)/build/$(TARGET) - # Set developer code and compile options # Set to YES for debugging DEBUG ?= NO @@ -90,14 +84,9 @@ PYMODULES = # Paths OPSYSTEM = ./System OPSYSTEMINC = $(OPSYSTEM)/inc -OPUAVTALK = ../../UAVTalk OPUAVTALKINC = $(OPUAVTALK)/inc -OPUAVOBJ = ../../UAVObjects OPUAVOBJINC = $(OPUAVOBJ)/inc -PIOS = ../../PiOS PIOSINC = $(PIOS)/inc -OPMODULEDIR = ../../Modules -FLIGHTLIB = ../../Libraries FLIGHTLIBINC = $(FLIGHTLIB)/inc MATHLIB = $(FLIGHTLIB)/math MATHLIBINC = $(FLIGHTLIB)/math @@ -110,10 +99,7 @@ STMLIBDIR = $(APPLIBDIR) STMSPDDIR = $(STMLIBDIR)/STM32F4xx_StdPeriph_Driver STMSPDSRCDIR = $(STMSPDDIR)/src STMSPDINCDIR = $(STMSPDDIR)/inc -OPUAVOBJ = ../../UAVObjects OPUAVOBJINC = $(OPUAVOBJ)/inc -#BOOT = ../../Bootloaders/INS -#BOOTINC = $(BOOT)/inc PYMITE = $(FLIGHTLIB)/PyMite PYMITELIB = $(PYMITE)/lib PYMITEPLAT = $(PYMITE)/platform/openpilot @@ -124,8 +110,6 @@ PYMITEINC += $(PYMITEPLAT) PYMITEINC += $(OUTDIR) FLIGHTPLANLIB = $(OPMODULEDIR)/FlightPlan/lib FLIGHTPLANS = $(OPMODULEDIR)/FlightPlan/flightplans -HWDEFSINC = ../board_hw_defs/$(BOARD_NAME) -UAVOBJSYNTHDIR = $(OUTDIR)/../uavobject-synthetics/flight SRC = # optional component libraries @@ -236,7 +220,7 @@ EXTRAINCDIRS += $(OPUAVTALK) EXTRAINCDIRS += $(OPUAVTALKINC) EXTRAINCDIRS += $(OPUAVOBJ) EXTRAINCDIRS += $(OPUAVOBJINC) -EXTRAINCDIRS += $(UAVOBJSYNTHDIR) +EXTRAINCDIRS += $(OPUAVSYNTHDIR) EXTRAINCDIRS += $(FLIGHTLIBINC) EXTRAINCDIRS += $(MATHLIBINC) EXTRAINCDIRS += $(PIOSSTM32F4XX) @@ -244,8 +228,6 @@ EXTRAINCDIRS += $(PIOSCOMMON) EXTRAINCDIRS += $(PIOSBOARDS) EXTRAINCDIRS += $(STMSPDINCDIR) EXTRAINCDIRS += $(CMSISDIR) -EXTRAINCDIRS += $(OPUAVSYNTHDIR) -EXTRAINCDIRS += $(BOOTINC) EXTRAINCDIRS += $(PYMITEINC) EXTRAINCDIRS += $(HWDEFSINC) diff --git a/flight/targets/Revolution/UAVObjects.inc b/flight/targets/Revolution/UAVObjects.inc index 545f6ecc7..4b937e900 100644 --- a/flight/targets/Revolution/UAVObjects.inc +++ b/flight/targets/Revolution/UAVObjects.inc @@ -95,5 +95,5 @@ UAVOBJSRCFILENAMES += altitudeholddesired UAVOBJSRCFILENAMES += waypoint UAVOBJSRCFILENAMES += waypointactive -UAVOBJSRC = $(foreach UAVOBJSRCFILE,$(UAVOBJSRCFILENAMES),$(UAVOBJSYNTHDIR)/$(UAVOBJSRCFILE).c ) +UAVOBJSRC = $(foreach UAVOBJSRCFILE,$(UAVOBJSRCFILENAMES),$(OPUAVSYNTHDIR)/$(UAVOBJSRCFILE).c ) UAVOBJDEFINE = $(foreach UAVOBJSRCFILE,$(UAVOBJSRCFILENAMES),-DUAVOBJ_INIT_$(UAVOBJSRCFILE) ) From 2f93d983b0d0526b9db215ada0a2930a17eff247 Mon Sep 17 00:00:00 2001 From: Stacey Sheldon Date: Sat, 17 Nov 2012 19:15:00 -0500 Subject: [PATCH 24/30] makefile: update ARM toolchain to 4.6-2012-q4 --- Makefile | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Makefile b/Makefile index 495937046..b724e7c59 100644 --- a/Makefile +++ b/Makefile @@ -203,10 +203,10 @@ qt_sdk_clean: $(V1) [ ! -d "$(QT_SDK_DIR)" ] || $(RM) -rf $(QT_SDK_DIR) # Set up ARM (STM32) SDK -ARM_SDK_DIR := $(TOOLS_DIR)/gcc-arm-none-eabi-4_6-2012q1 +ARM_SDK_DIR := $(TOOLS_DIR)/gcc-arm-none-eabi-4_6-2012q4 .PHONY: arm_sdk_install -arm_sdk_install: ARM_SDK_URL := https://launchpad.net/gcc-arm-embedded/4.6/4.6-2012-q1-update/+download/gcc-arm-none-eabi-4_6-2012q1-20120316.tar.bz2 +arm_sdk_install: ARM_SDK_URL := https://launchpad.net/gcc-arm-embedded/4.6/4.6-2012-q4-update/+download/gcc-arm-none-eabi-4_6-2012q4-20121016.tar.bz2 arm_sdk_install: ARM_SDK_FILE := $(notdir $(ARM_SDK_URL)) # order-only prereq on directory existance: arm_sdk_install: | $(DL_DIR) $(TOOLS_DIR) From 0fda8035c21f43a1ff6a4201cafb9c05ed7c1872 Mon Sep 17 00:00:00 2001 From: Stacey Sheldon Date: Sat, 17 Nov 2012 19:16:31 -0500 Subject: [PATCH 25/30] makefile: update to released openocd 0.6.1 --- Makefile | 16 +++++-- flight/Project/OpenOCD/stlink-v2.cfg | 11 ++--- flight/Project/OpenOCD/stm32f4xx.stlink.cfg | 47 ++++++++++++++++++--- 3 files changed, 59 insertions(+), 15 deletions(-) diff --git a/Makefile b/Makefile index b724e7c59..b03b2125a 100644 --- a/Makefile +++ b/Makefile @@ -228,8 +228,8 @@ OPENOCD_BUILD_DIR := $(DL_DIR)/openocd-build .PHONY: openocd_install openocd_install: | $(DL_DIR) $(TOOLS_DIR) -openocd_install: OPENOCD_URL := http://sourceforge.net/projects/openocd/files/openocd/0.5.0/openocd-0.5.0.tar.bz2/download -openocd_install: OPENOCD_FILE := openocd-0.5.0.tar.bz2 +openocd_install: OPENOCD_URL := http://sourceforge.net/projects/openocd/files/openocd/0.6.1/openocd-0.6.1.tar.bz2/download +openocd_install: OPENOCD_FILE := openocd-0.6.1.tar.bz2 openocd_install: openocd_clean # download the source only if it's newer than what we already have $(V1) wget -N -P "$(DL_DIR)" --trust-server-name "$(OPENOCD_URL)" @@ -239,11 +239,19 @@ openocd_install: openocd_clean $(V1) mkdir -p "$(OPENOCD_BUILD_DIR)" $(V1) tar -C $(OPENOCD_BUILD_DIR) -xjf "$(DL_DIR)/$(OPENOCD_FILE)" + # apply patches + $(V0) @echo " PATCH $(OPENOCD_DIR)" + $(V1) ( \ + cd $(OPENOCD_BUILD_DIR)/openocd-0.6.1 ; \ + patch -p1 < $(ROOT_DIR)/flight/Project/OpenOCD/0001-armv7m-remove-dummy-FP-regs-for-new-gdb.patch ; \ + patch -p1 < $(ROOT_DIR)/flight/Project/OpenOCD/0002-rtos-add-stm32_stlink-to-FreeRTOS-targets.patch ; \ + ) + # build and install $(V1) mkdir -p "$(OPENOCD_DIR)" $(V1) ( \ - cd $(OPENOCD_BUILD_DIR)/openocd-0.5.0 ; \ - ./configure --prefix="$(OPENOCD_DIR)" --enable-ft2232_libftdi ; \ + cd $(OPENOCD_BUILD_DIR)/openocd-0.6.1 ; \ + ./configure --prefix="$(OPENOCD_DIR)" --enable-ft2232_libftdi --enable-stlink ; \ $(MAKE) --silent ; \ $(MAKE) --silent install ; \ ) diff --git a/flight/Project/OpenOCD/stlink-v2.cfg b/flight/Project/OpenOCD/stlink-v2.cfg index c7f671477..585b1d92d 100644 --- a/flight/Project/OpenOCD/stlink-v2.cfg +++ b/flight/Project/OpenOCD/stlink-v2.cfg @@ -6,11 +6,12 @@ interface stlink stlink_layout usb stlink_device_desc "ST-LINK/V2" stlink_vid_pid 0x0483 0x3748 -# -# dummy values, not really needed -# -adapter_khz 1 -reset_config trst_and_srst + +# unused but set to disable warnings +adapter_khz 1000 + +#reset_config trst_and_srst +reset_config srst_only srst_nogate gdb_port 3333 tcl_port 6666 diff --git a/flight/Project/OpenOCD/stm32f4xx.stlink.cfg b/flight/Project/OpenOCD/stm32f4xx.stlink.cfg index 3d55f6da5..bae71ce74 100644 --- a/flight/Project/OpenOCD/stm32f4xx.stlink.cfg +++ b/flight/Project/OpenOCD/stm32f4xx.stlink.cfg @@ -1,27 +1,60 @@ # +# STM32f4x stlink pseudo target # + +if { [info exists CHIPNAME] == 0 } { + set CHIPNAME stm32f4x +} + +if { [info exists CPUTAPID] == 0 } { + set CPUTAPID 0x2ba01477 +} + +if { [info exists WORKAREASIZE] == 0 } { + set WORKAREASIZE 0x10000 +} + # +# stm32 stlink pseudo target +# + if { [info exists CHIPNAME] } { set _CHIPNAME $CHIPNAME } else { - set _CHIPNAME stm32f4x + set _CHIPNAME stm32f1x } # Work-area is a space in RAM used for flash programming -# By default use 64kB +# By default use 16kB if { [info exists WORKAREASIZE] } { set _WORKAREASIZE $WORKAREASIZE } else { - set _WORKAREASIZE 0x10000 + set _WORKAREASIZE 0x4000 } if { [info exists CPUTAPID] } { set _CPUTAPID $CPUTAPID } else { - set _CPUTAPID 0x2ba01477 + # this is the SW-DP tap id not the jtag tap id + set _CPUTAPID 0x1ba01477 } -transport select stlink_swd +if { [info exists TRANSPORT] } { + set _TRANSPORT $TRANSPORT + if { $TRANSPORT == "stlink_jtag" } { + if { [info exists CPUTAPID] == 0 } { + # jtag requires us to use the jtag tap id + set _CPUTAPID 0x3ba00477 + } + } +} else { + set _TRANSPORT stlink_swd +} + +# +# possibles value are stlink_swd or stlink_jtag +# +transport select $_TRANSPORT stlink newtap $_CHIPNAME cpu -expected-id $_CPUTAPID @@ -30,5 +63,7 @@ target create $_TARGETNAME stm32_stlink -chain-position $_TARGETNAME -rtos auto $_TARGETNAME configure -work-area-phys 0x20000000 -work-area-size $_WORKAREASIZE -work-area-backup 0 +# stm32f4x family uses stm32f2x driver set _FLASHNAME $_CHIPNAME.flash -flash bank $_FLASHNAME stm32f2x 0x08000000 0 0 0 $_TARGETNAME +flash bank $_FLASHNAME stm32f2x 0 0 0 0 $_TARGETNAME + From e55519b1e22f40f381a96567595eaf02742ce9c4 Mon Sep 17 00:00:00 2001 From: Stacey Sheldon Date: Tue, 27 Nov 2012 22:43:02 -0500 Subject: [PATCH 26/30] makefile: split tool install rules into separate makefile The rules for downloading/building/installing the various tools were cluttering the top-level makefile. Conflicts: Makefile --- Makefile | 344 ++------------------------------------------------ make/tools.mk | 318 ++++++++++++++++++++++++++++++++++++++++++++++ 2 files changed, 332 insertions(+), 330 deletions(-) create mode 100644 make/tools.mk diff --git a/Makefile b/Makefile index b03b2125a..89691050e 100644 --- a/Makefile +++ b/Makefile @@ -31,6 +31,20 @@ $(foreach var, $(SANITIZE_GCC_VARS), $(eval $(call SANITIZE_VAR,$(var),disallowe SANITIZE_DEPRECATED_VARS := USE_BOOTLOADER $(foreach var, $(SANITIZE_DEPRECATED_VARS), $(eval $(call SANITIZE_VAR,$(var),deprecated))) +# Decide on a verbosity level based on the V= parameter +export AT := @ + +ifndef V +export V0 := +export V1 := $(AT) +else ifeq ($(V), 0) +export V0 := $(AT) +export V1 := $(AT) +else ifeq ($(V), 1) +endif + +include $(ROOT_DIR)/make/tools.mk + # We almost need to consider autoconf/automake instead of this # I don't know if windows supports uname :-( QT_SPEC=win32-g++ @@ -52,18 +66,6 @@ GCS_BUILD_CONF ?= debug # Set up misc host tools RM=rm -# Decide on a verbosity level based on the V= parameter -export AT := @ - -ifndef V -export V0 := -export V1 := $(AT) -else ifeq ($(V), 0) -export V0 := $(AT) -export V1 := $(AT) -else ifeq ($(V), 1) -endif - .PHONY: help help: @echo @@ -158,324 +160,6 @@ $(TOOLS_DIR): $(BUILD_DIR): mkdir -p $@ -############################################################### -# -# Installers for tools required by the ground and flight builds -# -# NOTE: These are not tied to the default goals -# and must be invoked manually -# -############################################################### - -# Set up QT toolchain -QT_SDK_DIR := $(TOOLS_DIR)/qtsdk-v1.2.1 - -.PHONY: qt_sdk_install -# Choose the appropriate installer based on host architecture -ifneq (,$(filter $(ARCH), x86_64 amd64)) -# 64-bit -qt_sdk_install: QT_SDK_FILE := QtSdk-offline-linux-x86_64-v1.2.1.run -qt_sdk_install: QT_SDK_URL := http://www.developer.nokia.com/dp?uri=http://sw.nokia.com/id/14b2039c-0e1f-4774-a4f2-9aa60b6d5313/Qt_SDK_Lin64_offline -else -# 32-bit -qt_sdk_install: QT_SDK_URL := http://www.developer.nokia.com/dp?uri=http://sw.nokia.com/id/8ea74da4-fec1-4277-8b26-c58cc82e204b/Qt_SDK_Lin32_offline -qt_sdk_install: QT_SDK_FILE := QtSdk-offline-linux-x86-v1.2.1.run -endif -# order-only prereq on directory existance: -qt_sdk_install : | $(DL_DIR) $(TOOLS_DIR) -qt_sdk_install: qt_sdk_clean - # download the source only if it's newer than what we already have - $(V1) wget -N --content-disposition -P "$(DL_DIR)" "$(QT_SDK_URL)" - # tell the user exactly which path they should select in the GUI - $(V1) echo "*** NOTE NOTE NOTE ***" - $(V1) echo "*" - $(V1) echo "* In the GUI, please use exactly this path as the installation path:" - $(V1) echo "* $(QT_SDK_DIR)" - $(V1) echo "*" - $(V1) echo "*** NOTE NOTE NOTE ***" - - #installer is an executable, make it executable and run it - $(V1) chmod u+x "$(DL_DIR)/$(QT_SDK_FILE)" - $(V1) "$(DL_DIR)/$(QT_SDK_FILE)" -style cleanlooks - -.PHONY: qt_sdk_clean -qt_sdk_clean: - $(V1) [ ! -d "$(QT_SDK_DIR)" ] || $(RM) -rf $(QT_SDK_DIR) - -# Set up ARM (STM32) SDK -ARM_SDK_DIR := $(TOOLS_DIR)/gcc-arm-none-eabi-4_6-2012q4 - -.PHONY: arm_sdk_install -arm_sdk_install: ARM_SDK_URL := https://launchpad.net/gcc-arm-embedded/4.6/4.6-2012-q4-update/+download/gcc-arm-none-eabi-4_6-2012q4-20121016.tar.bz2 -arm_sdk_install: ARM_SDK_FILE := $(notdir $(ARM_SDK_URL)) -# order-only prereq on directory existance: -arm_sdk_install: | $(DL_DIR) $(TOOLS_DIR) -arm_sdk_install: arm_sdk_clean - # download the source only if it's newer than what we already have - $(V1) wget --no-check-certificate -N -P "$(DL_DIR)" "$(ARM_SDK_URL)" - - # binary only release so just extract it - $(V1) tar -C $(TOOLS_DIR) -xjf "$(DL_DIR)/$(ARM_SDK_FILE)" - -.PHONY: arm_sdk_clean -arm_sdk_clean: - $(V1) [ ! -d "$(ARM_SDK_DIR)" ] || $(RM) -r $(ARM_SDK_DIR) - -# Set up openocd tools -OPENOCD_DIR := $(TOOLS_DIR)/openocd -OPENOCD_WIN_DIR := $(TOOLS_DIR)/openocd_win -OPENOCD_BUILD_DIR := $(DL_DIR)/openocd-build - -.PHONY: openocd_install -openocd_install: | $(DL_DIR) $(TOOLS_DIR) -openocd_install: OPENOCD_URL := http://sourceforge.net/projects/openocd/files/openocd/0.6.1/openocd-0.6.1.tar.bz2/download -openocd_install: OPENOCD_FILE := openocd-0.6.1.tar.bz2 -openocd_install: openocd_clean - # download the source only if it's newer than what we already have - $(V1) wget -N -P "$(DL_DIR)" --trust-server-name "$(OPENOCD_URL)" - - # extract the source - $(V1) [ ! -d "$(OPENOCD_BUILD_DIR)" ] || $(RM) -r "$(OPENOCD_BUILD_DIR)" - $(V1) mkdir -p "$(OPENOCD_BUILD_DIR)" - $(V1) tar -C $(OPENOCD_BUILD_DIR) -xjf "$(DL_DIR)/$(OPENOCD_FILE)" - - # apply patches - $(V0) @echo " PATCH $(OPENOCD_DIR)" - $(V1) ( \ - cd $(OPENOCD_BUILD_DIR)/openocd-0.6.1 ; \ - patch -p1 < $(ROOT_DIR)/flight/Project/OpenOCD/0001-armv7m-remove-dummy-FP-regs-for-new-gdb.patch ; \ - patch -p1 < $(ROOT_DIR)/flight/Project/OpenOCD/0002-rtos-add-stm32_stlink-to-FreeRTOS-targets.patch ; \ - ) - - # build and install - $(V1) mkdir -p "$(OPENOCD_DIR)" - $(V1) ( \ - cd $(OPENOCD_BUILD_DIR)/openocd-0.6.1 ; \ - ./configure --prefix="$(OPENOCD_DIR)" --enable-ft2232_libftdi --enable-stlink ; \ - $(MAKE) --silent ; \ - $(MAKE) --silent install ; \ - ) - - # delete the extracted source when we're done - $(V1) [ ! -d "$(OPENOCD_BUILD_DIR)" ] || $(RM) -rf "$(OPENOCD_BUILD_DIR)" - -.PHONY: ftd2xx_install - -FTD2XX_DIR := $(DL_DIR)/ftd2xx - -ftd2xx_install: | $(DL_DIR) -ftd2xx_install: FTD2XX_URL := http://www.ftdichip.com/Drivers/CDM/Beta/CDM20817.zip -ftd2xx_install: FTD2XX_FILE := CDM20817.zip -ftd2xx_install: ftd2xx_clean - # download the file only if it's newer than what we already have - $(V0) @echo " DOWNLOAD $(FTD2XX_URL)" - $(V1) wget -q -N -P "$(DL_DIR)" "$(FTD2XX_URL)" - - # extract the source - $(V0) @echo " EXTRACT $(FTD2XX_FILE) -> $(FTD2XX_DIR)" - $(V1) mkdir -p "$(FTD2XX_DIR)" - $(V1) unzip -q -d "$(FTD2XX_DIR)" "$(DL_DIR)/$(FTD2XX_FILE)" - -.PHONY: ftd2xx_clean -ftd2xx_clean: - $(V0) @echo " CLEAN $(FTD2XX_DIR)" - $(V1) [ ! -d "$(FTD2XX_DIR)" ] || $(RM) -r "$(FTD2XX_DIR)" - -.PHONY: ftd2xx_install - -LIBUSB_WIN_DIR := $(DL_DIR)/libusb-win32-bin-1.2.6.0 - -libusb_win_install: | $(DL_DIR) -libusb_win_install: LIBUSB_WIN_URL := http://sourceforge.net/projects/libusb-win32/files/libusb-win32-releases/1.2.6.0/libusb-win32-bin-1.2.6.0.zip/download -libusb_win_install: LIBUSB_WIN_FILE := libusb-win32-bin-1.2.6.0.zip -libusb_win_install: libusb_win_clean - # download the file only if it's newer than what we already have - $(V0) @echo " DOWNLOAD $(LIBUSB_WIN_URL)" - $(V1) wget -q -N -P "$(DL_DIR)" --trust-server-name "$(LIBUSB_WIN_URL)" - - # extract the source - $(V0) @echo " EXTRACT $(LIBUSB_WIN_FILE) -> $(LIBUSB_WIN_DIR)" - $(V1) mkdir -p "$(LIBUSB_WIN_DIR)" - $(V1) unzip -q -d "$(DL_DIR)" "$(DL_DIR)/$(LIBUSB_WIN_FILE)" - - # fixup .h file needed by openocd build - $(V0) @echo " FIXUP $(LIBUSB_WIN_DIR)" - $(V1) ln -s "$(LIBUSB_WIN_DIR)/include/lusb0_usb.h" "$(LIBUSB_WIN_DIR)/include/usb.h" - -.PHONY: libusb_win_clean -libusb_win_clean: - $(V0) @echo " CLEAN $(LIBUSB_WIN_DIR)" - $(V1) [ ! -d "$(LIBUSB_WIN_DIR)" ] || $(RM) -r "$(LIBUSB_WIN_DIR)" - -.PHONY: openocd_git_win_install - -openocd_git_win_install: | $(DL_DIR) $(TOOLS_DIR) -openocd_git_win_install: OPENOCD_URL := git://openocd.git.sourceforge.net/gitroot/openocd/openocd -openocd_git_win_install: OPENOCD_REV := f1c0133321c8fcadadd10bba5537c0a634eb183b -openocd_git_win_install: openocd_win_clean libusb_win_install ftd2xx_install - # download the source - $(V0) @echo " DOWNLOAD $(OPENOCD_URL) @ $(OPENOCD_REV)" - $(V1) [ ! -d "$(OPENOCD_BUILD_DIR)" ] || $(RM) -rf "$(OPENOCD_BUILD_DIR)" - $(V1) mkdir -p "$(OPENOCD_BUILD_DIR)" - $(V1) git clone --no-checkout $(OPENOCD_URL) "$(DL_DIR)/openocd-build" - $(V1) ( \ - cd $(OPENOCD_BUILD_DIR) ; \ - git checkout -q $(OPENOCD_REV) ; \ - ) - - # apply patches - $(V0) @echo " PATCH $(OPENOCD_BUILD_DIR)" - $(V1) ( \ - cd $(OPENOCD_BUILD_DIR) ; \ - git apply < $(ROOT_DIR)/flight/Project/OpenOCD/0001-armv7m-remove-dummy-FP-regs-for-new-gdb.patch ; \ - git apply < $(ROOT_DIR)/flight/Project/OpenOCD/0002-rtos-add-stm32_stlink-to-FreeRTOS-targets.patch ; \ - ) - - # build and install - $(V0) @echo " BUILD $(OPENOCD_WIN_DIR)" - $(V1) mkdir -p "$(OPENOCD_WIN_DIR)" - $(V1) ( \ - cd $(OPENOCD_BUILD_DIR) ; \ - ./bootstrap ; \ - ./configure --enable-maintainer-mode --prefix="$(OPENOCD_WIN_DIR)" \ - --build=i686-pc-linux-gnu --host=i586-mingw32msvc \ - CPPFLAGS=-I$(LIBUSB_WIN_DIR)/include \ - LDFLAGS=-L$(LIBUSB_WIN_DIR)/lib/gcc \ - --enable-ft2232_ftd2xx --with-ftd2xx-win32-zipdir=$(FTD2XX_DIR) \ - --disable-werror \ - --enable-stlink ; \ - $(MAKE) ; \ - $(MAKE) install ; \ - ) - - # delete the extracted source when we're done - $(V1) [ ! -d "$(OPENOCD_BUILD_DIR)" ] || $(RM) -rf "$(OPENOCD_BUILD_DIR)" - -.PHONY: openocd_win_clean -openocd_win_clean: - $(V0) @echo " CLEAN $(OPENOCD_WIN_DIR)" - $(V1) [ ! -d "$(OPENOCD_WIN_DIR)" ] || $(RM) -r "$(OPENOCD_WIN_DIR)" - -.PHONY: openocd_git_install - -openocd_git_install: | $(DL_DIR) $(TOOLS_DIR) -openocd_git_install: OPENOCD_URL := git://openocd.git.sourceforge.net/gitroot/openocd/openocd -openocd_git_install: OPENOCD_REV := f1c0133321c8fcadadd10bba5537c0a634eb183b -openocd_git_install: openocd_clean - # download the source - $(V0) @echo " DOWNLOAD $(OPENOCD_URL) @ $(OPENOCD_REV)" - $(V1) [ ! -d "$(OPENOCD_BUILD_DIR)" ] || $(RM) -rf "$(OPENOCD_BUILD_DIR)" - $(V1) mkdir -p "$(OPENOCD_BUILD_DIR)" - $(V1) git clone --no-checkout $(OPENOCD_URL) "$(OPENOCD_BUILD_DIR)" - $(V1) ( \ - cd $(OPENOCD_BUILD_DIR) ; \ - git checkout -q $(OPENOCD_REV) ; \ - ) - - # apply patches - $(V0) @echo " PATCH $(OPENOCD_DIR)" - $(V1) ( \ - cd $(OPENOCD_BUILD_DIR) ; \ - git apply < $(ROOT_DIR)/flight/Project/OpenOCD/0001-armv7m-remove-dummy-FP-regs-for-new-gdb.patch ; \ - git apply < $(ROOT_DIR)/flight/Project/OpenOCD/0002-rtos-add-stm32_stlink-to-FreeRTOS-targets.patch ; \ - ) - - # build and install - $(V0) @echo " BUILD $(OPENOCD_DIR)" - $(V1) mkdir -p "$(OPENOCD_DIR)" - $(V1) ( \ - cd $(OPENOCD_BUILD_DIR) ; \ - ./bootstrap ; \ - ./configure --enable-maintainer-mode --prefix="$(OPENOCD_DIR)" --enable-ft2232_libftdi --enable-buspirate --enable-stlink ; \ - $(MAKE) ; \ - $(MAKE) install ; \ - ) - - # delete the extracted source when we're done - $(V1) [ ! -d "$(OPENOCD_BUILD_DIR)" ] || $(RM) -rf "$(OPENOCD_BUILD_DIR)" - -.PHONY: openocd_clean -openocd_clean: - $(V0) @echo " CLEAN $(OPENOCD_DIR)" - $(V1) [ ! -d "$(OPENOCD_DIR)" ] || $(RM) -r "$(OPENOCD_DIR)" - -STM32FLASH_DIR := $(TOOLS_DIR)/stm32flash - -.PHONY: stm32flash_install -stm32flash_install: STM32FLASH_URL := http://stm32flash.googlecode.com/svn/trunk -stm32flash_install: STM32FLASH_REV := 61 -stm32flash_install: stm32flash_clean - # download the source - $(V0) @echo " DOWNLOAD $(STM32FLASH_URL) @ r$(STM32FLASH_REV)" - $(V1) svn export -q -r "$(STM32FLASH_REV)" "$(STM32FLASH_URL)" "$(STM32FLASH_DIR)" - - # build - $(V0) @echo " BUILD $(STM32FLASH_DIR)" - $(V1) $(MAKE) --silent -C $(STM32FLASH_DIR) all - -.PHONY: stm32flash_clean -stm32flash_clean: - $(V0) @echo " CLEAN $(STM32FLASH_DIR)" - $(V1) [ ! -d "$(STM32FLASH_DIR)" ] || $(RM) -r "$(STM32FLASH_DIR)" - -DFUUTIL_DIR := $(TOOLS_DIR)/dfu-util - -.PHONY: dfuutil_install -dfuutil_install: DFUUTIL_URL := http://dfu-util.gnumonks.org/releases/dfu-util-0.5.tar.gz -dfuutil_install: DFUUTIL_FILE := $(notdir $(DFUUTIL_URL)) -dfuutil_install: | $(DL_DIR) $(TOOLS_DIR) -dfuutil_install: dfuutil_clean - # download the source - $(V0) @echo " DOWNLOAD $(DFUUTIL_URL)" - $(V1) wget -N -P "$(DL_DIR)" "$(DFUUTIL_URL)" - - # extract the source - $(V0) @echo " EXTRACT $(DFUUTIL_FILE)" - $(V1) [ ! -d "$(DL_DIR)/dfuutil-build" ] || $(RM) -r "$(DL_DIR)/dfuutil-build" - $(V1) mkdir -p "$(DL_DIR)/dfuutil-build" - $(V1) tar -C $(DL_DIR)/dfuutil-build -xf "$(DL_DIR)/$(DFUUTIL_FILE)" - - # build - $(V0) @echo " BUILD $(DFUUTIL_DIR)" - $(V1) mkdir -p "$(DFUUTIL_DIR)" - $(V1) ( \ - cd $(DL_DIR)/dfuutil-build/dfu-util-0.5 ; \ - ./configure --prefix="$(DFUUTIL_DIR)" ; \ - $(MAKE) ; \ - $(MAKE) install ; \ - ) - -.PHONY: dfuutil_clean -dfuutil_clean: - $(V0) @echo " CLEAN $(DFUUTIL_DIR)" - $(V1) [ ! -d "$(DFUUTIL_DIR)" ] || $(RM) -r "$(DFUUTIL_DIR)" - -# see http://developer.android.com/sdk/ for latest versions -ANDROID_SDK_DIR := $(TOOLS_DIR)/android-sdk-linux -.PHONY: android_sdk_install -android_sdk_install: ANDROID_SDK_URL := http://dl.google.com/android/android-sdk_r20.0.3-linux.tgz -android_sdk_install: ANDROID_SDK_FILE := $(notdir $(ANDROID_SDK_URL)) -# order-only prereq on directory existance: -android_sdk_install: | $(DL_DIR) $(TOOLS_DIR) -android_sdk_install: android_sdk_clean - # download the source only if it's newer than what we already have - $(V0) @echo " DOWNLOAD $(ANDROID_SDK_URL)" - $(V1) wget --no-check-certificate -N -P "$(DL_DIR)" "$(ANDROID_SDK_URL)" - - # binary only release so just extract it - $(V0) @echo " EXTRACT $(ANDROID_SDK_FILE)" - $(V1) tar -C $(TOOLS_DIR) -xf "$(DL_DIR)/$(ANDROID_SDK_FILE)" - -.PHONY: android_sdk_clean -android_sdk_clean: - $(V0) @echo " CLEAN $(ANDROID_SDK_DIR)" - $(V1) [ ! -d "$(ANDROID_SDK_DIR)" ] || $(RM) -r $(ANDROID_SDK_DIR) - -.PHONY: android_sdk_update -android_sdk_update: - $(V0) @echo " UPDATE $(ANDROID_SDK_DIR)" - $(ANDROID_SDK_DIR)/tools/android update sdk --no-ui -t platform-tools,android-16,addon-google_apis-google-16 - ############################## # # Set up paths to tools diff --git a/make/tools.mk b/make/tools.mk new file mode 100644 index 000000000..49e58066f --- /dev/null +++ b/make/tools.mk @@ -0,0 +1,318 @@ +############################################################### +# +# Installers for tools required by the ground and flight builds +# +# NOTE: These are not tied to the default goals +# and must be invoked manually +# +############################################################### + +# Set up QT toolchain +QT_SDK_DIR := $(TOOLS_DIR)/qtsdk-v1.2.1 + +.PHONY: qt_sdk_install +# Choose the appropriate installer based on host architecture +ifneq (,$(filter $(ARCH), x86_64 amd64)) +# 64-bit +qt_sdk_install: QT_SDK_FILE := QtSdk-offline-linux-x86_64-v1.2.1.run +qt_sdk_install: QT_SDK_URL := http://www.developer.nokia.com/dp?uri=http://sw.nokia.com/id/14b2039c-0e1f-4774-a4f2-9aa60b6d5313/Qt_SDK_Lin64_offline +else +# 32-bit +qt_sdk_install: QT_SDK_URL := http://www.developer.nokia.com/dp?uri=http://sw.nokia.com/id/8ea74da4-fec1-4277-8b26-c58cc82e204b/Qt_SDK_Lin32_offline +qt_sdk_install: QT_SDK_FILE := QtSdk-offline-linux-x86-v1.2.1.run +endif +# order-only prereq on directory existance: +qt_sdk_install : | $(DL_DIR) $(TOOLS_DIR) +qt_sdk_install: qt_sdk_clean + # download the source only if it's newer than what we already have + $(V1) wget -N --content-disposition -P "$(DL_DIR)" "$(QT_SDK_URL)" + # tell the user exactly which path they should select in the GUI + $(V1) echo "*** NOTE NOTE NOTE ***" + $(V1) echo "*" + $(V1) echo "* In the GUI, please use exactly this path as the installation path:" + $(V1) echo "* $(QT_SDK_DIR)" + $(V1) echo "*" + $(V1) echo "*** NOTE NOTE NOTE ***" + + #installer is an executable, make it executable and run it + $(V1) chmod u+x "$(DL_DIR)/$(QT_SDK_FILE)" + $(V1) "$(DL_DIR)/$(QT_SDK_FILE)" -style cleanlooks + +.PHONY: qt_sdk_clean +qt_sdk_clean: + $(V1) [ ! -d "$(QT_SDK_DIR)" ] || $(RM) -rf $(QT_SDK_DIR) + +# Set up ARM (STM32) SDK +ARM_SDK_DIR := $(TOOLS_DIR)/gcc-arm-none-eabi-4_6-2012q4 + +.PHONY: arm_sdk_install +arm_sdk_install: ARM_SDK_URL := https://launchpad.net/gcc-arm-embedded/4.6/4.6-2012-q4-update/+download/gcc-arm-none-eabi-4_6-2012q4-20121016.tar.bz2 +arm_sdk_install: ARM_SDK_FILE := $(notdir $(ARM_SDK_URL)) +# order-only prereq on directory existance: +arm_sdk_install: | $(DL_DIR) $(TOOLS_DIR) +arm_sdk_install: arm_sdk_clean + # download the source only if it's newer than what we already have + $(V1) wget --no-check-certificate -N -P "$(DL_DIR)" "$(ARM_SDK_URL)" + + # binary only release so just extract it + $(V1) tar -C $(TOOLS_DIR) -xjf "$(DL_DIR)/$(ARM_SDK_FILE)" + +.PHONY: arm_sdk_clean +arm_sdk_clean: + $(V1) [ ! -d "$(ARM_SDK_DIR)" ] || $(RM) -r $(ARM_SDK_DIR) + +# Set up openocd tools +OPENOCD_DIR := $(TOOLS_DIR)/openocd +OPENOCD_WIN_DIR := $(TOOLS_DIR)/openocd_win +OPENOCD_BUILD_DIR := $(DL_DIR)/openocd-build + +.PHONY: openocd_install +openocd_install: | $(DL_DIR) $(TOOLS_DIR) +openocd_install: OPENOCD_URL := http://sourceforge.net/projects/openocd/files/openocd/0.6.1/openocd-0.6.1.tar.bz2/download +openocd_install: OPENOCD_FILE := openocd-0.6.1.tar.bz2 +openocd_install: openocd_clean + # download the source only if it's newer than what we already have + $(V1) wget -N -P "$(DL_DIR)" --trust-server-name "$(OPENOCD_URL)" + + # extract the source + $(V1) [ ! -d "$(OPENOCD_BUILD_DIR)" ] || $(RM) -r "$(OPENOCD_BUILD_DIR)" + $(V1) mkdir -p "$(OPENOCD_BUILD_DIR)" + $(V1) tar -C $(OPENOCD_BUILD_DIR) -xjf "$(DL_DIR)/$(OPENOCD_FILE)" + + # apply patches + $(V0) @echo " PATCH $(OPENOCD_DIR)" + $(V1) ( \ + cd $(OPENOCD_BUILD_DIR)/openocd-0.6.1 ; \ + patch -p1 < $(ROOT_DIR)/flight/Project/OpenOCD/0001-armv7m-remove-dummy-FP-regs-for-new-gdb.patch ; \ + patch -p1 < $(ROOT_DIR)/flight/Project/OpenOCD/0002-rtos-add-stm32_stlink-to-FreeRTOS-targets.patch ; \ + ) + + # build and install + $(V1) mkdir -p "$(OPENOCD_DIR)" + $(V1) ( \ + cd $(OPENOCD_BUILD_DIR)/openocd-0.6.1 ; \ + ./configure --prefix="$(OPENOCD_DIR)" --enable-ft2232_libftdi --enable-stlink ; \ + $(MAKE) --silent ; \ + $(MAKE) --silent install ; \ + ) + + # delete the extracted source when we're done + $(V1) [ ! -d "$(OPENOCD_BUILD_DIR)" ] || $(RM) -rf "$(OPENOCD_BUILD_DIR)" + +.PHONY: ftd2xx_install + +FTD2XX_DIR := $(DL_DIR)/ftd2xx + +ftd2xx_install: | $(DL_DIR) +ftd2xx_install: FTD2XX_URL := http://www.ftdichip.com/Drivers/CDM/Beta/CDM20817.zip +ftd2xx_install: FTD2XX_FILE := CDM20817.zip +ftd2xx_install: ftd2xx_clean + # download the file only if it's newer than what we already have + $(V0) @echo " DOWNLOAD $(FTD2XX_URL)" + $(V1) wget -q -N -P "$(DL_DIR)" "$(FTD2XX_URL)" + + # extract the source + $(V0) @echo " EXTRACT $(FTD2XX_FILE) -> $(FTD2XX_DIR)" + $(V1) mkdir -p "$(FTD2XX_DIR)" + $(V1) unzip -q -d "$(FTD2XX_DIR)" "$(DL_DIR)/$(FTD2XX_FILE)" + +.PHONY: ftd2xx_clean +ftd2xx_clean: + $(V0) @echo " CLEAN $(FTD2XX_DIR)" + $(V1) [ ! -d "$(FTD2XX_DIR)" ] || $(RM) -r "$(FTD2XX_DIR)" + +.PHONY: ftd2xx_install + +LIBUSB_WIN_DIR := $(DL_DIR)/libusb-win32-bin-1.2.6.0 + +libusb_win_install: | $(DL_DIR) +libusb_win_install: LIBUSB_WIN_URL := http://sourceforge.net/projects/libusb-win32/files/libusb-win32-releases/1.2.6.0/libusb-win32-bin-1.2.6.0.zip/download +libusb_win_install: LIBUSB_WIN_FILE := libusb-win32-bin-1.2.6.0.zip +libusb_win_install: libusb_win_clean + # download the file only if it's newer than what we already have + $(V0) @echo " DOWNLOAD $(LIBUSB_WIN_URL)" + $(V1) wget -q -N -P "$(DL_DIR)" --trust-server-name "$(LIBUSB_WIN_URL)" + + # extract the source + $(V0) @echo " EXTRACT $(LIBUSB_WIN_FILE) -> $(LIBUSB_WIN_DIR)" + $(V1) mkdir -p "$(LIBUSB_WIN_DIR)" + $(V1) unzip -q -d "$(DL_DIR)" "$(DL_DIR)/$(LIBUSB_WIN_FILE)" + + # fixup .h file needed by openocd build + $(V0) @echo " FIXUP $(LIBUSB_WIN_DIR)" + $(V1) ln -s "$(LIBUSB_WIN_DIR)/include/lusb0_usb.h" "$(LIBUSB_WIN_DIR)/include/usb.h" + +.PHONY: libusb_win_clean +libusb_win_clean: + $(V0) @echo " CLEAN $(LIBUSB_WIN_DIR)" + $(V1) [ ! -d "$(LIBUSB_WIN_DIR)" ] || $(RM) -r "$(LIBUSB_WIN_DIR)" + +.PHONY: openocd_git_win_install + +openocd_git_win_install: | $(DL_DIR) $(TOOLS_DIR) +openocd_git_win_install: OPENOCD_URL := git://openocd.git.sourceforge.net/gitroot/openocd/openocd +openocd_git_win_install: OPENOCD_REV := f1c0133321c8fcadadd10bba5537c0a634eb183b +openocd_git_win_install: openocd_win_clean libusb_win_install ftd2xx_install + # download the source + $(V0) @echo " DOWNLOAD $(OPENOCD_URL) @ $(OPENOCD_REV)" + $(V1) [ ! -d "$(OPENOCD_BUILD_DIR)" ] || $(RM) -rf "$(OPENOCD_BUILD_DIR)" + $(V1) mkdir -p "$(OPENOCD_BUILD_DIR)" + $(V1) git clone --no-checkout $(OPENOCD_URL) "$(DL_DIR)/openocd-build" + $(V1) ( \ + cd $(OPENOCD_BUILD_DIR) ; \ + git checkout -q $(OPENOCD_REV) ; \ + ) + + # apply patches + $(V0) @echo " PATCH $(OPENOCD_BUILD_DIR)" + $(V1) ( \ + cd $(OPENOCD_BUILD_DIR) ; \ + git apply < $(ROOT_DIR)/flight/Project/OpenOCD/0001-armv7m-remove-dummy-FP-regs-for-new-gdb.patch ; \ + git apply < $(ROOT_DIR)/flight/Project/OpenOCD/0002-rtos-add-stm32_stlink-to-FreeRTOS-targets.patch ; \ + ) + + # build and install + $(V0) @echo " BUILD $(OPENOCD_WIN_DIR)" + $(V1) mkdir -p "$(OPENOCD_WIN_DIR)" + $(V1) ( \ + cd $(OPENOCD_BUILD_DIR) ; \ + ./bootstrap ; \ + ./configure --enable-maintainer-mode --prefix="$(OPENOCD_WIN_DIR)" \ + --build=i686-pc-linux-gnu --host=i586-mingw32msvc \ + CPPFLAGS=-I$(LIBUSB_WIN_DIR)/include \ + LDFLAGS=-L$(LIBUSB_WIN_DIR)/lib/gcc \ + --enable-ft2232_ftd2xx --with-ftd2xx-win32-zipdir=$(FTD2XX_DIR) \ + --disable-werror \ + --enable-stlink ; \ + $(MAKE) ; \ + $(MAKE) install ; \ + ) + + # delete the extracted source when we're done + $(V1) [ ! -d "$(OPENOCD_BUILD_DIR)" ] || $(RM) -rf "$(OPENOCD_BUILD_DIR)" + +.PHONY: openocd_win_clean +openocd_win_clean: + $(V0) @echo " CLEAN $(OPENOCD_WIN_DIR)" + $(V1) [ ! -d "$(OPENOCD_WIN_DIR)" ] || $(RM) -r "$(OPENOCD_WIN_DIR)" + +.PHONY: openocd_git_install + +openocd_git_install: | $(DL_DIR) $(TOOLS_DIR) +openocd_git_install: OPENOCD_URL := git://openocd.git.sourceforge.net/gitroot/openocd/openocd +openocd_git_install: OPENOCD_REV := f1c0133321c8fcadadd10bba5537c0a634eb183b +openocd_git_install: openocd_clean + # download the source + $(V0) @echo " DOWNLOAD $(OPENOCD_URL) @ $(OPENOCD_REV)" + $(V1) [ ! -d "$(OPENOCD_BUILD_DIR)" ] || $(RM) -rf "$(OPENOCD_BUILD_DIR)" + $(V1) mkdir -p "$(OPENOCD_BUILD_DIR)" + $(V1) git clone --no-checkout $(OPENOCD_URL) "$(OPENOCD_BUILD_DIR)" + $(V1) ( \ + cd $(OPENOCD_BUILD_DIR) ; \ + git checkout -q $(OPENOCD_REV) ; \ + ) + + # apply patches + $(V0) @echo " PATCH $(OPENOCD_DIR)" + $(V1) ( \ + cd $(OPENOCD_BUILD_DIR) ; \ + git apply < $(ROOT_DIR)/flight/Project/OpenOCD/0001-armv7m-remove-dummy-FP-regs-for-new-gdb.patch ; \ + git apply < $(ROOT_DIR)/flight/Project/OpenOCD/0002-rtos-add-stm32_stlink-to-FreeRTOS-targets.patch ; \ + ) + + # build and install + $(V0) @echo " BUILD $(OPENOCD_DIR)" + $(V1) mkdir -p "$(OPENOCD_DIR)" + $(V1) ( \ + cd $(OPENOCD_BUILD_DIR) ; \ + ./bootstrap ; \ + ./configure --enable-maintainer-mode --prefix="$(OPENOCD_DIR)" --enable-ft2232_libftdi --enable-buspirate --enable-stlink ; \ + $(MAKE) ; \ + $(MAKE) install ; \ + ) + + # delete the extracted source when we're done + $(V1) [ ! -d "$(OPENOCD_BUILD_DIR)" ] || $(RM) -rf "$(OPENOCD_BUILD_DIR)" + +.PHONY: openocd_clean +openocd_clean: + $(V0) @echo " CLEAN $(OPENOCD_DIR)" + $(V1) [ ! -d "$(OPENOCD_DIR)" ] || $(RM) -r "$(OPENOCD_DIR)" + +STM32FLASH_DIR := $(TOOLS_DIR)/stm32flash + +.PHONY: stm32flash_install +stm32flash_install: STM32FLASH_URL := http://stm32flash.googlecode.com/svn/trunk +stm32flash_install: STM32FLASH_REV := 61 +stm32flash_install: stm32flash_clean + # download the source + $(V0) @echo " DOWNLOAD $(STM32FLASH_URL) @ r$(STM32FLASH_REV)" + $(V1) svn export -q -r "$(STM32FLASH_REV)" "$(STM32FLASH_URL)" "$(STM32FLASH_DIR)" + + # build + $(V0) @echo " BUILD $(STM32FLASH_DIR)" + $(V1) $(MAKE) --silent -C $(STM32FLASH_DIR) all + +.PHONY: stm32flash_clean +stm32flash_clean: + $(V0) @echo " CLEAN $(STM32FLASH_DIR)" + $(V1) [ ! -d "$(STM32FLASH_DIR)" ] || $(RM) -r "$(STM32FLASH_DIR)" + +DFUUTIL_DIR := $(TOOLS_DIR)/dfu-util + +.PHONY: dfuutil_install +dfuutil_install: DFUUTIL_URL := http://dfu-util.gnumonks.org/releases/dfu-util-0.7.tar.gz +dfuutil_install: DFUUTIL_FILE := $(notdir $(DFUUTIL_URL)) +dfuutil_install: | $(DL_DIR) $(TOOLS_DIR) +dfuutil_install: dfuutil_clean + # download the source + $(V0) @echo " DOWNLOAD $(DFUUTIL_URL)" + $(V1) wget -N -P "$(DL_DIR)" "$(DFUUTIL_URL)" + + # extract the source + $(V0) @echo " EXTRACT $(DFUUTIL_FILE)" + $(V1) [ ! -d "$(DL_DIR)/dfuutil-build" ] || $(RM) -r "$(DL_DIR)/dfuutil-build" + $(V1) mkdir -p "$(DL_DIR)/dfuutil-build" + $(V1) tar -C $(DL_DIR)/dfuutil-build -xf "$(DL_DIR)/$(DFUUTIL_FILE)" + + # build + $(V0) @echo " BUILD $(DFUUTIL_DIR)" + $(V1) mkdir -p "$(DFUUTIL_DIR)" + $(V1) ( \ + cd $(DL_DIR)/dfuutil-build/dfu-util-0.7 ; \ + ./configure --prefix="$(DFUUTIL_DIR)" ; \ + $(MAKE) ; \ + $(MAKE) install ; \ + ) + +.PHONY: dfuutil_clean +dfuutil_clean: + $(V0) @echo " CLEAN $(DFUUTIL_DIR)" + $(V1) [ ! -d "$(DFUUTIL_DIR)" ] || $(RM) -r "$(DFUUTIL_DIR)" + +# see http://developer.android.com/sdk/ for latest versions +ANDROID_SDK_DIR := $(TOOLS_DIR)/android-sdk-linux +.PHONY: android_sdk_install +android_sdk_install: ANDROID_SDK_URL := http://dl.google.com/android/android-sdk_r20.0.3-linux.tgz +android_sdk_install: ANDROID_SDK_FILE := $(notdir $(ANDROID_SDK_URL)) +# order-only prereq on directory existance: +android_sdk_install: | $(DL_DIR) $(TOOLS_DIR) +android_sdk_install: android_sdk_clean + # download the source only if it's newer than what we already have + $(V0) @echo " DOWNLOAD $(ANDROID_SDK_URL)" + $(V1) wget --no-check-certificate -N -P "$(DL_DIR)" "$(ANDROID_SDK_URL)" + + # binary only release so just extract it + $(V0) @echo " EXTRACT $(ANDROID_SDK_FILE)" + $(V1) tar -C $(TOOLS_DIR) -xf "$(DL_DIR)/$(ANDROID_SDK_FILE)" + +.PHONY: android_sdk_clean +android_sdk_clean: + $(V0) @echo " CLEAN $(ANDROID_SDK_DIR)" + $(V1) [ ! -d "$(ANDROID_SDK_DIR)" ] || $(RM) -r $(ANDROID_SDK_DIR) + +.PHONY: android_sdk_update +android_sdk_update: + $(V0) @echo " UPDATE $(ANDROID_SDK_DIR)" + $(ANDROID_SDK_DIR)/tools/android update sdk --no-ui -t platform-tools,android-16,addon-google_apis-google-16 + From f500ac1e23a91614fc6db75855abc587558b76f6 Mon Sep 17 00:00:00 2001 From: Stacey Sheldon Date: Tue, 27 Nov 2012 22:59:25 -0500 Subject: [PATCH 27/30] rename: move UAVObjects and UAVTalk directories under targets --- Makefile | 4 ++-- flight/{ => targets}/UAVObjects/Makefiletemplate.inc | 0 flight/{ => targets}/UAVObjects/eventdispatcher.c | 0 flight/{ => targets}/UAVObjects/inc/eventdispatcher.h | 0 flight/{ => targets}/UAVObjects/inc/uavobjectmanager.h | 0 flight/{ => targets}/UAVObjects/inc/uavobjectsinittemplate.h | 0 flight/{ => targets}/UAVObjects/inc/uavobjecttemplate.h | 0 flight/{ => targets}/UAVObjects/inc/utlist.h | 0 flight/{ => targets}/UAVObjects/uavobjectmanager.c | 0 flight/{ => targets}/UAVObjects/uavobjectsinittemplate.c | 0 flight/{ => targets}/UAVObjects/uavobjecttemplate.c | 0 flight/{ => targets}/UAVTalk/inc/uavtalk.h | 0 flight/{ => targets}/UAVTalk/inc/uavtalk_priv.h | 0 flight/{ => targets}/UAVTalk/uavtalk.c | 0 .../generators/flight/uavobjectgeneratorflight.cpp | 2 +- 15 files changed, 3 insertions(+), 3 deletions(-) rename flight/{ => targets}/UAVObjects/Makefiletemplate.inc (100%) rename flight/{ => targets}/UAVObjects/eventdispatcher.c (100%) rename flight/{ => targets}/UAVObjects/inc/eventdispatcher.h (100%) rename flight/{ => targets}/UAVObjects/inc/uavobjectmanager.h (100%) rename flight/{ => targets}/UAVObjects/inc/uavobjectsinittemplate.h (100%) rename flight/{ => targets}/UAVObjects/inc/uavobjecttemplate.h (100%) rename flight/{ => targets}/UAVObjects/inc/utlist.h (100%) rename flight/{ => targets}/UAVObjects/uavobjectmanager.c (100%) rename flight/{ => targets}/UAVObjects/uavobjectsinittemplate.c (100%) rename flight/{ => targets}/UAVObjects/uavobjecttemplate.c (100%) rename flight/{ => targets}/UAVTalk/inc/uavtalk.h (100%) rename flight/{ => targets}/UAVTalk/inc/uavtalk_priv.h (100%) rename flight/{ => targets}/UAVTalk/uavtalk.c (100%) diff --git a/Makefile b/Makefile index 89691050e..01e9ccd19 100644 --- a/Makefile +++ b/Makefile @@ -424,8 +424,8 @@ uavo-collections_clean: PIOS := $(ROOT_DIR)/flight/PiOS FLIGHTLIB := $(ROOT_DIR)/flight/Libraries OPMODULEDIR := $(ROOT_DIR)/flight/Modules -OPUAVOBJ := $(ROOT_DIR)/flight/UAVObjects -OPUAVTALK := $(ROOT_DIR)/flight/UAVTalk +OPUAVOBJ := $(ROOT_DIR)/flight/targets/UAVObjects +OPUAVTALK := $(ROOT_DIR)/flight/targets/UAVTalk HWDEFS := $(ROOT_DIR)/flight/targets/board_hw_defs DOXYGENDIR := $(ROOT_DIR)/flight/Doc/Doxygen OPUAVSYNTHDIR := $(BUILD_DIR)/uavobject-synthetics/flight diff --git a/flight/UAVObjects/Makefiletemplate.inc b/flight/targets/UAVObjects/Makefiletemplate.inc similarity index 100% rename from flight/UAVObjects/Makefiletemplate.inc rename to flight/targets/UAVObjects/Makefiletemplate.inc diff --git a/flight/UAVObjects/eventdispatcher.c b/flight/targets/UAVObjects/eventdispatcher.c similarity index 100% rename from flight/UAVObjects/eventdispatcher.c rename to flight/targets/UAVObjects/eventdispatcher.c diff --git a/flight/UAVObjects/inc/eventdispatcher.h b/flight/targets/UAVObjects/inc/eventdispatcher.h similarity index 100% rename from flight/UAVObjects/inc/eventdispatcher.h rename to flight/targets/UAVObjects/inc/eventdispatcher.h diff --git a/flight/UAVObjects/inc/uavobjectmanager.h b/flight/targets/UAVObjects/inc/uavobjectmanager.h similarity index 100% rename from flight/UAVObjects/inc/uavobjectmanager.h rename to flight/targets/UAVObjects/inc/uavobjectmanager.h diff --git a/flight/UAVObjects/inc/uavobjectsinittemplate.h b/flight/targets/UAVObjects/inc/uavobjectsinittemplate.h similarity index 100% rename from flight/UAVObjects/inc/uavobjectsinittemplate.h rename to flight/targets/UAVObjects/inc/uavobjectsinittemplate.h diff --git a/flight/UAVObjects/inc/uavobjecttemplate.h b/flight/targets/UAVObjects/inc/uavobjecttemplate.h similarity index 100% rename from flight/UAVObjects/inc/uavobjecttemplate.h rename to flight/targets/UAVObjects/inc/uavobjecttemplate.h diff --git a/flight/UAVObjects/inc/utlist.h b/flight/targets/UAVObjects/inc/utlist.h similarity index 100% rename from flight/UAVObjects/inc/utlist.h rename to flight/targets/UAVObjects/inc/utlist.h diff --git a/flight/UAVObjects/uavobjectmanager.c b/flight/targets/UAVObjects/uavobjectmanager.c similarity index 100% rename from flight/UAVObjects/uavobjectmanager.c rename to flight/targets/UAVObjects/uavobjectmanager.c diff --git a/flight/UAVObjects/uavobjectsinittemplate.c b/flight/targets/UAVObjects/uavobjectsinittemplate.c similarity index 100% rename from flight/UAVObjects/uavobjectsinittemplate.c rename to flight/targets/UAVObjects/uavobjectsinittemplate.c diff --git a/flight/UAVObjects/uavobjecttemplate.c b/flight/targets/UAVObjects/uavobjecttemplate.c similarity index 100% rename from flight/UAVObjects/uavobjecttemplate.c rename to flight/targets/UAVObjects/uavobjecttemplate.c diff --git a/flight/UAVTalk/inc/uavtalk.h b/flight/targets/UAVTalk/inc/uavtalk.h similarity index 100% rename from flight/UAVTalk/inc/uavtalk.h rename to flight/targets/UAVTalk/inc/uavtalk.h diff --git a/flight/UAVTalk/inc/uavtalk_priv.h b/flight/targets/UAVTalk/inc/uavtalk_priv.h similarity index 100% rename from flight/UAVTalk/inc/uavtalk_priv.h rename to flight/targets/UAVTalk/inc/uavtalk_priv.h diff --git a/flight/UAVTalk/uavtalk.c b/flight/targets/UAVTalk/uavtalk.c similarity index 100% rename from flight/UAVTalk/uavtalk.c rename to flight/targets/UAVTalk/uavtalk.c diff --git a/ground/uavobjgenerator/generators/flight/uavobjectgeneratorflight.cpp b/ground/uavobjgenerator/generators/flight/uavobjectgeneratorflight.cpp index 3d9fd12b6..8b0e99e34 100644 --- a/ground/uavobjgenerator/generators/flight/uavobjectgeneratorflight.cpp +++ b/ground/uavobjgenerator/generators/flight/uavobjectgeneratorflight.cpp @@ -35,7 +35,7 @@ bool UAVObjectGeneratorFlight::generate(UAVObjectParser* parser,QString template QString flightObjInit,objInc,objFileNames,objNames; qint32 sizeCalc; - flightCodePath = QDir( templatepath + QString("flight/UAVObjects")); + flightCodePath = QDir( templatepath + QString("flight/targets/UAVObjects")); flightOutputPath = QDir( outputpath + QString("flight") ); flightOutputPath.mkpath(flightOutputPath.absolutePath()); From 396f210d078ba49f0363ef96d50b28d4f4f7daa9 Mon Sep 17 00:00:00 2001 From: Oleg Semyonov Date: Mon, 28 Jan 2013 03:02:04 +0200 Subject: [PATCH 28/30] Remove stray file in RemoteSystemsTempFiles --- flight/RemoteSystemsTempFiles/.project | 12 ------------ 1 file changed, 12 deletions(-) delete mode 100644 flight/RemoteSystemsTempFiles/.project diff --git a/flight/RemoteSystemsTempFiles/.project b/flight/RemoteSystemsTempFiles/.project deleted file mode 100644 index 5447a64fa..000000000 --- a/flight/RemoteSystemsTempFiles/.project +++ /dev/null @@ -1,12 +0,0 @@ - - - RemoteSystemsTempFiles - - - - - - - org.eclipse.rse.ui.remoteSystemsTempNature - - From 5fdaccc1fa3d94dd39bc17b1f0ab55a27dce2551 Mon Sep 17 00:00:00 2001 From: Alessio Morale Date: Sun, 24 Feb 2013 18:33:29 +0100 Subject: [PATCH 29/30] sim_posix: unified inc files with the rest of PiOS .h, some dir moves/cleanup, fixed some compilation issues. --- flight/PiOS.posix/Boards/pios_board.h | 10 - flight/PiOS.posix/inc/FreeRTOSConfig.h | 107 --------- flight/PiOS/Boards/pios_board.h | 2 + .../{PiOS.posix => PiOS}/Boards/sim_posix.h | 0 flight/PiOS/inc/pios_debug.h | 4 + flight/PiOS/inc/pios_initcall.h | 21 ++ flight/{PiOS.posix => PiOS}/inc/pios_posix.h | 0 flight/PiOS/inc/pios_sdcard.h | 9 +- flight/{PiOS.posix => PiOS}/inc/pios_udp.h | 0 .../{PiOS.posix => PiOS}/inc/pios_udp_priv.h | 0 flight/PiOS/pios.h | 6 +- .../pios.h => PiOS/pios_sim_posix.h} | 12 +- .../Libraries/FreeRTOS/Source/croutine.c | 0 .../FreeRTOS/Source/include/FreeRTOS.h | 0 .../FreeRTOS/Source/include/StackMacros.h | 0 .../FreeRTOS/Source/include/croutine.h | 0 .../Libraries/FreeRTOS/Source/include/list.h | 0 .../FreeRTOS/Source/include/mpu_wrappers.h | 0 .../FreeRTOS/Source/include/portable.h | 0 .../FreeRTOS/Source/include/projdefs.h | 0 .../Libraries/FreeRTOS/Source/include/queue.h | 0 .../FreeRTOS/Source/include/semphr.h | 0 .../Libraries/FreeRTOS/Source/include/task.h | 0 .../posix/Libraries/FreeRTOS/Source/list.c | 0 .../FreeRTOS/Source/portable/GCC/Posix/port.c | 0 .../GCC/Posix/port.c.documentation.txt | 0 .../Source/portable/GCC/Posix/portmacro.h | 0 .../FreeRTOS/Source/portable/MemMang/heap_3.c | 0 .../FreeRTOS/Source/portable/readme.txt | 0 .../posix/Libraries/FreeRTOS/Source/queue.c | 0 .../Libraries/FreeRTOS/Source/readme.txt | 0 .../posix/Libraries/FreeRTOS/Source/tasks.c | 0 .../posix/Libraries/FreeRTOS/library.mk | 0 flight/{PiOS.posix => PiOS}/posix/library.mk | 0 .../posix/pios_bl_helper.c | 0 .../posix/pios_board_info.c | 0 flight/{PiOS.posix => PiOS}/posix/pios_com.c | 0 flight/{PiOS.posix => PiOS}/posix/pios_crc.c | 0 .../{PiOS.posix => PiOS}/posix/pios_debug.c | 0 .../{PiOS.posix => PiOS}/posix/pios_delay.c | 0 flight/{PiOS.posix => PiOS}/posix/pios_iap.c | 0 flight/{PiOS.posix => PiOS}/posix/pios_irq.c | 0 flight/{PiOS.posix => PiOS}/posix/pios_led.c | 0 flight/{PiOS.posix => PiOS}/posix/pios_rcvr.c | 0 .../{PiOS.posix => PiOS}/posix/pios_sdcard.c | 2 +- .../{PiOS.posix => PiOS}/posix/pios_servo.c | 0 flight/{PiOS.posix => PiOS}/posix/pios_sys.c | 0 flight/{PiOS.posix => PiOS}/posix/pios_udp.c | 0 flight/{PiOS.posix => PiOS}/posix/pios_wdg.c | 3 +- .../SimPosix/System/inc/FreeRTOSConfig.h | 210 +++++++++--------- .../SimPosix/System/inc/FreeRTOSConfig_bk.h | 103 +++++++++ 51 files changed, 255 insertions(+), 234 deletions(-) delete mode 100644 flight/PiOS.posix/Boards/pios_board.h delete mode 100644 flight/PiOS.posix/inc/FreeRTOSConfig.h rename flight/{PiOS.posix => PiOS}/Boards/sim_posix.h (100%) rename flight/{PiOS.posix => PiOS}/inc/pios_posix.h (100%) rename flight/{PiOS.posix => PiOS}/inc/pios_udp.h (100%) rename flight/{PiOS.posix => PiOS}/inc/pios_udp_priv.h (100%) rename flight/{PiOS.posix/pios.h => PiOS/pios_sim_posix.h} (92%) rename flight/{PiOS.posix => PiOS}/posix/Libraries/FreeRTOS/Source/croutine.c (100%) rename flight/{PiOS.posix => PiOS}/posix/Libraries/FreeRTOS/Source/include/FreeRTOS.h (100%) rename flight/{PiOS.posix => PiOS}/posix/Libraries/FreeRTOS/Source/include/StackMacros.h (100%) rename flight/{PiOS.posix => PiOS}/posix/Libraries/FreeRTOS/Source/include/croutine.h (100%) rename flight/{PiOS.posix => PiOS}/posix/Libraries/FreeRTOS/Source/include/list.h (100%) rename flight/{PiOS.posix => PiOS}/posix/Libraries/FreeRTOS/Source/include/mpu_wrappers.h (100%) rename flight/{PiOS.posix => PiOS}/posix/Libraries/FreeRTOS/Source/include/portable.h (100%) rename flight/{PiOS.posix => PiOS}/posix/Libraries/FreeRTOS/Source/include/projdefs.h (100%) rename flight/{PiOS.posix => PiOS}/posix/Libraries/FreeRTOS/Source/include/queue.h (100%) rename flight/{PiOS.posix => PiOS}/posix/Libraries/FreeRTOS/Source/include/semphr.h (100%) rename flight/{PiOS.posix => PiOS}/posix/Libraries/FreeRTOS/Source/include/task.h (100%) rename flight/{PiOS.posix => PiOS}/posix/Libraries/FreeRTOS/Source/list.c (100%) rename flight/{PiOS.posix => PiOS}/posix/Libraries/FreeRTOS/Source/portable/GCC/Posix/port.c (100%) rename flight/{PiOS.posix => PiOS}/posix/Libraries/FreeRTOS/Source/portable/GCC/Posix/port.c.documentation.txt (100%) rename flight/{PiOS.posix => PiOS}/posix/Libraries/FreeRTOS/Source/portable/GCC/Posix/portmacro.h (100%) rename flight/{PiOS.posix => PiOS}/posix/Libraries/FreeRTOS/Source/portable/MemMang/heap_3.c (100%) rename flight/{PiOS.posix => PiOS}/posix/Libraries/FreeRTOS/Source/portable/readme.txt (100%) rename flight/{PiOS.posix => PiOS}/posix/Libraries/FreeRTOS/Source/queue.c (100%) rename flight/{PiOS.posix => PiOS}/posix/Libraries/FreeRTOS/Source/readme.txt (100%) rename flight/{PiOS.posix => PiOS}/posix/Libraries/FreeRTOS/Source/tasks.c (100%) rename flight/{PiOS.posix => PiOS}/posix/Libraries/FreeRTOS/library.mk (100%) rename flight/{PiOS.posix => PiOS}/posix/library.mk (100%) rename flight/{PiOS.posix => PiOS}/posix/pios_bl_helper.c (100%) rename flight/{PiOS.posix => PiOS}/posix/pios_board_info.c (100%) rename flight/{PiOS.posix => PiOS}/posix/pios_com.c (100%) rename flight/{PiOS.posix => PiOS}/posix/pios_crc.c (100%) rename flight/{PiOS.posix => PiOS}/posix/pios_debug.c (100%) rename flight/{PiOS.posix => PiOS}/posix/pios_delay.c (100%) rename flight/{PiOS.posix => PiOS}/posix/pios_iap.c (100%) rename flight/{PiOS.posix => PiOS}/posix/pios_irq.c (100%) rename flight/{PiOS.posix => PiOS}/posix/pios_led.c (100%) rename flight/{PiOS.posix => PiOS}/posix/pios_rcvr.c (100%) rename flight/{PiOS.posix => PiOS}/posix/pios_sdcard.c (95%) rename flight/{PiOS.posix => PiOS}/posix/pios_servo.c (100%) rename flight/{PiOS.posix => PiOS}/posix/pios_sys.c (100%) rename flight/{PiOS.posix => PiOS}/posix/pios_udp.c (100%) rename flight/{PiOS.posix => PiOS}/posix/pios_wdg.c (96%) create mode 100644 flight/targets/SimPosix/System/inc/FreeRTOSConfig_bk.h diff --git a/flight/PiOS.posix/Boards/pios_board.h b/flight/PiOS.posix/Boards/pios_board.h deleted file mode 100644 index 9917a1d23..000000000 --- a/flight/PiOS.posix/Boards/pios_board.h +++ /dev/null @@ -1,10 +0,0 @@ -#ifndef PIOS_BOARD_H_ -#define PIOS_BOARD_H_ - -#ifdef USE_SIM_POSIX -#include "sim_posix.h" -#else -#error Board definition has not been provided. -#endif - -#endif /* PIOS_BOARD_H_ */ diff --git a/flight/PiOS.posix/inc/FreeRTOSConfig.h b/flight/PiOS.posix/inc/FreeRTOSConfig.h deleted file mode 100644 index f6602c721..000000000 --- a/flight/PiOS.posix/inc/FreeRTOSConfig.h +++ /dev/null @@ -1,107 +0,0 @@ - -#ifndef FREERTOS_CONFIG_H -#define FREERTOS_CONFIG_H - -/*----------------------------------------------------------- - * Application specific definitions. - * - * These definitions should be adjusted for your particular hardware and - * application requirements. - * - * THESE PARAMETERS ARE DESCRIBED WITHIN THE 'CONFIGURATION' SECTION OF THE - * FreeRTOS API DOCUMENTATION AVAILABLE ON THE FreeRTOS.org WEB SITE. - * - * See http://www.freertos.org/a00110.html. - *----------------------------------------------------------*/ - -/* Notes: We use 5 task priorities */ - - -#ifdef __APPLE__ - #define COND_SIGNALING - #define CHECK_TASK_RESUMES - #define RUNNING_THREAD_MUTEX -// #define TICK_SIGNAL -// #define TICK_SIGWAIT - #define IDLE_SLEEPS - - #define configUSE_PREEMPTION 1 - #define configIDLE_SHOULD_YIELD 0 -#endif -#ifdef __CYGWIN__ - #define COND_SIGNALING - #define CHECK_TASK_RESUMES -// #define RUNNING_THREAD_MUTEX -// #define TICK_SIGNAL - #define TICK_SIGWAIT - #define IDLE_SLEEPS - - #define configUSE_PREEMPTION 0 - #define configIDLE_SHOULD_YIELD 1 -#endif -#ifdef __linux__ - #define COND_SIGNALING - #define CHECK_TASK_RESUMES - #define RUNNING_THREAD_MUTEX -// #define TICK_SIGNAL -// #define TICK_SIGWAIT - #define IDLE_SLEEPS - - #define configUSE_PREEMPTION 1 - #define configIDLE_SHOULD_YIELD 0 -#endif - - -#define configUSE_IDLE_HOOK 1 -#define configUSE_TICK_HOOK 0 -#define configCPU_CLOCK_HZ ( ( unsigned long ) 72000000 ) -#define configTICK_RATE_HZ ( ( portTickType ) 1000 ) -#define configMAX_PRIORITIES ( ( unsigned portBASE_TYPE ) 5 ) -#define configMINIMAL_STACK_SIZE ( ( unsigned short ) 256 ) -#define configTOTAL_HEAP_SIZE ( ( size_t ) ( 45 * 1024 ) ) -#define configMAX_TASK_NAME_LEN ( 16 ) -#define configUSE_TRACE_FACILITY 0 -#define configUSE_16_BIT_TICKS 0 -#define configUSE_MUTEXES 1 -#define configUSE_RECURSIVE_MUTEXES 1 -#define configUSE_COUNTING_SEMAPHORES 0 -#define configUSE_ALTERNATIVE_API 0 -#define configCHECK_FOR_STACK_OVERFLOW 2 -#define configQUEUE_REGISTRY_SIZE 10 - - -/* Co-routine definitions. */ -#define configUSE_CO_ROUTINES 0 -#define configMAX_CO_ROUTINE_PRIORITIES ( 2 ) - -/* Set the following definitions to 1 to include the API function, or zero -to exclude the API function. */ - -#define INCLUDE_vTaskPrioritySet 1 -#define INCLUDE_uxTaskPriorityGet 1 -#define INCLUDE_vTaskDelete 1 -#define INCLUDE_vTaskCleanUpResources 0 -#define INCLUDE_vTaskSuspend 1 -#define INCLUDE_vTaskDelayUntil 1 -#define INCLUDE_vTaskDelay 1 -#define INCLUDE_xTaskGetSchedulerState 1 -#define INCLUDE_xTaskGetCurrentTaskHandle 1 -#define INCLUDE_uxTaskGetStackHighWaterMark 0 - - - - -/* This is the raw value as per the Cortex-M3 NVIC. Values can be 255 -(lowest) to 1 (highest maskable) to 0 (highest non-maskable). */ -#define configKERNEL_INTERRUPT_PRIORITY 15 << 4 /* equivalent to NVIC priority 15 */ -#define configMAX_SYSCALL_INTERRUPT_PRIORITY 3 << 4 /* equivalent to NVIC priority 3 */ - - -/* This is the value being used as per the ST library which permits 16 -priority values, 0 to 15. This must correspond to the -configKERNEL_INTERRUPT_PRIORITY setting. Here 15 corresponds to the lowest -NVIC value of 255. */ -#define configLIBRARY_KERNEL_INTERRUPT_PRIORITY 15 - -#endif /* FREERTOS_CONFIG_H */ - diff --git a/flight/PiOS/Boards/pios_board.h b/flight/PiOS/Boards/pios_board.h index 120c7d64a..aced5f898 100644 --- a/flight/PiOS/Boards/pios_board.h +++ b/flight/PiOS/Boards/pios_board.h @@ -17,6 +17,8 @@ #include "STM32F4xx_OSD.h" #elif USE_STM32F4xx_RM #include "STM32F4xx_RevoMini.h" +#elif USE_SIM_POSIX +#include "sim_posix.h" #else #error Board definition has not been provided. #endif diff --git a/flight/PiOS.posix/Boards/sim_posix.h b/flight/PiOS/Boards/sim_posix.h similarity index 100% rename from flight/PiOS.posix/Boards/sim_posix.h rename to flight/PiOS/Boards/sim_posix.h diff --git a/flight/PiOS/inc/pios_debug.h b/flight/PiOS/inc/pios_debug.h index 4dc5f5b3e..aa3eb3332 100644 --- a/flight/PiOS/inc/pios_debug.h +++ b/flight/PiOS/inc/pios_debug.h @@ -33,9 +33,13 @@ extern const char *PIOS_DEBUG_AssertMsg; +#ifdef USE_SIM_POSIX +void PIOS_DEBUG_Init(void); +#else #include void PIOS_DEBUG_Init(const struct pios_tim_channel * channels, uint8_t num_channels); +#endif void PIOS_DEBUG_PinHigh(uint8_t pin); void PIOS_DEBUG_PinLow(uint8_t pin); void PIOS_DEBUG_PinValue8Bit(uint8_t value); diff --git a/flight/PiOS/inc/pios_initcall.h b/flight/PiOS/inc/pios_initcall.h index e242989c0..1f1dea393 100644 --- a/flight/PiOS/inc/pios_initcall.h +++ b/flight/PiOS/inc/pios_initcall.h @@ -51,6 +51,26 @@ typedef struct { /* Init module section */ extern initmodule_t __module_initcall_start[], __module_initcall_end[]; +#ifdef USE_SIM_POSIX + +extern void InitModules(); +extern void StartModules(); + +#define MODULE_INITCALL(ifn, sfn) + +#define MODULE_TASKCREATE_ALL { \ + /* Start all module threads */ \ + StartModules(); \ + } + +#define MODULE_INITIALISE_ALL { \ + /* Initialize modules */ \ + InitModules(); \ + /* Initialize the system thread */ \ + SystemModInitialize();} + +#else + /* initcalls are now grouped by functionality into separate * subsections. Ordering inside the subsections is determined * by link order. @@ -77,6 +97,7 @@ extern initmodule_t __module_initcall_start[], __module_initcall_end[]; if (fn->fn_tinit) \ (fn->fn_tinit)(); } +#endif /* USE_SIM_POSIX */ #endif /* PIOS_INITCALL_H */ /** diff --git a/flight/PiOS.posix/inc/pios_posix.h b/flight/PiOS/inc/pios_posix.h similarity index 100% rename from flight/PiOS.posix/inc/pios_posix.h rename to flight/PiOS/inc/pios_posix.h diff --git a/flight/PiOS/inc/pios_sdcard.h b/flight/PiOS/inc/pios_sdcard.h index f839b99a5..8cbe3fd9f 100644 --- a/flight/PiOS/inc/pios_sdcard.h +++ b/flight/PiOS/inc/pios_sdcard.h @@ -80,17 +80,17 @@ typedef struct { uint16_t OEM_AppliID; /* OEM/Application ID */ char ProdName[6]; /* Product Name */ uint8_t ProdRev; /* Product Revision */ - u32 ProdSN; /* Product Serial Number */ + uint32_t ProdSN; /* Product Serial Number */ uint8_t Reserved1; /* Reserved1 */ uint16_t ManufactDate; /* Manufacturing Date */ uint8_t msd_CRC; /* CRC */ uint8_t Reserved2; /* always 1 */ } SDCARDCidTypeDef; - +#ifndef USE_SIM_POSIX /* Global Variables */ extern VOLINFO PIOS_SDCARD_VolInfo; extern uint8_t PIOS_SDCARD_Sector[SECTOR_SIZE]; - +#endif /* Prototypes */ extern int32_t PIOS_SDCARD_Init(uint32_t spi_id); extern int32_t PIOS_SDCARD_PowerOn(void); @@ -106,9 +106,10 @@ extern int32_t PIOS_SDCARD_StartupLog(void); extern int32_t PIOS_SDCARD_IsMounted(); extern int32_t PIOS_SDCARD_MountFS(uint32_t StartupLog); extern int32_t PIOS_SDCARD_GetFree(void); - +#ifndef USE_SIM_POSIX extern int32_t PIOS_SDCARD_ReadBuffer(PFILEINFO fileinfo, uint8_t * buffer, uint32_t len); extern int32_t PIOS_SDCARD_ReadLine(PFILEINFO fileinfo, uint8_t * buffer, uint32_t max_len); +#endif extern int32_t PIOS_SDCARD_FileCopy(char *Source, char *Destination); extern int32_t PIOS_SDCARD_FileDelete(char *Filename); diff --git a/flight/PiOS.posix/inc/pios_udp.h b/flight/PiOS/inc/pios_udp.h similarity index 100% rename from flight/PiOS.posix/inc/pios_udp.h rename to flight/PiOS/inc/pios_udp.h diff --git a/flight/PiOS.posix/inc/pios_udp_priv.h b/flight/PiOS/inc/pios_udp_priv.h similarity index 100% rename from flight/PiOS.posix/inc/pios_udp_priv.h rename to flight/PiOS/inc/pios_udp_priv.h diff --git a/flight/PiOS/pios.h b/flight/PiOS/pios.h index 66de54a3e..2ce7e80ec 100644 --- a/flight/PiOS/pios.h +++ b/flight/PiOS/pios.h @@ -27,7 +27,9 @@ #ifndef PIOS_H #define PIOS_H - +#ifdef USE_SIM_POSIX +#include +#else /* PIOS Feature Selection */ #include "pios_config.h" @@ -169,5 +171,5 @@ #include #define NELEMENTS(x) (sizeof(x) / sizeof(*(x))) - +#endif /* USE_SIMPOSIX */ #endif /* PIOS_H */ diff --git a/flight/PiOS.posix/pios.h b/flight/PiOS/pios_sim_posix.h similarity index 92% rename from flight/PiOS.posix/pios.h rename to flight/PiOS/pios_sim_posix.h index 28e896835..b51837f3e 100644 --- a/flight/PiOS.posix/pios.h +++ b/flight/PiOS/pios_sim_posix.h @@ -25,11 +25,11 @@ */ -#ifndef PIOS_H -#define PIOS_H +#ifndef PIOS_SIM_POSIX_H +#define PIOS_SIM_POSIX_H /* PIOS Feature Selection */ -#include "pios_config.h" +#include "pios_config.h" #include #if defined(PIOS_INCLUDE_FREERTOS) @@ -49,10 +49,10 @@ #include /* Generic initcall infrastructure */ -#include "pios_initcall.h" +#include /* PIOS Board Specific Device Configuration */ -#include "pios_board.h" +#include "pios_board.h" /* PIOS Hardware Includes (posix) */ #include @@ -77,4 +77,4 @@ #define NELEMENTS(x) (sizeof(x) / sizeof(*(x))) -#endif /* PIOS_H */ +#endif /* PIOS_POSIX_H */ diff --git a/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/croutine.c b/flight/PiOS/posix/Libraries/FreeRTOS/Source/croutine.c similarity index 100% rename from flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/croutine.c rename to flight/PiOS/posix/Libraries/FreeRTOS/Source/croutine.c diff --git a/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/include/FreeRTOS.h b/flight/PiOS/posix/Libraries/FreeRTOS/Source/include/FreeRTOS.h similarity index 100% rename from flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/include/FreeRTOS.h rename to flight/PiOS/posix/Libraries/FreeRTOS/Source/include/FreeRTOS.h diff --git a/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/include/StackMacros.h b/flight/PiOS/posix/Libraries/FreeRTOS/Source/include/StackMacros.h similarity index 100% rename from flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/include/StackMacros.h rename to flight/PiOS/posix/Libraries/FreeRTOS/Source/include/StackMacros.h diff --git a/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/include/croutine.h b/flight/PiOS/posix/Libraries/FreeRTOS/Source/include/croutine.h similarity index 100% rename from flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/include/croutine.h rename to flight/PiOS/posix/Libraries/FreeRTOS/Source/include/croutine.h diff --git a/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/include/list.h b/flight/PiOS/posix/Libraries/FreeRTOS/Source/include/list.h similarity index 100% rename from flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/include/list.h rename to flight/PiOS/posix/Libraries/FreeRTOS/Source/include/list.h diff --git a/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/include/mpu_wrappers.h b/flight/PiOS/posix/Libraries/FreeRTOS/Source/include/mpu_wrappers.h similarity index 100% rename from flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/include/mpu_wrappers.h rename to flight/PiOS/posix/Libraries/FreeRTOS/Source/include/mpu_wrappers.h diff --git a/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/include/portable.h b/flight/PiOS/posix/Libraries/FreeRTOS/Source/include/portable.h similarity index 100% rename from flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/include/portable.h rename to flight/PiOS/posix/Libraries/FreeRTOS/Source/include/portable.h diff --git a/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/include/projdefs.h b/flight/PiOS/posix/Libraries/FreeRTOS/Source/include/projdefs.h similarity index 100% rename from flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/include/projdefs.h rename to flight/PiOS/posix/Libraries/FreeRTOS/Source/include/projdefs.h diff --git a/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/include/queue.h b/flight/PiOS/posix/Libraries/FreeRTOS/Source/include/queue.h similarity index 100% rename from flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/include/queue.h rename to flight/PiOS/posix/Libraries/FreeRTOS/Source/include/queue.h diff --git a/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/include/semphr.h b/flight/PiOS/posix/Libraries/FreeRTOS/Source/include/semphr.h similarity index 100% rename from flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/include/semphr.h rename to flight/PiOS/posix/Libraries/FreeRTOS/Source/include/semphr.h diff --git a/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/include/task.h b/flight/PiOS/posix/Libraries/FreeRTOS/Source/include/task.h similarity index 100% rename from flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/include/task.h rename to flight/PiOS/posix/Libraries/FreeRTOS/Source/include/task.h diff --git a/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/list.c b/flight/PiOS/posix/Libraries/FreeRTOS/Source/list.c similarity index 100% rename from flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/list.c rename to flight/PiOS/posix/Libraries/FreeRTOS/Source/list.c diff --git a/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/portable/GCC/Posix/port.c b/flight/PiOS/posix/Libraries/FreeRTOS/Source/portable/GCC/Posix/port.c similarity index 100% rename from flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/portable/GCC/Posix/port.c rename to flight/PiOS/posix/Libraries/FreeRTOS/Source/portable/GCC/Posix/port.c diff --git a/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/portable/GCC/Posix/port.c.documentation.txt b/flight/PiOS/posix/Libraries/FreeRTOS/Source/portable/GCC/Posix/port.c.documentation.txt similarity index 100% rename from flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/portable/GCC/Posix/port.c.documentation.txt rename to flight/PiOS/posix/Libraries/FreeRTOS/Source/portable/GCC/Posix/port.c.documentation.txt diff --git a/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/portable/GCC/Posix/portmacro.h b/flight/PiOS/posix/Libraries/FreeRTOS/Source/portable/GCC/Posix/portmacro.h similarity index 100% rename from flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/portable/GCC/Posix/portmacro.h rename to flight/PiOS/posix/Libraries/FreeRTOS/Source/portable/GCC/Posix/portmacro.h diff --git a/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/portable/MemMang/heap_3.c b/flight/PiOS/posix/Libraries/FreeRTOS/Source/portable/MemMang/heap_3.c similarity index 100% rename from flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/portable/MemMang/heap_3.c rename to flight/PiOS/posix/Libraries/FreeRTOS/Source/portable/MemMang/heap_3.c diff --git a/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/portable/readme.txt b/flight/PiOS/posix/Libraries/FreeRTOS/Source/portable/readme.txt similarity index 100% rename from flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/portable/readme.txt rename to flight/PiOS/posix/Libraries/FreeRTOS/Source/portable/readme.txt diff --git a/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/queue.c b/flight/PiOS/posix/Libraries/FreeRTOS/Source/queue.c similarity index 100% rename from flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/queue.c rename to flight/PiOS/posix/Libraries/FreeRTOS/Source/queue.c diff --git a/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/readme.txt b/flight/PiOS/posix/Libraries/FreeRTOS/Source/readme.txt similarity index 100% rename from flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/readme.txt rename to flight/PiOS/posix/Libraries/FreeRTOS/Source/readme.txt diff --git a/flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/tasks.c b/flight/PiOS/posix/Libraries/FreeRTOS/Source/tasks.c similarity index 100% rename from flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/tasks.c rename to flight/PiOS/posix/Libraries/FreeRTOS/Source/tasks.c diff --git a/flight/PiOS.posix/posix/Libraries/FreeRTOS/library.mk b/flight/PiOS/posix/Libraries/FreeRTOS/library.mk similarity index 100% rename from flight/PiOS.posix/posix/Libraries/FreeRTOS/library.mk rename to flight/PiOS/posix/Libraries/FreeRTOS/library.mk diff --git a/flight/PiOS.posix/posix/library.mk b/flight/PiOS/posix/library.mk similarity index 100% rename from flight/PiOS.posix/posix/library.mk rename to flight/PiOS/posix/library.mk diff --git a/flight/PiOS.posix/posix/pios_bl_helper.c b/flight/PiOS/posix/pios_bl_helper.c similarity index 100% rename from flight/PiOS.posix/posix/pios_bl_helper.c rename to flight/PiOS/posix/pios_bl_helper.c diff --git a/flight/PiOS.posix/posix/pios_board_info.c b/flight/PiOS/posix/pios_board_info.c similarity index 100% rename from flight/PiOS.posix/posix/pios_board_info.c rename to flight/PiOS/posix/pios_board_info.c diff --git a/flight/PiOS.posix/posix/pios_com.c b/flight/PiOS/posix/pios_com.c similarity index 100% rename from flight/PiOS.posix/posix/pios_com.c rename to flight/PiOS/posix/pios_com.c diff --git a/flight/PiOS.posix/posix/pios_crc.c b/flight/PiOS/posix/pios_crc.c similarity index 100% rename from flight/PiOS.posix/posix/pios_crc.c rename to flight/PiOS/posix/pios_crc.c diff --git a/flight/PiOS.posix/posix/pios_debug.c b/flight/PiOS/posix/pios_debug.c similarity index 100% rename from flight/PiOS.posix/posix/pios_debug.c rename to flight/PiOS/posix/pios_debug.c diff --git a/flight/PiOS.posix/posix/pios_delay.c b/flight/PiOS/posix/pios_delay.c similarity index 100% rename from flight/PiOS.posix/posix/pios_delay.c rename to flight/PiOS/posix/pios_delay.c diff --git a/flight/PiOS.posix/posix/pios_iap.c b/flight/PiOS/posix/pios_iap.c similarity index 100% rename from flight/PiOS.posix/posix/pios_iap.c rename to flight/PiOS/posix/pios_iap.c diff --git a/flight/PiOS.posix/posix/pios_irq.c b/flight/PiOS/posix/pios_irq.c similarity index 100% rename from flight/PiOS.posix/posix/pios_irq.c rename to flight/PiOS/posix/pios_irq.c diff --git a/flight/PiOS.posix/posix/pios_led.c b/flight/PiOS/posix/pios_led.c similarity index 100% rename from flight/PiOS.posix/posix/pios_led.c rename to flight/PiOS/posix/pios_led.c diff --git a/flight/PiOS.posix/posix/pios_rcvr.c b/flight/PiOS/posix/pios_rcvr.c similarity index 100% rename from flight/PiOS.posix/posix/pios_rcvr.c rename to flight/PiOS/posix/pios_rcvr.c diff --git a/flight/PiOS.posix/posix/pios_sdcard.c b/flight/PiOS/posix/pios_sdcard.c similarity index 95% rename from flight/PiOS.posix/posix/pios_sdcard.c rename to flight/PiOS/posix/pios_sdcard.c index 1e43c8086..d9e0b3760 100644 --- a/flight/PiOS.posix/posix/pios_sdcard.c +++ b/flight/PiOS/posix/pios_sdcard.c @@ -38,7 +38,7 @@ * \param[in] mode currently only mode 0 supported * \return < 0 if initialisation failed */ -int32_t PIOS_SDCARD_Init(void) +int32_t PIOS_SDCARD_Init(uint32_t spi_id) { /* No error */ return 0; diff --git a/flight/PiOS.posix/posix/pios_servo.c b/flight/PiOS/posix/pios_servo.c similarity index 100% rename from flight/PiOS.posix/posix/pios_servo.c rename to flight/PiOS/posix/pios_servo.c diff --git a/flight/PiOS.posix/posix/pios_sys.c b/flight/PiOS/posix/pios_sys.c similarity index 100% rename from flight/PiOS.posix/posix/pios_sys.c rename to flight/PiOS/posix/pios_sys.c diff --git a/flight/PiOS.posix/posix/pios_udp.c b/flight/PiOS/posix/pios_udp.c similarity index 100% rename from flight/PiOS.posix/posix/pios_udp.c rename to flight/PiOS/posix/pios_udp.c diff --git a/flight/PiOS.posix/posix/pios_wdg.c b/flight/PiOS/posix/pios_wdg.c similarity index 96% rename from flight/PiOS.posix/posix/pios_wdg.c rename to flight/PiOS/posix/pios_wdg.c index 3a9fcc3fb..e60bb549d 100644 --- a/flight/PiOS.posix/posix/pios_wdg.c +++ b/flight/PiOS/posix/pios_wdg.c @@ -51,8 +51,9 @@ * @param[in] delayMs The delay period in ms * @returns Maximum recommended delay between updates */ -void PIOS_WDG_Init() +uint16_t PIOS_WDG_Init() { + return 0; } /** diff --git a/flight/targets/SimPosix/System/inc/FreeRTOSConfig.h b/flight/targets/SimPosix/System/inc/FreeRTOSConfig.h index 72d6e288a..f6602c721 100644 --- a/flight/targets/SimPosix/System/inc/FreeRTOSConfig.h +++ b/flight/targets/SimPosix/System/inc/FreeRTOSConfig.h @@ -1,103 +1,107 @@ - -#ifndef FREERTOS_CONFIG_H -#define FREERTOS_CONFIG_H - -/*----------------------------------------------------------- - * Application specific definitions. - * - * These definitions should be adjusted for your particular hardware and - * application requirements. - * - * THESE PARAMETERS ARE DESCRIBED WITHIN THE 'CONFIGURATION' SECTION OF THE - * FreeRTOS API DOCUMENTATION AVAILABLE ON THE FreeRTOS.org WEB SITE. - * - * See http://www.freertos.org/a00110.html. - *----------------------------------------------------------*/ - -/** - * @addtogroup PIOS PIOS - * @{ - * @addtogroup FreeRTOS FreeRTOS - * @{ - */ - -/* Notes: We use 5 task priorities */ - -#define configCPU_CLOCK_HZ (SYSCLK_FREQ) // really the NVIC clock ... -#define configTICK_RATE_HZ ((portTickType )1000) -#define configMAX_PRIORITIES ((unsigned portBASE_TYPE)5) -#define configMINIMAL_STACK_SIZE ((unsigned short)512) -#define configTOTAL_HEAP_SIZE ((size_t)(180 * 1024)) // this is minimum, not total -#define configMAX_TASK_NAME_LEN (16) - -#define configUSE_PREEMPTION 1 -#define configUSE_IDLE_HOOK 1 -#define configUSE_TICK_HOOK 0 -#define configUSE_TRACE_FACILITY 0 -#define configUSE_16_BIT_TICKS 0 -#define configIDLE_SHOULD_YIELD 0 -#define configUSE_MUTEXES 1 -#define configUSE_RECURSIVE_MUTEXES 1 -#define configUSE_COUNTING_SEMAPHORES 0 -#define configUSE_ALTERNATIVE_API 0 -#define configCHECK_FOR_STACK_OVERFLOW 2 -#define configQUEUE_REGISTRY_SIZE 10 - -#define configUSE_TIMERS 1 -#define configTIMER_TASK_PRIORITY (configMAX_PRIORITIES - 1) /* run timers at max priority */ -#define configTIMER_QUEUE_LENGTH 10 -#define configTIMER_TASK_STACK_DEPTH configMINIMAL_STACK_SIZE - -/* Co-routine definitions. */ -#define configUSE_CO_ROUTINES 0 -//#define configMAX_CO_ROUTINE_PRIORITIES ( 2 ) - -/* Set the following definitions to 1 to include the API function, or zero -to exclude the API function. */ - -#define INCLUDE_vTaskPrioritySet 1 -#define INCLUDE_uxTaskPriorityGet 1 -#define INCLUDE_vTaskDelete 1 -#define INCLUDE_vTaskCleanUpResources 1 -#define INCLUDE_vTaskSuspend 1 -#define INCLUDE_vTaskDelayUntil 1 -#define INCLUDE_vTaskDelay 1 -#define INCLUDE_xTaskGetSchedulerState 1 -#define INCLUDE_xTaskGetCurrentTaskHandle 1 -#define INCLUDE_uxTaskGetStackHighWaterMark 1 - -/* This is the raw value as per the Cortex-M3 NVIC. Values can be 255 -(lowest) to 1 (highest maskable) to 0 (highest non-maskable). */ -#define configKERNEL_INTERRUPT_PRIORITY 15 << 4 /* equivalent to NVIC priority 15 */ -#define configMAX_SYSCALL_INTERRUPT_PRIORITY 3 << 4 /* equivalent to NVIC priority 3 */ - -/* This is the value being used as per the ST library which permits 16 -priority values, 0 to 15. This must correspond to the -configKERNEL_INTERRUPT_PRIORITY setting. Here 15 corresponds to the lowest -NVIC value of 255. */ -#define configLIBRARY_KERNEL_INTERRUPT_PRIORITY 15 - -/* Enable run time stats collection */ -#define configGENERATE_RUN_TIME_STATS 1 -#define INCLUDE_uxTaskGetRunTime 1 - -/* - * Once we move to CMSIS2 we can at least use: - * - * CoreDebug->DEMCR |= CoreDebug_DEMCR_TRCENA_Msk; - * - * (still nothing for the DWT registers, surprisingly) - */ -#define portCONFIGURE_TIMER_FOR_RUN_TIME_STATS() \ - do { \ - (*(unsigned long *)0xe000edfc) |= (1<<24); /* DEMCR |= DEMCR_TRCENA */ \ - (*(unsigned long *)0xe0001000) |= 1; /* DWT_CTRL |= DWT_CYCCNT_ENA */ \ - } while(0) -#define portGET_RUN_TIME_COUNTER_VALUE() (*(unsigned long *)0xe0001004) /* DWT_CYCCNT */ - - -/** - * @} - */ - -#endif /* FREERTOS_CONFIG_H */ + +#ifndef FREERTOS_CONFIG_H +#define FREERTOS_CONFIG_H + +/*----------------------------------------------------------- + * Application specific definitions. + * + * These definitions should be adjusted for your particular hardware and + * application requirements. + * + * THESE PARAMETERS ARE DESCRIBED WITHIN THE 'CONFIGURATION' SECTION OF THE + * FreeRTOS API DOCUMENTATION AVAILABLE ON THE FreeRTOS.org WEB SITE. + * + * See http://www.freertos.org/a00110.html. + *----------------------------------------------------------*/ + +/* Notes: We use 5 task priorities */ + + +#ifdef __APPLE__ + #define COND_SIGNALING + #define CHECK_TASK_RESUMES + #define RUNNING_THREAD_MUTEX +// #define TICK_SIGNAL +// #define TICK_SIGWAIT + #define IDLE_SLEEPS + + #define configUSE_PREEMPTION 1 + #define configIDLE_SHOULD_YIELD 0 +#endif +#ifdef __CYGWIN__ + #define COND_SIGNALING + #define CHECK_TASK_RESUMES +// #define RUNNING_THREAD_MUTEX +// #define TICK_SIGNAL + #define TICK_SIGWAIT + #define IDLE_SLEEPS + + #define configUSE_PREEMPTION 0 + #define configIDLE_SHOULD_YIELD 1 +#endif +#ifdef __linux__ + #define COND_SIGNALING + #define CHECK_TASK_RESUMES + #define RUNNING_THREAD_MUTEX +// #define TICK_SIGNAL +// #define TICK_SIGWAIT + #define IDLE_SLEEPS + + #define configUSE_PREEMPTION 1 + #define configIDLE_SHOULD_YIELD 0 +#endif + + +#define configUSE_IDLE_HOOK 1 +#define configUSE_TICK_HOOK 0 +#define configCPU_CLOCK_HZ ( ( unsigned long ) 72000000 ) +#define configTICK_RATE_HZ ( ( portTickType ) 1000 ) +#define configMAX_PRIORITIES ( ( unsigned portBASE_TYPE ) 5 ) +#define configMINIMAL_STACK_SIZE ( ( unsigned short ) 256 ) +#define configTOTAL_HEAP_SIZE ( ( size_t ) ( 45 * 1024 ) ) +#define configMAX_TASK_NAME_LEN ( 16 ) +#define configUSE_TRACE_FACILITY 0 +#define configUSE_16_BIT_TICKS 0 +#define configUSE_MUTEXES 1 +#define configUSE_RECURSIVE_MUTEXES 1 +#define configUSE_COUNTING_SEMAPHORES 0 +#define configUSE_ALTERNATIVE_API 0 +#define configCHECK_FOR_STACK_OVERFLOW 2 +#define configQUEUE_REGISTRY_SIZE 10 + + +/* Co-routine definitions. */ +#define configUSE_CO_ROUTINES 0 +#define configMAX_CO_ROUTINE_PRIORITIES ( 2 ) + +/* Set the following definitions to 1 to include the API function, or zero +to exclude the API function. */ + +#define INCLUDE_vTaskPrioritySet 1 +#define INCLUDE_uxTaskPriorityGet 1 +#define INCLUDE_vTaskDelete 1 +#define INCLUDE_vTaskCleanUpResources 0 +#define INCLUDE_vTaskSuspend 1 +#define INCLUDE_vTaskDelayUntil 1 +#define INCLUDE_vTaskDelay 1 +#define INCLUDE_xTaskGetSchedulerState 1 +#define INCLUDE_xTaskGetCurrentTaskHandle 1 +#define INCLUDE_uxTaskGetStackHighWaterMark 0 + + + + +/* This is the raw value as per the Cortex-M3 NVIC. Values can be 255 +(lowest) to 1 (highest maskable) to 0 (highest non-maskable). */ +#define configKERNEL_INTERRUPT_PRIORITY 15 << 4 /* equivalent to NVIC priority 15 */ +#define configMAX_SYSCALL_INTERRUPT_PRIORITY 3 << 4 /* equivalent to NVIC priority 3 */ + + +/* This is the value being used as per the ST library which permits 16 +priority values, 0 to 15. This must correspond to the +configKERNEL_INTERRUPT_PRIORITY setting. Here 15 corresponds to the lowest +NVIC value of 255. */ +#define configLIBRARY_KERNEL_INTERRUPT_PRIORITY 15 + +#endif /* FREERTOS_CONFIG_H */ + diff --git a/flight/targets/SimPosix/System/inc/FreeRTOSConfig_bk.h b/flight/targets/SimPosix/System/inc/FreeRTOSConfig_bk.h new file mode 100644 index 000000000..72d6e288a --- /dev/null +++ b/flight/targets/SimPosix/System/inc/FreeRTOSConfig_bk.h @@ -0,0 +1,103 @@ + +#ifndef FREERTOS_CONFIG_H +#define FREERTOS_CONFIG_H + +/*----------------------------------------------------------- + * Application specific definitions. + * + * These definitions should be adjusted for your particular hardware and + * application requirements. + * + * THESE PARAMETERS ARE DESCRIBED WITHIN THE 'CONFIGURATION' SECTION OF THE + * FreeRTOS API DOCUMENTATION AVAILABLE ON THE FreeRTOS.org WEB SITE. + * + * See http://www.freertos.org/a00110.html. + *----------------------------------------------------------*/ + +/** + * @addtogroup PIOS PIOS + * @{ + * @addtogroup FreeRTOS FreeRTOS + * @{ + */ + +/* Notes: We use 5 task priorities */ + +#define configCPU_CLOCK_HZ (SYSCLK_FREQ) // really the NVIC clock ... +#define configTICK_RATE_HZ ((portTickType )1000) +#define configMAX_PRIORITIES ((unsigned portBASE_TYPE)5) +#define configMINIMAL_STACK_SIZE ((unsigned short)512) +#define configTOTAL_HEAP_SIZE ((size_t)(180 * 1024)) // this is minimum, not total +#define configMAX_TASK_NAME_LEN (16) + +#define configUSE_PREEMPTION 1 +#define configUSE_IDLE_HOOK 1 +#define configUSE_TICK_HOOK 0 +#define configUSE_TRACE_FACILITY 0 +#define configUSE_16_BIT_TICKS 0 +#define configIDLE_SHOULD_YIELD 0 +#define configUSE_MUTEXES 1 +#define configUSE_RECURSIVE_MUTEXES 1 +#define configUSE_COUNTING_SEMAPHORES 0 +#define configUSE_ALTERNATIVE_API 0 +#define configCHECK_FOR_STACK_OVERFLOW 2 +#define configQUEUE_REGISTRY_SIZE 10 + +#define configUSE_TIMERS 1 +#define configTIMER_TASK_PRIORITY (configMAX_PRIORITIES - 1) /* run timers at max priority */ +#define configTIMER_QUEUE_LENGTH 10 +#define configTIMER_TASK_STACK_DEPTH configMINIMAL_STACK_SIZE + +/* Co-routine definitions. */ +#define configUSE_CO_ROUTINES 0 +//#define configMAX_CO_ROUTINE_PRIORITIES ( 2 ) + +/* Set the following definitions to 1 to include the API function, or zero +to exclude the API function. */ + +#define INCLUDE_vTaskPrioritySet 1 +#define INCLUDE_uxTaskPriorityGet 1 +#define INCLUDE_vTaskDelete 1 +#define INCLUDE_vTaskCleanUpResources 1 +#define INCLUDE_vTaskSuspend 1 +#define INCLUDE_vTaskDelayUntil 1 +#define INCLUDE_vTaskDelay 1 +#define INCLUDE_xTaskGetSchedulerState 1 +#define INCLUDE_xTaskGetCurrentTaskHandle 1 +#define INCLUDE_uxTaskGetStackHighWaterMark 1 + +/* This is the raw value as per the Cortex-M3 NVIC. Values can be 255 +(lowest) to 1 (highest maskable) to 0 (highest non-maskable). */ +#define configKERNEL_INTERRUPT_PRIORITY 15 << 4 /* equivalent to NVIC priority 15 */ +#define configMAX_SYSCALL_INTERRUPT_PRIORITY 3 << 4 /* equivalent to NVIC priority 3 */ + +/* This is the value being used as per the ST library which permits 16 +priority values, 0 to 15. This must correspond to the +configKERNEL_INTERRUPT_PRIORITY setting. Here 15 corresponds to the lowest +NVIC value of 255. */ +#define configLIBRARY_KERNEL_INTERRUPT_PRIORITY 15 + +/* Enable run time stats collection */ +#define configGENERATE_RUN_TIME_STATS 1 +#define INCLUDE_uxTaskGetRunTime 1 + +/* + * Once we move to CMSIS2 we can at least use: + * + * CoreDebug->DEMCR |= CoreDebug_DEMCR_TRCENA_Msk; + * + * (still nothing for the DWT registers, surprisingly) + */ +#define portCONFIGURE_TIMER_FOR_RUN_TIME_STATS() \ + do { \ + (*(unsigned long *)0xe000edfc) |= (1<<24); /* DEMCR |= DEMCR_TRCENA */ \ + (*(unsigned long *)0xe0001000) |= 1; /* DWT_CTRL |= DWT_CYCCNT_ENA */ \ + } while(0) +#define portGET_RUN_TIME_COUNTER_VALUE() (*(unsigned long *)0xe0001004) /* DWT_CYCCNT */ + + +/** + * @} + */ + +#endif /* FREERTOS_CONFIG_H */ From d26aaa6f6d3aa9855aed6b14d4699be0d9f453b9 Mon Sep 17 00:00:00 2001 From: Alessio Morale Date: Sun, 24 Feb 2013 20:59:51 +0100 Subject: [PATCH 30/30] sim_posix Removed unused files --- flight/PiOS.posix/inc/pios_bl_helper.h | 46 --------- flight/PiOS.posix/inc/pios_board_info.h | 24 ----- flight/PiOS.posix/inc/pios_com.h | 65 ------------ flight/PiOS.posix/inc/pios_com_priv.h | 44 -------- flight/PiOS.posix/inc/pios_crc.h | 31 ------ flight/PiOS.posix/inc/pios_debug.h | 56 ---------- flight/PiOS.posix/inc/pios_delay.h | 48 --------- flight/PiOS.posix/inc/pios_iap.h | 45 -------- flight/PiOS.posix/inc/pios_initcall.h | 72 ------------- flight/PiOS.posix/inc/pios_irq.h | 38 ------- flight/PiOS.posix/inc/pios_led.h | 39 ------- flight/PiOS.posix/inc/pios_rcvr.h | 57 ----------- flight/PiOS.posix/inc/pios_rcvr_priv.h | 48 --------- flight/PiOS.posix/inc/pios_sdcard.h | 113 --------------------- flight/PiOS.posix/inc/pios_servo.h | 43 -------- flight/PiOS.posix/inc/pios_struct_helper.h | 12 --- flight/PiOS.posix/inc/pios_sys.h | 50 --------- flight/PiOS.posix/inc/pios_wdg.h | 45 -------- 18 files changed, 876 deletions(-) delete mode 100644 flight/PiOS.posix/inc/pios_bl_helper.h delete mode 100644 flight/PiOS.posix/inc/pios_board_info.h delete mode 100644 flight/PiOS.posix/inc/pios_com.h delete mode 100644 flight/PiOS.posix/inc/pios_com_priv.h delete mode 100644 flight/PiOS.posix/inc/pios_crc.h delete mode 100644 flight/PiOS.posix/inc/pios_debug.h delete mode 100644 flight/PiOS.posix/inc/pios_delay.h delete mode 100644 flight/PiOS.posix/inc/pios_iap.h delete mode 100644 flight/PiOS.posix/inc/pios_initcall.h delete mode 100644 flight/PiOS.posix/inc/pios_irq.h delete mode 100644 flight/PiOS.posix/inc/pios_led.h delete mode 100644 flight/PiOS.posix/inc/pios_rcvr.h delete mode 100644 flight/PiOS.posix/inc/pios_rcvr_priv.h delete mode 100644 flight/PiOS.posix/inc/pios_sdcard.h delete mode 100644 flight/PiOS.posix/inc/pios_servo.h delete mode 100644 flight/PiOS.posix/inc/pios_struct_helper.h delete mode 100644 flight/PiOS.posix/inc/pios_sys.h delete mode 100644 flight/PiOS.posix/inc/pios_wdg.h diff --git a/flight/PiOS.posix/inc/pios_bl_helper.h b/flight/PiOS.posix/inc/pios_bl_helper.h deleted file mode 100644 index e2e9e694e..000000000 --- a/flight/PiOS.posix/inc/pios_bl_helper.h +++ /dev/null @@ -1,46 +0,0 @@ -/** - ****************************************************************************** - * @addtogroup PIOS PIOS Core hardware abstraction layer - * @{ - * @addtogroup PIOS_BOOTLOADER Functions - * @brief HAL code to interface to the OpenPilot AHRS module - * @{ - * - * @file pios_bl_helper.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Bootloader Helper Functions - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef PIOS_BL_HELPER_H_ -#define PIOS_BL_HELPER_H_ - -extern uint8_t *PIOS_BL_HELPER_FLASH_If_Read(uint32_t SectorAddress); - -extern uint8_t PIOS_BL_HELPER_FLASH_Ini(); - -extern uint32_t PIOS_BL_HELPER_CRC_Memory_Calc(); - -extern void PIOS_BL_HELPER_FLASH_Read_Description(uint8_t * array, uint8_t size); - -extern uint8_t PIOS_BL_HELPER_FLASH_Start(); - -extern void PIOS_BL_HELPER_CRC_Ini(); - -#endif /* PIOS_BL_HELPER_H_ */ diff --git a/flight/PiOS.posix/inc/pios_board_info.h b/flight/PiOS.posix/inc/pios_board_info.h deleted file mode 100644 index 3ff7aa886..000000000 --- a/flight/PiOS.posix/inc/pios_board_info.h +++ /dev/null @@ -1,24 +0,0 @@ -#ifndef PIOS_BOARD_INFO_H -#define PIOS_BOARD_INFO_H - -#include /* uint* */ - -#define PIOS_BOARD_INFO_BLOB_MAGIC 0xBDBDBDBD - -struct pios_board_info { - uint32_t magic; - uint8_t board_type; - uint8_t board_rev; - uint8_t bl_rev; - uint8_t hw_type; - uint32_t fw_base; - uint32_t fw_size; - uint32_t desc_base; - uint32_t desc_size; - uint32_t ee_base; - uint32_t ee_size; -} __attribute__((packed)); - -extern const struct pios_board_info pios_board_info_blob; - -#endif /* PIOS_BOARD_INFO_H */ diff --git a/flight/PiOS.posix/inc/pios_com.h b/flight/PiOS.posix/inc/pios_com.h deleted file mode 100644 index cbee33735..000000000 --- a/flight/PiOS.posix/inc/pios_com.h +++ /dev/null @@ -1,65 +0,0 @@ -/** - ****************************************************************************** - * @addtogroup PIOS PIOS Core hardware abstraction layer - * @{ - * @addtogroup PIOS_COM COM layer functions - * @brief Hardware communication layer - * @{ - * - * @file pios_com.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * Parts by Thorsten Klose (tk@midibox.org) - * @brief COM layer functions header - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef PIOS_COM_H -#define PIOS_COM_H - -typedef uint16_t (*pios_com_callback)(uint32_t context, uint8_t * buf, uint16_t buf_len, uint16_t * headroom, bool * task_woken); - -struct pios_com_driver { - void (*init)(uint32_t id); - void (*set_baud)(uint32_t id, uint32_t baud); - void (*tx_start)(uint32_t id, uint16_t tx_bytes_avail); - void (*rx_start)(uint32_t id, uint16_t rx_bytes_avail); - void (*bind_rx_cb)(uint32_t id, pios_com_callback rx_in_cb, uint32_t context); - void (*bind_tx_cb)(uint32_t id, pios_com_callback tx_out_cb, uint32_t context); -}; - -/* Public Functions */ -extern int32_t PIOS_COM_Init(uint32_t * com_id, const struct pios_com_driver * driver, uint32_t lower_id, uint8_t * rx_buffer, uint16_t rx_buffer_len, uint8_t * tx_buffer, uint16_t tx_buffer_len); -extern int32_t PIOS_COM_ChangeBaud(uint32_t com_id, uint32_t baud); -extern int32_t PIOS_COM_SendCharNonBlocking(uint32_t com_id, char c); -extern int32_t PIOS_COM_SendChar(uint32_t com_id, char c); -extern int32_t PIOS_COM_SendBufferNonBlocking(uint32_t com_id, const uint8_t *buffer, uint16_t len); -extern int32_t PIOS_COM_SendBuffer(uint32_t com_id, const uint8_t *buffer, uint16_t len); -extern int32_t PIOS_COM_SendStringNonBlocking(uint32_t com_id, const char *str); -extern int32_t PIOS_COM_SendString(uint32_t com_id, const char *str); -extern int32_t PIOS_COM_SendFormattedStringNonBlocking(uint32_t com_id, const char *format, ...); -extern int32_t PIOS_COM_SendFormattedString(uint32_t com_id, const char *format, ...); -extern uint16_t PIOS_COM_ReceiveBuffer(uint32_t com_id, uint8_t * buf, uint16_t buf_len, uint32_t timeout_ms); -extern int32_t PIOS_COM_ReceiveBufferUsed(uint32_t com_id); - -#endif /* PIOS_COM_H */ - -/** - * @} - * @} - */ diff --git a/flight/PiOS.posix/inc/pios_com_priv.h b/flight/PiOS.posix/inc/pios_com_priv.h deleted file mode 100644 index 54af82bcb..000000000 --- a/flight/PiOS.posix/inc/pios_com_priv.h +++ /dev/null @@ -1,44 +0,0 @@ -/** - ****************************************************************************** - * @addtogroup PIOS PIOS Core hardware abstraction layer - * @{ - * @addtogroup PIOS_COM COM layer functions - * @brief Hardware communication layer - * @{ - * - * @file pios_com_priv.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * Parts by Thorsten Klose (tk@midibox.org) - * @brief COM private definitions. - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef PIOS_COM_PRIV_H -#define PIOS_COM_PRIV_H - -#include - -extern int32_t PIOS_COM_ReceiveHandler(uint32_t com_id); - -#endif /* PIOS_COM_PRIV_H */ - -/** - * @} - * @} - */ diff --git a/flight/PiOS.posix/inc/pios_crc.h b/flight/PiOS.posix/inc/pios_crc.h deleted file mode 100644 index 3a64f8bab..000000000 --- a/flight/PiOS.posix/inc/pios_crc.h +++ /dev/null @@ -1,31 +0,0 @@ -/** - ****************************************************************************** - * @addtogroup PIOS PIOS Core hardware abstraction layer - * @{ - * @addtogroup PIOS_CRC CRC Functions - * @{ - * - * @file pios_crc.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief CRC functions header. - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -uint8_t PIOS_CRC_updateByte(uint8_t crc, const uint8_t data); -uint8_t PIOS_CRC_updateCRC(uint8_t crc, const uint8_t* data, int32_t length); diff --git a/flight/PiOS.posix/inc/pios_debug.h b/flight/PiOS.posix/inc/pios_debug.h deleted file mode 100644 index e663d224e..000000000 --- a/flight/PiOS.posix/inc/pios_debug.h +++ /dev/null @@ -1,56 +0,0 @@ -/** - ****************************************************************************** - * @addtogroup PIOS PIOS Core hardware abstraction layer - * @{ - * @defgroup PIOS_DEBUG Debugging Functions - * @brief Debugging functionality - * @{ - * - * @file pios_i2c.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Debug helper functions header. - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef PIOS_DEBUG_H -#define PIOS_DEBUG_H - -extern const char *PIOS_DEBUG_AssertMsg; - -void PIOS_DEBUG_Init(void); -void PIOS_DEBUG_PinHigh(uint8_t pin); -void PIOS_DEBUG_PinLow(uint8_t pin); -void PIOS_DEBUG_PinValue8Bit(uint8_t value); -void PIOS_DEBUG_PinValue4BitL(uint8_t value); -void PIOS_DEBUG_Panic(const char *msg); - -#ifdef DEBUG -#define PIOS_DEBUG_Assert(test) if (!(test)) PIOS_DEBUG_Panic(PIOS_DEBUG_AssertMsg); -#define PIOS_Assert(test) PIOS_DEBUG_Assert(test) -#else -#define PIOS_DEBUG_Assert(test) -#define PIOS_Assert(test) if (!(test)) while (1); -#endif - -#endif /* PIOS_DEBUG_H */ - -/** - * @} - * @} - */ diff --git a/flight/PiOS.posix/inc/pios_delay.h b/flight/PiOS.posix/inc/pios_delay.h deleted file mode 100644 index 4b79e3ef1..000000000 --- a/flight/PiOS.posix/inc/pios_delay.h +++ /dev/null @@ -1,48 +0,0 @@ -/** - ****************************************************************************** - * @addtogroup PIOS PIOS Core hardware abstraction layer - * @{ - * @addtogroup PIOS_DELAY Delay Functions - * @brief PiOS Delay functionality - * @{ - * - * @file pios_settings.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Settings functions header - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef PIOS_DELAY_H -#define PIOS_DELAY_H - -/* Public Functions */ -extern int32_t PIOS_DELAY_Init(void); -extern int32_t PIOS_DELAY_WaituS(uint32_t uS); -extern int32_t PIOS_DELAY_WaitmS(uint32_t mS); -extern uint32_t PIOS_DELAY_GetuS(); -extern uint32_t PIOS_DELAY_GetuSSince(uint32_t t); -extern uint32_t PIOS_DELAY_GetRaw(); -extern uint32_t PIOS_DELAY_DiffuS(uint32_t raw); - -#endif /* PIOS_DELAY_H */ - -/** - * @} - * @} - */ diff --git a/flight/PiOS.posix/inc/pios_iap.h b/flight/PiOS.posix/inc/pios_iap.h deleted file mode 100644 index d9b41170b..000000000 --- a/flight/PiOS.posix/inc/pios_iap.h +++ /dev/null @@ -1,45 +0,0 @@ -/*! - * @File iap.h - * @Brief Header file for the In-Application-Programming Module - * - * Created on: Sep 6, 2010 - * Author: joe - */ - -#ifndef PIOS_IAP_H_ -#define PIOS_IAP_H_ - - -/**************************************************************************************** - * Header files - ****************************************************************************************/ - -/***************************************************************************************** - * Public Definitions/Macros - ****************************************************************************************/ -#if defined(STM32F4XX) -#define MAGIC_REG_1 RTC_BKP_DR1 -#define MAGIC_REG_2 RTC_BKP_DR2 -#define IAP_BOOTCOUNT RTC_BKP_DR3 -#else -#define MAGIC_REG_1 BKP_DR1 -#define MAGIC_REG_2 BKP_DR2 -#define IAP_BOOTCOUNT BKP_DR3 -#endif - -/**************************************************************************************** - * Public Functions - ****************************************************************************************/ -void PIOS_IAP_Init(void); -uint32_t PIOS_IAP_CheckRequest( void ); -void PIOS_IAP_SetRequest1(void); -void PIOS_IAP_SetRequest2(void); -void PIOS_IAP_ClearRequest(void); -uint16_t PIOS_IAP_ReadBootCount(void); -void PIOS_IAP_WriteBootCount(uint16_t); - -/**************************************************************************************** - * Public Data - ****************************************************************************************/ - -#endif /* PIOS_IAP_H_ */ diff --git a/flight/PiOS.posix/inc/pios_initcall.h b/flight/PiOS.posix/inc/pios_initcall.h deleted file mode 100644 index f88081c33..000000000 --- a/flight/PiOS.posix/inc/pios_initcall.h +++ /dev/null @@ -1,72 +0,0 @@ -/** - ****************************************************************************** - * @addtogroup PIOS PIOS Initcall infrastructure - * @{ - * @addtogroup PIOS_INITCALL Generic Initcall Macros - * @brief Initcall Macros - * @{ - * - * @file pios_initcall.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2011. - * @brief Initcall header - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef PIOS_INITCALL_H -#define PIOS_INITCALL_H - -/** - * Just a stub define to make things compile. - * Automatically link based initialization currently doesn't work - * since posix really runs on a multitude of architectures - * and we cannot define a linker script for each of them atm - */ - - -typedef int32_t (*initcall_t)(void); -typedef struct { - initcall_t fn_minit; - initcall_t fn_tinit; -} initmodule_t; - -/* Init module section */ -extern initmodule_t __module_initcall_start[], __module_initcall_end[]; - -extern void InitModules(); -extern void StartModules(); - -#define MODULE_INITCALL(ifn, sfn) - -#define MODULE_TASKCREATE_ALL { \ - /* Start all module threads */ \ - StartModules(); \ - } - -#define MODULE_INITIALISE_ALL { \ - /* Initialize modules */ \ - InitModules(); \ - /* Initialize the system thread */ \ - SystemModInitialize();} - -#endif /* PIOS_INITCALL_H */ - -/** - * @} - * @} - */ diff --git a/flight/PiOS.posix/inc/pios_irq.h b/flight/PiOS.posix/inc/pios_irq.h deleted file mode 100644 index f9b9dbb97..000000000 --- a/flight/PiOS.posix/inc/pios_irq.h +++ /dev/null @@ -1,38 +0,0 @@ -/** - ****************************************************************************** - * @addtogroup PIOS PIOS Core hardware abstraction layer - * @{ - * @addtogroup PIOS_IRQ IRQ Setup Functions - * @{ - * - * @file pios_irq.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * Parts by Thorsten Klose (tk@midibox.org) - * @brief IRQ functions header. - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef PIOS_IRQ_H -#define PIOS_IRQ_H - -/* Public Functions */ -extern int32_t PIOS_IRQ_Disable(void); -extern int32_t PIOS_IRQ_Enable(void); - -#endif /* PIOS_IRQ_H */ diff --git a/flight/PiOS.posix/inc/pios_led.h b/flight/PiOS.posix/inc/pios_led.h deleted file mode 100644 index 6ce08b0a0..000000000 --- a/flight/PiOS.posix/inc/pios_led.h +++ /dev/null @@ -1,39 +0,0 @@ -/** - ****************************************************************************** - * @addtogroup PIOS PIOS Core hardware abstraction layer - * @{ - * @addtogroup PIOS_LED LED Functions - * @{ - * - * @file pios_led.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief LED functions header. - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef PIOS_LED_H -#define PIOS_LED_H - -/* Public Functions */ -extern void PIOS_LED_On(uint32_t led_id); -extern void PIOS_LED_Off(uint32_t led_id); -extern void PIOS_LED_Toggle(uint32_t led_id); -extern void PIOS_LED_Init(); - -#endif /* PIOS_LED_H */ diff --git a/flight/PiOS.posix/inc/pios_rcvr.h b/flight/PiOS.posix/inc/pios_rcvr.h deleted file mode 100644 index ab493cd35..000000000 --- a/flight/PiOS.posix/inc/pios_rcvr.h +++ /dev/null @@ -1,57 +0,0 @@ -/** - ****************************************************************************** - * @addtogroup PIOS PIOS Core hardware abstraction layer - * @{ - * @addtogroup PIOS_RCVR RCVR layer functions - * @brief Hardware communication layer - * @{ - * - * @file pios_rcvr.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief RCVR layer functions header - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef PIOS_RCVR_H -#define PIOS_RCVR_H - -struct pios_rcvr_driver { - void (*init)(uint32_t id); - int32_t (*read)(uint32_t id, uint8_t channel); -}; - -/* Public Functions */ -extern int32_t PIOS_RCVR_Read(uint32_t rcvr_id, uint8_t channel); - -/*! Define error codes for PIOS_RCVR_Get */ -enum PIOS_RCVR_errors { - /*! Indicates that a failsafe condition or missing receiver detected for that channel */ - PIOS_RCVR_TIMEOUT = 0, - /*! Channel is invalid for this driver (usually out of range supported) */ - PIOS_RCVR_INVALID = -1, - /*! Indicates that the driver for this channel has not been initialized */ - PIOS_RCVR_NODRIVER = -2 -}; - -#endif /* PIOS_RCVR_H */ - -/** - * @} - * @} - */ diff --git a/flight/PiOS.posix/inc/pios_rcvr_priv.h b/flight/PiOS.posix/inc/pios_rcvr_priv.h deleted file mode 100644 index 968dc2116..000000000 --- a/flight/PiOS.posix/inc/pios_rcvr_priv.h +++ /dev/null @@ -1,48 +0,0 @@ -/** - ****************************************************************************** - * @addtogroup PIOS PIOS Core hardware abstraction layer - * @{ - * @addtogroup PIOS_RCVR RCVR Functions - * @brief PIOS interface for RCVR drivers - * @{ - * - * @file pios_rcvr_priv.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * Parts by Thorsten Klose (tk@midibox.org) - * @brief USART private definitions. - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef PIOS_RCVR_PRIV_H -#define PIOS_RCVR_PRIV_H - -#include - -extern uint32_t pios_rcvr_max_channel; - -extern int32_t PIOS_RCVR_Init(uint32_t * rcvr_id, const struct pios_rcvr_driver * driver, const uint32_t lower_id); - -extern void PIOS_RCVR_IRQ_Handler(uint32_t rcvr_id); - -#endif /* PIOS_RCVR_PRIV_H */ - -/** - * @} - * @} - */ diff --git a/flight/PiOS.posix/inc/pios_sdcard.h b/flight/PiOS.posix/inc/pios_sdcard.h deleted file mode 100644 index 225d9de80..000000000 --- a/flight/PiOS.posix/inc/pios_sdcard.h +++ /dev/null @@ -1,113 +0,0 @@ -/** - ****************************************************************************** - * - * @file pios_sdcard.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * Parts by Thorsten Klose (tk@midibox.org) - * @brief System and hardware Init functions header. - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef PIOS_SDCARD_H -#define PIOS_SDCARD_H - -#if defined(PIOS_INCLUDE_SDCARD) - -/* Public Functions */ -typedef struct { - uint8_t CSDStruct; /* CSD structure */ - uint8_t SysSpecVersion; /* System specification version */ - uint8_t Reserved1; /* Reserved */ - uint8_t TAAC; /* Data read access-time 1 */ - uint8_t NSAC; /* Data read access-time 2 in CLK cycles */ - uint8_t MaxBusClkFrec; /* Max. bus clock frequency */ - uint16_t CardComdClasses; /* Card command classes */ - uint8_t RdBlockLen; /* Max. read data block length */ - uint8_t PartBlockRead; /* Partial blocks for read allowed */ - uint8_t WrBlockMisalign; /* Write block misalignment */ - uint8_t RdBlockMisalign; /* Read block misalignment */ - uint8_t DSRImpl; /* DSR implemented */ - uint8_t Reserved2; /* Reserved */ - uint16_t DeviceSize; /* Device Size */ - uint8_t MaxRdCurrentVDDMin; /* Max. read current @ VDD min */ - uint8_t MaxRdCurrentVDDMax; /* Max. read current @ VDD max */ - uint8_t MaxWrCurrentVDDMin; /* Max. write current @ VDD min */ - uint8_t MaxWrCurrentVDDMax; /* Max. write current @ VDD max */ - uint8_t DeviceSizeMul; /* Device size multiplier */ - uint8_t EraseGrSize; /* Erase group size */ - uint8_t EraseGrMul; /* Erase group size multiplier */ - uint8_t WrProtectGrSize; /* Write protect group size */ - uint8_t WrProtectGrEnable; /* Write protect group enable */ - uint8_t ManDeflECC; /* Manufacturer default ECC */ - uint8_t WrSpeedFact; /* Write speed factor */ - uint8_t MaxWrBlockLen; /* Max. write data block length */ - uint8_t WriteBlockPaPartial; /* Partial blocks for write allowed */ - uint8_t Reserved3; /* Reserved */ - uint8_t ContentProtectAppli; /* Content protection application */ - uint8_t FileFormatGrouop; /* File format group */ - uint8_t CopyFlag; /* Copy flag (OTP) */ - uint8_t PermWrProtect; /* Permanent write protection */ - uint8_t TempWrProtect; /* Temporary write protection */ - uint8_t FileFormat; /* File Format */ - uint8_t ECC; /* ECC code */ - uint8_t msd_CRC; /* CRC */ - uint8_t Reserved4; /* always 1*/ -} SDCARDCsdTypeDef; - -/* Structure taken from Mass Storage Driver example provided by STM */ -typedef struct { - uint8_t ManufacturerID; /* ManufacturerID */ - uint16_t OEM_AppliID; /* OEM/Application ID */ - char ProdName[6]; /* Product Name */ - uint8_t ProdRev; /* Product Revision */ - uint32_t ProdSN; /* Product Serial Number */ - uint8_t Reserved1; /* Reserved1 */ - uint16_t ManufactDate; /* Manufacturing Date */ - uint8_t msd_CRC; /* CRC */ - uint8_t Reserved2; /* always 1*/ -} SDCARDCidTypeDef; - -/* Global Variables */ -//extern VOLINFO PIOS_SDCARD_VolInfo; -//extern uint8_t PIOS_SDCARD_Sector[SECTOR_SIZE]; - -/* Prototypes */ -extern int32_t PIOS_SDCARD_Init(void); -extern int32_t PIOS_SDCARD_PowerOn(void); -extern int32_t PIOS_SDCARD_PowerOff(void); -extern int32_t PIOS_SDCARD_CheckAvailable(uint8_t was_available); -extern int32_t PIOS_SDCARD_SendSDCCmd(uint8_t cmd, uint32_t addr, uint8_t crc); -extern int32_t PIOS_SDCARD_SectorRead(uint32_t sector, uint8_t *buffer); -extern int32_t PIOS_SDCARD_SectorWrite(uint32_t sector, uint8_t *buffer); -extern int32_t PIOS_SDCARD_CIDRead(SDCARDCidTypeDef *cid); -extern int32_t PIOS_SDCARD_CSDRead(SDCARDCsdTypeDef *csd); - -extern int32_t PIOS_SDCARD_StartupLog(void); -extern int32_t PIOS_SDCARD_IsMounted(); -extern int32_t PIOS_SDCARD_MountFS(uint32_t StartupLog); -extern int32_t PIOS_SDCARD_GetFree(void); - -//extern int32_t PIOS_SDCARD_ReadBuffer(PFILEINFO fileinfo, uint8_t *buffer, uint32_t len); -//extern int32_t PIOS_SDCARD_ReadLine(PFILEINFO fileinfo, uint8_t *buffer, uint32_t max_len); -extern int32_t PIOS_SDCARD_FileCopy(char *Source, char *Destination); -extern int32_t PIOS_SDCARD_FileDelete(char *Filename); - -#endif - -#endif /* PIOS_SDCARD_H */ diff --git a/flight/PiOS.posix/inc/pios_servo.h b/flight/PiOS.posix/inc/pios_servo.h deleted file mode 100644 index 952baa5a0..000000000 --- a/flight/PiOS.posix/inc/pios_servo.h +++ /dev/null @@ -1,43 +0,0 @@ -/** - ****************************************************************************** - * @addtogroup PIOS PIOS Core hardware abstraction layer - * @{ - * @addtogroup PIOS_SERVO RC Servo Functions - * @{ - * - * @file pios_servo.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief RC Servo functions header. - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef PIOS_SERVO_H -#define PIOS_SERVO_H - -/* Public Functions */ -extern void PIOS_Servo_Init(void); -extern void PIOS_Servo_SetHz(const uint16_t * speeds, uint8_t num_banks); -extern void PIOS_Servo_Set(uint8_t Servo, uint16_t Position); - -#endif /* PIOS_SERVO_H */ - -/** - * @} - * @} - */ diff --git a/flight/PiOS.posix/inc/pios_struct_helper.h b/flight/PiOS.posix/inc/pios_struct_helper.h deleted file mode 100644 index 6196d9b26..000000000 --- a/flight/PiOS.posix/inc/pios_struct_helper.h +++ /dev/null @@ -1,12 +0,0 @@ -/* Taken from include/linux/kernel.h from the Linux kernel tree */ - -/** - * container_of - cast a member of a structure out to the containing structure - * @ptr: the pointer to the member. - * @type: the type of the container struct this is embedded in. - * @member: the name of the member within the struct. - * - */ -#define container_of(ptr, type, member) ({ \ - const typeof( ((type *)0)->member ) *__mptr = (ptr); \ - (type *)( (char *)__mptr - offsetof(type,member) );}) diff --git a/flight/PiOS.posix/inc/pios_sys.h b/flight/PiOS.posix/inc/pios_sys.h deleted file mode 100644 index 7f183a892..000000000 --- a/flight/PiOS.posix/inc/pios_sys.h +++ /dev/null @@ -1,50 +0,0 @@ -/** - ****************************************************************************** - * @addtogroup PIOS PIOS Core hardware abstraction layer - * @{ - * @addtogroup PIOS_SYS System Functions - * @brief PIOS System Initialization code - * @{ - * - * @file pios_sys.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * Parts by Thorsten Klose (tk@midibox.org) - * @brief System and hardware Init functions header. - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef PIOS_SYS_H -#define PIOS_SYS_H - -#define PIOS_SYS_SERIAL_NUM_BINARY_LEN 12 -#define PIOS_SYS_SERIAL_NUM_ASCII_LEN (PIOS_SYS_SERIAL_NUM_BINARY_LEN * 2) - -/* Public Functions */ -extern void PIOS_SYS_Init(void); -extern int32_t PIOS_SYS_Reset(void); -extern uint32_t PIOS_SYS_getCPUFlashSize(void); -extern int32_t PIOS_SYS_SerialNumberGetBinary(uint8_t array[PIOS_SYS_SERIAL_NUM_BINARY_LEN]); -extern int32_t PIOS_SYS_SerialNumberGet(char str[PIOS_SYS_SERIAL_NUM_ASCII_LEN+1]); - -#endif /* PIOS_SYS_H */ - -/** - * @} - * @} - */ diff --git a/flight/PiOS.posix/inc/pios_wdg.h b/flight/PiOS.posix/inc/pios_wdg.h deleted file mode 100644 index 3de3317fc..000000000 --- a/flight/PiOS.posix/inc/pios_wdg.h +++ /dev/null @@ -1,45 +0,0 @@ -/** - ****************************************************************************** - * @addtogroup PIOS PIOS Core hardware abstraction layer - * @{ - * @addtogroup PIOS_WDG Watchdog Functions - * @{ - * - * @file pios_wdg.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * Parts by Thorsten Klose (tk@midibox.org) - * @brief SPI functions header. - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef PIOS_WDG -#define PIOS_WDG - -void PIOS_WDG_Init(); -bool PIOS_WDG_RegisterFlag(uint16_t flag_requested); -bool PIOS_WDG_UpdateFlag(uint16_t flag); -uint16_t PIOS_WDG_GetBootupFlags(); -uint16_t PIOS_WDG_GetActiveFlags(); -void PIOS_WDG_Clear(void); - -#define PIOS_WDG_ACTUATOR 0x0001 -#define PIOS_WDG_STABILIZATION 0x0002 -#define PIOS_WDG_MANUAL 0x0008 - -#endif