From 7136215930f1b2f3f8790df03a99566dfbd7396e Mon Sep 17 00:00:00 2001 From: patacongo Date: Sat, 4 Jan 2020 11:06:44 -0600 Subject: [PATCH 1/4] sched_mergepending.c: Correct some errors in comments. (#38) * Documentation/NuttXCCodingStandard.html: Remove requirement to decorate ignored returned values with (void). * sched_mergepending.c: Correct some errors in comments. Co-authored-by: Gregory Nutt --- sched/sched/sched_mergepending.c | 20 +++++++++----------- 1 file changed, 9 insertions(+), 11 deletions(-) diff --git a/sched/sched/sched_mergepending.c b/sched/sched/sched_mergepending.c index a5840f0335e..3f4acff54a5 100644 --- a/sched/sched/sched_mergepending.c +++ b/sched/sched/sched_mergepending.c @@ -76,11 +76,10 @@ * a context switch is needed. * * Assumptions: - * - The caller has established a critical section before - * calling this function (calling sched_lock() first is NOT - * a good idea -- use enter_critical_section()). - * - The caller handles the condition that occurs if the - * the head of the sched_mergTSTATE_TASK_PENDINGs is changed. + * - The caller has established a critical section before calling this + * function. + * - The caller handles the condition that occurs if the head of the + * ready-to-run task list is changed. * ****************************************************************************/ @@ -181,11 +180,10 @@ bool sched_mergepending(void) * a context switch is needed. * * Assumptions: - * - The caller has established a critical section before - * calling this function (calling sched_lock() first is NOT - * a good idea -- use enter_critical_section()). - * - The caller handles the condition that occurs if the - * the head of the sched_mergTSTATE_TASK_PENDINGs is changed. + * - The caller has established a critical section before calling this + * function. + * - The caller handles the condition that occurs if the head of the + * ready-to-run task list is changed. * ****************************************************************************/ @@ -261,7 +259,7 @@ bool sched_mergepending(void) (FAR dq_queue_t *)&g_pendingtasks, TSTATE_TASK_PENDING); - /* And return with the schedule locked and tasks in the + /* And return with the scheduler locked and tasks in the * pending task list. */ From 390ebd504f6bf484d460e288dc2636db32b56adc Mon Sep 17 00:00:00 2001 From: Minamiya_Natsuki Date: Sun, 5 Jan 2020 07:45:30 -0600 Subject: [PATCH 2/4] arch/arm/src/stm32h7: Port QSPI driver from STM32F7 to STM32H7 --- arch/arm/src/stm32f7/hardware/stm32_qspi.h | 4 +- arch/arm/src/stm32h7/Kconfig | 140 +- arch/arm/src/stm32h7/Make.defs | 5 + arch/arm/src/stm32h7/hardware/stm32_qspi.h | 239 ++ arch/arm/src/stm32h7/stm32_qspi.c | 2799 ++++++++++++++++++++ arch/arm/src/stm32h7/stm32_qspi.h | 144 + 6 files changed, 3327 insertions(+), 4 deletions(-) create mode 100644 arch/arm/src/stm32h7/hardware/stm32_qspi.h create mode 100644 arch/arm/src/stm32h7/stm32_qspi.c create mode 100644 arch/arm/src/stm32h7/stm32_qspi.h diff --git a/arch/arm/src/stm32f7/hardware/stm32_qspi.h b/arch/arm/src/stm32f7/hardware/stm32_qspi.h index 61c84d2ea2f..3f69a8addb7 100644 --- a/arch/arm/src/stm32f7/hardware/stm32_qspi.h +++ b/arch/arm/src/stm32f7/hardware/stm32_qspi.h @@ -236,6 +236,4 @@ * Public Functions ****************************************************************************************/ -#endif /* __ARCH_ARM_SRC_STM32F7_HARDWARE_STM32L4_QSPI_H */ - - +#endif /* __ARCH_ARM_SRC_STM32F7_HARDWARE_STM32F7_QSPI_H */ diff --git a/arch/arm/src/stm32h7/Kconfig b/arch/arm/src/stm32h7/Kconfig index 788056aff48..dcd26f1750f 100644 --- a/arch/arm/src/stm32h7/Kconfig +++ b/arch/arm/src/stm32h7/Kconfig @@ -304,6 +304,10 @@ config STM32H7_OTG_USBREGEN bool "Enable USB voltage regulator" default n +config STM32H7_QUADSPI + bool "QuadSPI" + default n + config STM32H7_USBDEV_REGDEBUG bool "OTG USBDEV REGDEBUG" default n @@ -1154,6 +1158,8 @@ config STM32H7_RTC_LSECLOCK_RUN_DRV_CAPABILITY endif # STM32H7_RTC_LSECLOCK +endmenu # RTC Configuration + config STM32H7_EXTERNAL_RAM bool "External RAM on FMC" default n @@ -1162,7 +1168,139 @@ config STM32H7_EXTERNAL_RAM ---help--- In addition to internal SDRAM, external RAM may be available through the FMC. -endmenu # RTC Configuration +menu "QuadSPI Configuration" + depends on STM32H7_QUADSPI + +config STM32H7_QSPI_FLASH_SIZE + int "Size of attached serial flash, bytes" + default 16777216 + range 1 2147483648 + ---help--- + The STM32H7 QSPI peripheral requires the size of the Flash be specified + +config STM32H7_QSPI_FIFO_THESHOLD + int "Number of bytes before asserting FIFO threshold flag" + default 4 + range 1 16 + ---help--- + The STM32H7 QSPI peripheral requires that the FIFO threshold be specified + I would leave it at the default value of 4 unless you know what you are doing. + +config STM32H7_QSPI_CSHT + int "Number of cycles Chip Select must be inactive between transactions" + default 1 + range 1 8 + ---help--- + The STM32H7 QSPI peripheral requires that it be specified the minimum number + of AHB cycles that Chip Select be held inactive between transactions. + +choice + prompt "Transfer technique" + default STM32H7_QSPI_DMA + ---help--- + You can choose between using polling, interrupts, or DMA to transfer data + over the QSPI interface. + +config STM32H7_QSPI_POLLING + bool "Polling" + ---help--- + Use conventional register I/O with status polling to transfer data. + +config STM32H7_QSPI_INTERRUPTS + bool "Interrupts" + ---help--- + User interrupt driven I/O transfers. + +config STM32H7_QSPI_DMA + bool "DMA" + depends on STM32H7_DMA + ---help--- + Use DMA to improve QSPI transfer performance. + +endchoice + +choice + prompt "Bank selection" + default STM32H7_QSPI_MODE_BANK1 + ---help--- + You can choose between using polling, interrupts, or DMA to transfer data + over the QSPI interface. + +config STM32H7_QSPI_MODE_BANK1 + bool "Bank 1" + +config STM32H7_QSPI_MODE_BANK2 + bool "Bank 2" + +config STM32H7_QSPI_MODE_DUAL + bool "Dual Bank" + +endchoice + +choice + prompt "DMA Priority" + default STM32H7_QSPI_DMAPRIORITY_MEDIUM + depends on STM32H7_DMA + ---help--- + The DMA controller supports priority levels. You are probably fine + with the default of 'medium' except for special cases. In the event + of contention between to channels at the same priority, the lower + numbered channel has hardware priority over the higher numbered one. + +config STM32H7_QSPI_DMAPRIORITY_VERYHIGH + bool "Very High priority" + depends on STM32H7_DMA + ---help--- + 'Highest' priority. + +config STM32H7_QSPI_DMAPRIORITY_HIGH + bool "High priority" + depends on STM32H7_DMA + ---help--- + 'High' priority. + +config STM32H7_QSPI_DMAPRIORITY_MEDIUM + bool "Medium priority" + depends on STM32H7_DMA + ---help--- + 'Medium' priority. + +config STM32H7_QSPI_DMAPRIORITY_LOW + bool "Low priority" + depends on STM32H7_DMA + ---help--- + 'Low' priority. + +endchoice + +config STM32H7_QSPI_DMATHRESHOLD + int "QSPI DMA threshold" + default 4 + depends on STM32H7_QSPI_DMA + ---help--- + When QSPI DMA is enabled, small DMA transfers will still be performed + by polling logic. This value is the threshold below which transfers + will still be performed by conventional register status polling. + +config STM32H7_QSPI_DMADEBUG + bool "QSPI DMA transfer debug" + depends on STM32H7_QSPI_DMA && DEBUG_SPI && DEBUG_DMA + default n + ---help--- + Enable special debug instrumentation to analyze QSPI DMA data transfers. + This logic is as non-invasive as possible: It samples DMA + registers at key points in the data transfer and then dumps all of + the registers at the end of the transfer. + +config STM32H7_QSPI_REGDEBUG + bool "QSPI Register level debug" + depends on DEBUG_SPI_INFO + default n + ---help--- + Output detailed register-level QSPI device debug information. + Requires also CONFIG_DEBUG_SPI_INFO. + +endmenu config STM32H7_CUSTOM_CLOCKCONFIG bool "Custom clock configuration" diff --git a/arch/arm/src/stm32h7/Make.defs b/arch/arm/src/stm32h7/Make.defs index 90921db97f5..965f38ab487 100644 --- a/arch/arm/src/stm32h7/Make.defs +++ b/arch/arm/src/stm32h7/Make.defs @@ -161,6 +161,11 @@ ifeq ($(CONFIG_STM32H7_PWR),y) CHIP_CSRCS += stm32_pwr.c endif + +ifeq ($(CONFIG_STM32H7_QUADSPI),y) +CHIP_CSRCS += stm32_qspi.c +endif + ifeq ($(CONFIG_STM32H7_RTC),y) CHIP_CSRCS += stm32_rtc.c ifeq ($(CONFIG_RTC_ALARM),y) diff --git a/arch/arm/src/stm32h7/hardware/stm32_qspi.h b/arch/arm/src/stm32h7/hardware/stm32_qspi.h new file mode 100644 index 00000000000..6b7f6bf6a36 --- /dev/null +++ b/arch/arm/src/stm32h7/hardware/stm32_qspi.h @@ -0,0 +1,239 @@ +/**************************************************************************** + * arch/arm/src/stm32h7/hardware/stm32_qspi.h + * + * Copyright (C) 2016, 2019 Gregory Nutt. All rights reserved. + * Author: dev@ziggurat29.com + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#ifndef __ARCH_ARM_SRC_STM32H7_HARDWARE_STM32H7_QSPI_H +#define __ARCH_ARM_SRC_STM32H7_HARDWARE_STM32H7_QSPI_H + +/**************************************************************************************** + * Included Files + ****************************************************************************************/ + +#include +#include + +#include "chip.h" + +/**************************************************************************************** + * Pre-processor Definitions + ****************************************************************************************/ + +/* General Characteristics **************************************************************/ + +#define STM32H7_QSPI_MINBITS 8 /* Minimum word width */ +#define STM32H7_QSPI_MAXBITS 32 /* Maximum word width */ + +/* QSPI register offsets ****************************************************************/ + +#define STM32_QUADSPI_CR_OFFSET 0x0000 /* Control Register */ +#define STM32_QUADSPI_DCR_OFFSET 0x0004 /* Device Configuration Register */ +#define STM32_QUADSPI_SR_OFFSET 0x0008 /* Status Register */ +#define STM32_QUADSPI_FCR_OFFSET 0x000c /* Flag Clear Register */ +#define STM32_QUADSPI_DLR_OFFSET 0x0010 /* Data Length Register */ +#define STM32_QUADSPI_CCR_OFFSET 0x0014 /* Communication Configuration Register */ +#define STM32_QUADSPI_AR_OFFSET 0x0018 /* Address Register */ +#define STM32_QUADSPI_ABR_OFFSET 0x001c /* Alternate Bytes Register */ +#define STM32_QUADSPI_DR_OFFSET 0x0020 /* Data Register */ +#define STM32_QUADSPI_PSMKR_OFFSET 0x0024 /* Polling Status mask Register */ +#define STM32_QUADSPI_PSMAR_OFFSET 0x0028 /* Polling Status match Register */ +#define STM32_QUADSPI_PIR_OFFSET 0x002c /* Polling Interval Register */ +#define STM32_QUADSPI_LPTR_OFFSET 0x0030 /* Low-Power Timeout Register */ + +/* QSPI register addresses **************************************************************/ + +#define STM32_QUADSPI_CR (STM32_QUADSPI_BASE+STM32_QUADSPI_CR_OFFSET) /* Control Register */ +#define STM32_QUADSPI_DCR (STM32_QUADSPI_BASE+STM32_QUADSPI_DCR_OFFSET) /* Device Configuration Register */ +#define STM32_QUADSPI_SR (STM32_QUADSPI_BASE+STM32_QUADSPI_SR_OFFSET) /* Status Register */ +#define STM32_QUADSPI_FCR (STM32_QUADSPI_BASE+STM32_QUADSPI_FCR_OFFSET) /* Flag Clear Register */ +#define STM32_QUADSPI_DLR (STM32_QUADSPI_BASE+STM32_QUADSPI_DLR_OFFSET) /* Data Length Register */ +#define STM32_QUADSPI_CCR (STM32_QUADSPI_BASE+STM32_QUADSPI_CCR_OFFSET) /* Communication Configuration Register */ +#define STM32_QUADSPI_AR (STM32_QUADSPI_BASE+STM32_QUADSPI_AR_OFFSET) /* Address Register */ +#define STM32_QUADSPI_ABR (STM32_QUADSPI_BASE+STM32_QUADSPI_ABR_OFFSET) /* Alternate Bytes Register */ +#define STM32_QUADSPI_DR (STM32_QUADSPI_BASE+STM32_QUADSPI_DR_OFFSET) /* Data Register */ +#define STM32_QUADSPI_PSMKR (STM32_QUADSPI_BASE+STM32_QUADSPI_PSMKR_OFFSET) /* Polling Status mask Register */ +#define STM32_QUADSPI_PSMAR (STM32_QUADSPI_BASE+STM32_QUADSPI_PSMAR_OFFSET) /* Polling Status match Register */ +#define STM32_QUADSPI_PIR (STM32_QUADSPI_BASE+STM32_QUADSPI_PIR_OFFSET) /* Polling Interval Register */ +#define STM32_QUADSPI_LPTR (STM32_QUADSPI_BASE+STM32_QUADSPI_LPTR_OFFSET) /* Low-Power Timeout Register */ + +/* QSPI register bit definitions ********************************************************/ + +/* Control Register */ + +#define QSPI_CR_EN (1 << 0) /* Bit 0: QSPI Enable */ +#define QSPI_CR_ABORT (1 << 1) /* Bit 1: Abort request */ +#define QSPI_CR_TCEN (1 << 3) /* Bit 3: Timeout counter enable */ +#define QSPI_CR_SSHIFT (1 << 4) /* Bit 4: Sample shift */ +#define QSPI_CR_DFM (1 << 6) /* Bit 6: DFM: Dual-flash mode */ +#define QSPI_CR_FSEL (1 << 7) /* Bit 7: FSEL: Flash memory selection */ +#define QSPI_CR_FTHRES_SHIFT (8) /* Bits 8-11: FIFO threshold level */ +#define QSPI_CR_FTHRES_MASK (0x0f << QSPI_CR_FTHRES_SHIFT) +#define QSPI_CR_TEIE (1 << 16) /* Bit 16: Transfer error interrupt enable */ +#define QSPI_CR_TCIE (1 << 17) /* Bit 17: Transfer complete interrupt enable */ +#define QSPI_CR_FTIE (1 << 18) /* Bit 18: FIFO threshold interrupt enable */ +#define QSPI_CR_SMIE (1 << 19) /* Bit 19: Status match interrupt enable */ +#define QSPI_CR_TOIE (1 << 20) /* Bit 20: TimeOut interrupt enable */ +#define QSPI_CR_APMS (1 << 22) /* Bit 22: Automatic poll mode stop */ +#define QSPI_CR_PMM (1 << 23) /* Bit 23: Polling match mode */ +#define QSPI_CR_PRESCALER_SHIFT (24) /* Bits 24-31: Clock prescaler */ +#define QSPI_CR_PRESCALER_MASK (0xff << QSPI_CR_PRESCALER_SHIFT) + +/* Device Configuration Register */ + +#define QSPI_DCR_CKMODE (1 << 0) /* Bit 0: Mode 0 / mode 3 */ +#define QSPI_DCR_CSHT_SHIFT (8) /* Bits 8-10: Chip select high time */ +#define QSPI_DCR_CSHT_MASK (0x7 << QSPI_DCR_CSHT_SHIFT) +#define QSPI_DCR_FSIZE_SHIFT (16) /* Bits 16-20: Flash memory size */ +#define QSPI_DCR_FSIZE_MASK (0x1f << QSPI_DCR_FSIZE_SHIFT) + +/* Status Register */ + +#define QSPI_SR_TEF (1 << 0) /* Bit 0: Transfer error flag */ +#define QSPI_SR_TCF (1 << 1) /* Bit 1: Transfer complete flag */ +#define QSPI_SR_FTF (1 << 2) /* Bit 2: FIFO threshold flag */ +#define QSPI_SR_SMF (1 << 3) /* Bit 3: Status match flag */ +#define QSPI_SR_TOF (1 << 4) /* Bit 4: Timeout flag */ +#define QSPI_SR_BUSY (1 << 5) /* Bit 5: Busy */ +#define QSPI_SR_FLEVEL_SHIFT (8) /* Bits 8-12: FIFO threshold level */ +#define QSPI_SR_FLEVEL_MASK (0x1f << QSPI_SR_FLEVEL_SHIFT) + +/* Flag Clear Register */ + +#define QSPI_FCR_CTEF (1 << 0) /* Bit 0: Clear Transfer error flag */ +#define QSPI_FCR_CTCF (1 << 1) /* Bit 1: Clear Transfer complete flag */ +#define QSPI_FCR_CSMF (1 << 3) /* Bit 3: Clear Status match flag */ +#define QSPI_FCR_CTOF (1 << 4) /* Bit 4: Clear Timeout flag */ + +/* Data Length Register */ + +/* Communication Configuration Register */ + +#define CCR_IMODE_NONE 0 /* No instruction */ +#define CCR_IMODE_SINGLE 1 /* Instruction on a single line */ +#define CCR_IMODE_DUAL 2 /* Instruction on two lines */ +#define CCR_IMODE_QUAD 3 /* Instruction on four lines */ + +#define CCR_ADMODE_NONE 0 /* No address */ +#define CCR_ADMODE_SINGLE 1 /* Address on a single line */ +#define CCR_ADMODE_DUAL 2 /* Address on two lines */ +#define CCR_ADMODE_QUAD 3 /* Address on four lines */ + +#define CCR_ADSIZE_8 0 /* 8-bit address */ +#define CCR_ADSIZE_16 1 /* 16-bit address */ +#define CCR_ADSIZE_24 2 /* 24-bit address */ +#define CCR_ADSIZE_32 3 /* 32-bit address */ + +#define CCR_ABMODE_NONE 0 /* No alternate bytes */ +#define CCR_ABMODE_SINGLE 1 /* Alternate bytes on a single line */ +#define CCR_ABMODE_DUAL 2 /* Alternate bytes on two lines */ +#define CCR_ABMODE_QUAD 3 /* Alternate bytes on four lines */ + +#define CCR_ABSIZE_8 0 /* 8-bit alternate byte */ +#define CCR_ABSIZE_16 1 /* 16-bit alternate bytes */ +#define CCR_ABSIZE_24 2 /* 24-bit alternate bytes */ +#define CCR_ABSIZE_32 3 /* 32-bit alternate bytes */ + +#define CCR_DMODE_NONE 0 /* No data */ +#define CCR_DMODE_SINGLE 1 /* Data on a single line */ +#define CCR_DMODE_DUAL 2 /* Data on two lines */ +#define CCR_DMODE_QUAD 3 /* Data on four lines */ + +#define CCR_FMODE_INDWR 0 /* Indirect write mode */ +#define CCR_FMODE_INDRD 1 /* Indirect read mode */ +#define CCR_FMODE_AUTOPOLL 2 /* Automatic polling mode */ +#define CCR_FMODE_MEMMAP 3 /* Memory-mapped mode */ + +#define QSPI_CCR_INSTRUCTION_SHIFT (0) /* Bits 0-7: Instruction */ +#define QSPI_CCR_INSTRUCTION_MASK (0xff << QSPI_CCR_INSTRUCTION_SHIFT) +# define QSPI_CCR_INST(n) ((uint32_t)(n) << QSPI_CCR_INSTRUCTION_SHIFT) +#define QSPI_CCR_IMODE_SHIFT (8) /* Bits 8-9: Instruction mode */ +#define QSPI_CCR_IMODE_MASK (0x3 << QSPI_CCR_IMODE_SHIFT) +# define QSPI_CCR_IMODE(n) ((uint32_t)(n) << QSPI_CCR_IMODE_SHIFT) +#define QSPI_CCR_ADMODE_SHIFT (10) /* Bits 10-11: Address mode */ +#define QSPI_CCR_ADMODE_MASK (0x3 << QSPI_CCR_ADMODE_SHIFT) +# define QSPI_CCR_ADMODE(n) ((uint32_t)(n) << QSPI_CCR_ADMODE_SHIFT) +#define QSPI_CCR_ADSIZE_SHIFT (12) /* Bits 12-13: Address size */ +#define QSPI_CCR_ADSIZE_MASK (0x3 << QSPI_CCR_ADSIZE_SHIFT) +# define QSPI_CCR_ADSIZE(n) ((uint32_t)(n) << QSPI_CCR_ADSIZE_SHIFT) +#define QSPI_CCR_ABMODE_SHIFT (14) /* Bits 14-15: Alternate bytes mode */ +#define QSPI_CCR_ABMODE_MASK (0x3 << QSPI_CCR_ABMODE_SHIFT) +# define QSPI_CCR_ABMODE(n) ((uint32_t)(n) << QSPI_CCR_ABMODE_SHIFT) +#define QSPI_CCR_ABSIZE_SHIFT (16) /* Bits 16-17: Alternate bytes size */ +#define QSPI_CCR_ABSIZE_MASK (0x3 << QSPI_CCR_ABSIZE_SHIFT) +# define QSPI_CCR_ABSIZE(n) ((uint32_t)(n) << QSPI_CCR_ABSIZE_SHIFT) +#define QSPI_CCR_DCYC_SHIFT (18) /* Bits 18-23: Number of dummy cycles */ +#define QSPI_CCR_DCYC_MASK (0x1f << QSPI_CCR_DCYC_SHIFT) +# define QSPI_CCR_DCYC(n) ((uint32_t)(n) << QSPI_CCR_DCYC_SHIFT) +#define QSPI_CCR_DMODE_SHIFT (24) /* Bits 24-25: Data mode */ +#define QSPI_CCR_DMODE_MASK (0x3 << QSPI_CCR_DMODE_SHIFT) +# define QSPI_CCR_DMODE(n) ((uint32_t)(n) << QSPI_CCR_DMODE_SHIFT) +#define QSPI_CCR_FMODE_SHIFT (26) /* Bits 26-27: Functional mode */ +#define QSPI_CCR_FMODE_MASK (0x3 << QSPI_CCR_FMODE_SHIFT) +# define QSPI_CCR_FMODE(n) ((uint32_t)(n) << QSPI_CCR_FMODE_SHIFT) +#define QSPI_CCR_SIOO (1 << 28) /* Bit 28: Send instruction only once mode */ +#define QSPI_CCR_FRCM (1 << 29) /* Bit 28: Enters Free running clock mode */ +#define QSPI_CCR_DDRM (1 << 31) /* Bit 31: Double data rate mode */ + +/* Address Register */ + +/* Alternate Bytes Register */ + +/* Data Register */ + +/* Polling Status mask Register */ + +/* Polling Status match Register */ + +/* Polling Interval Register */ + +#define QSPI_PIR_INTERVAL_SHIFT (0) /* Bits 0-15: Polling interval */ +#define QSPI_PIR_INTERVAL_MASK (0xFFff << QSPI_PIR_INTERVAL_SHIFT) + +/* Low-Power Timeout Register */ + +#define QSPI_LPTR_TIMEOUT_SHIFT (0) /* Bits 0-15: Timeout period */ +#define QSPI_LPTR_TIMEOUT_MASK (0xFFff << QSPI_PIR_INTERVAL_SHIFT) + +/**************************************************************************************** + * Public Types + ****************************************************************************************/ + +/**************************************************************************************** + * Public Data + ****************************************************************************************/ + +/**************************************************************************************** + * Public Functions + ****************************************************************************************/ + +#endif /* __ARCH_ARM_SRC_STM32H7_HARDWARE_STM32H4_QSPI_H */ diff --git a/arch/arm/src/stm32h7/stm32_qspi.c b/arch/arm/src/stm32h7/stm32_qspi.c new file mode 100644 index 00000000000..81d9c671716 --- /dev/null +++ b/arch/arm/src/stm32h7/stm32_qspi.c @@ -0,0 +1,2799 @@ +/**************************************************************************** + * arch/arm/src/stm32h7/stm32_qspi.c + * + * Copyright (C) 2016-2017, 2019 Gregory Nutt. All rights reserved. + * Author: dev@ziggurat29.com + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include "stm32_qspi.h" + +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include + +#include +#include +#include +#include +#include +#include +#include + +#include "up_internal.h" +#include "up_arch.h" +#include "barriers.h" + +#include "stm32_gpio.h" +#include "stm32_dma.h" +#include "stm32_rcc.h" +#include "hardware/stm32_qspi.h" + +#ifdef CONFIG_STM32H7_QUADSPI + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* QSPI memory synchronization */ + +#define MEMORY_SYNC() do { ARM_DSB(); ARM_ISB(); } while (0) + +/* Ensure that the DMA buffers are word-aligned. */ + +#define ALIGN_SHIFT 2 +#define ALIGN_MASK 3 +#define ALIGN_UP(n) (((n)+ALIGN_MASK) & ~ALIGN_MASK) +#define IS_ALIGNED(n) (((uint32_t)(n) & ALIGN_MASK) == 0) + +/* Debug ********************************************************************/ + +/* Check if QSPI debug is enabled */ + +#ifndef CONFIG_DEBUG_DMA +# undef CONFIG_STM32H7_QSPI_DMADEBUG +#endif + +#define DMA_INITIAL 0 +#define DMA_AFTER_SETUP 1 +#define DMA_AFTER_START 2 +#define DMA_CALLBACK 3 +#define DMA_TIMEOUT 3 +#define DMA_END_TRANSFER 4 +#define DMA_NSAMPLES 5 + +/* Can't have both interrupt-driven QSPI and DMA QSPI */ + +#if defined(CONFIG_STM32H7_QSPI_INTERRUPTS) && defined(CONFIG_STM32H7_QSPI_DMA) +# error "Cannot enable both interrupt mode and DMA mode for QSPI" +#endif + +/* Sanity check that board.h defines requisite QSPI pinmap options for */ + +#if (!defined(GPIO_QSPI_CS) || !defined(GPIO_QSPI_IO0) || !defined(GPIO_QSPI_IO1) || \ + !defined(GPIO_QSPI_IO2) || !defined(GPIO_QSPI_IO3) || !defined(GPIO_QSPI_SCK)) +# error you must define QSPI pinmapping options for GPIO_QSPI_CS GPIO_QSPI_IO0 \ + GPIO_QSPI_IO1 GPIO_QSPI_IO2 GPIO_QSPI_IO3 GPIO_QSPI_SCK in your board.h +#endif + +#ifdef CONFIG_STM32H7_QSPI_DMA + +# ifdef DMAMAP_QUADSPI + +/* QSPI DMA Channel/Stream selection. There + * are multiple DMA stream options that must be dis-ambiguated in the board.h + * file. + */ + +# define DMACHAN_QUADSPI DMAMAP_QUADSPI +# endif + +# if defined(CONFIG_STM32H7_QSPI_DMAPRIORITY_LOW) +# define QSPI_DMA_PRIO DMA_SCR_PRILO +# elif defined(CONFIG_STM32H7_QSPI_DMAPRIORITY_MEDIUM) +# define QSPI_DMA_PRIO DMA_SCR_PRIMED +# elif defined(CONFIG_STM32H7_QSPI_DMAPRIORITY_HIGH) +# define QSPI_DMA_PRIO DMA_SCR_PRIHI +# elif defined(CONFIG_STM32H7_QSPI_DMAPRIORITY_VERYHIGH) +# define QSPI_DMA_PRIO DMA_SCR_PRIVERYHI +# else +# define QSPI_DMA_PRIO DMA_SCR_PRIMED +# endif + +#endif /* CONFIG_STM32H7_QSPI_DMA */ + +#ifndef STM32_SYSCLK_FREQUENCY +# error your board.h needs to define the value of STM32_SYSCLK_FREQUENCY +#endif + +#if !defined(CONFIG_STM32H7_QSPI_FLASH_SIZE) || 0 == CONFIG_STM32H7_QSPI_FLASH_SIZE +# error you must specify a positive flash size via CONFIG_STM32H7_QSPI_FLASH_SIZE +#endif + +/* DMA timeout. The value is not critical; we just don't want the system to + * hang in the event that a DMA does not finish. + */ + +#define DMA_TIMEOUT_MS (800) +#define DMA_TIMEOUT_TICKS MSEC2TICK(DMA_TIMEOUT_MS) + +/* Clocking *****************************************************************/ + +/* The QSPI bit rate clock is generated by dividing the peripheral clock by + * a value between 1 and 255 + */ + +#define STL32F7_QSPI_CLOCK STM32_SYSCLK_FREQUENCY /* Frequency of the QSPI clock */ + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +/* The state of the QSPI controller. + * + * NOTE: the STM32H7 supports only a single QSPI peripheral. Logic here is + * designed to support multiple QSPI peripherals. + */ + +struct stm32h7_qspidev_s +{ + struct qspi_dev_s qspi; /* Externally visible part of the QSPI interface */ + uint32_t base; /* QSPI controller register base address */ + uint32_t frequency; /* Requested clock frequency */ + uint32_t actual; /* Actual clock frequency */ + uint8_t mode; /* Mode 0,3 */ + uint8_t nbits; /* Width of word in bits (8 to 32) */ + uint8_t intf; /* QSPI controller number (0) */ + bool initialized; /* TRUE: Controller has been initialized */ + sem_t exclsem; /* Assures mutually exclusive access to QSPI */ + bool memmap; /* TRUE: Controller is in memory mapped mode */ + +#ifdef CONFIG_STM32H7_QSPI_INTERRUPTS + xcpt_t handler; /* Interrupt handler */ + uint8_t irq; /* Interrupt number */ + sem_t op_sem; /* Block until complete */ + struct qspi_xctnspec_s *xctn; /* context of transaction in progress */ +#endif + +#ifdef CONFIG_STM32H7_QSPI_DMA + bool candma; /* DMA is supported */ + sem_t dmawait; /* Used to wait for DMA completion */ + int result; /* DMA result */ + DMA_HANDLE dmach; /* QSPI DMA handle */ + WDOG_ID dmadog; /* Watchdog that handles DMA timeouts */ +#endif + + /* Debug stuff */ + +#ifdef CONFIG_STM32H7_QSPI_DMADEBUG + struct stm32h7_dmaregs_s dmaregs[DMA_NSAMPLES]; +#endif + +#ifdef CONFIG_STM32H7_QSPI_REGDEBUG + bool wrlast; /* Last was a write */ + uint32_t addresslast; /* Last address */ + uint32_t valuelast; /* Last value */ + int ntimes; /* Number of times */ +#endif +}; + +/* The QSPI transaction specification + * + * This is mostly the values of the CCR and DLR, AR, ABR, broken out into a C + * structure since these fields need to be considered at various phases of + * thee transaction processing activity. + */ + +struct qspi_xctnspec_s +{ + uint8_t instrmode; /* 'instruction mode'; 0=none, 1=single, 2=dual, 3=quad */ + uint8_t instr; /* the (8-bit) Instruction (if any) */ + + uint8_t addrmode; /* 'address mode'; 0=none, 1=single, 2=dual, 3=quad */ + uint8_t addrsize; /* address size (n - 1); 0, 1, 2, 3 */ + uint32_t addr; /* the address (if any) (1 to 4 bytes as per addrsize) */ + + uint8_t altbytesmode; /* 'alt bytes mode'; 0=none, 1=single, 2=dual, 3=quad */ + uint8_t altbytessize; /* 'alt bytes' size (n - 1); 0, 1, 2, 3 */ + uint32_t altbytes; /* the 'alt bytes' (if any) */ + + uint8_t dummycycles; /* number of Dummy Cycles; 0 - 32 */ + + uint8_t datamode; /* 'data mode'; 0=none, 1=single, 2=dual, 3=quad */ + uint32_t datasize; /* number of data bytes (0xffffffff == undefined) */ + FAR void *buffer; /* Data buffer */ + + uint8_t isddr; /* true if 'double data rate' */ + uint8_t issioo; /* true if 'send instruction only once' mode */ + +#ifdef CONFIG_STM32H7_QSPI_INTERRUPTS + uint8_t function; /* functional mode; to distinguish a read or write */ + int8_t disposition; /* how it all turned out */ + uint32_t idxnow; /* index into databuffer of current byte in transfer */ +#endif +}; + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/* Helpers */ + +#ifdef CONFIG_STM32H7_QSPI_REGDEBUG +static bool qspi_checkreg(struct stm32h7_qspidev_s *priv, bool wr, + uint32_t value, uint32_t address); +#else +# define qspi_checkreg(priv,wr,value,address) (false) +#endif + +static inline uint32_t qspi_getreg(struct stm32h7_qspidev_s *priv, + unsigned int offset); +static inline void qspi_putreg(struct stm32h7_qspidev_s *priv, uint32_t value, + unsigned int offset); + +#ifdef CONFIG_DEBUG_SPI_INFO +static void qspi_dumpregs(struct stm32h7_qspidev_s *priv, + const char *msg); +#else +# define qspi_dumpregs(priv,msg) +#endif + +#if defined(CONFIG_DEBUG_SPI_INFO) && defined(CONFIG_DEBUG_GPIO) +static void qspi_dumpgpioconfig(const char *msg); +#else +# define qspi_dumpgpioconfig(msg) +#endif + +/* Interrupts */ + +#ifdef CONFIG_STM32H7_QSPI_INTERRUPTS +static int qspi0_interrupt(int irq, void *context, FAR void *arg); + +#endif + +/* DMA support */ + +#ifdef CONFIG_STM32H7_QSPI_DMA + +# ifdef CONFIG_STM32H7_QSPI_DMADEBUG +# define qspi_dma_sample(s,i) stm32h7_dmasample((s)->dmach, &(s)->dmaregs[i]) +static void qspi_dma_sampleinit(struct stm32h7_qspidev_s *priv); +static void qspi_dma_sampledone(struct stm32h7_qspidev_s *priv); +# else +# define qspi_dma_sample(s,i) +# define qspi_dma_sampleinit(s) +# define qspi_dma_sampledone(s) +# endif + +# ifndef CONFIG_STM32H7_QSPI_DMATHRESHOLD +# define CONFIG_STM32H7_QSPI_DMATHRESHOLD 4 +# endif + +#endif + +/* QSPI methods */ + +static int qspi_lock(struct qspi_dev_s *dev, bool lock); +static uint32_t qspi_setfrequency(struct qspi_dev_s *dev, uint32_t frequency); +static void qspi_setmode(struct qspi_dev_s *dev, enum qspi_mode_e mode); +static void qspi_setbits(struct qspi_dev_s *dev, int nbits); +static int qspi_command(struct qspi_dev_s *dev, + struct qspi_cmdinfo_s *cmdinfo); +static int qspi_memory(struct qspi_dev_s *dev, + struct qspi_meminfo_s *meminfo); +static FAR void *qspi_alloc(FAR struct qspi_dev_s *dev, size_t buflen); +static void qspi_free(FAR struct qspi_dev_s *dev, FAR void *buffer); + +/* Initialization */ + +static int qspi_hw_initialize(struct stm32h7_qspidev_s *priv); + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/* QSPI0 driver operations */ + +static const struct qspi_ops_s g_qspi0ops = +{ + .lock = qspi_lock, + .setfrequency = qspi_setfrequency, + .setmode = qspi_setmode, + .setbits = qspi_setbits, + .command = qspi_command, + .memory = qspi_memory, + .alloc = qspi_alloc, + .free = qspi_free, +}; + +/* This is the overall state of the QSPI0 controller */ + +static struct stm32h7_qspidev_s g_qspi0dev = +{ + .qspi = + { + .ops = &g_qspi0ops, + }, + .base = STM32_QUADSPI_BASE, +#ifdef CONFIG_STM32H7_QSPI_INTERRUPTS + .handler = qspi0_interrupt, + .irq = STM32_IRQ_QUADSPI, +#endif + .intf = 0, +#ifdef CONFIG_STM32H7_QSPI_DMA + .candma = true, +#endif +}; + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: qspi_checkreg + * + * Description: + * Check if the current register access is a duplicate of the preceding. + * + * Input Parameters: + * value - The value to be written + * address - The address of the register to write to + * + * Returned Value: + * true: This is the first register access of this type. + * false: This is the same as the preceding register access. + * + ****************************************************************************/ + +#ifdef CONFIG_STM32H7_QSPI_REGDEBUG +static bool qspi_checkreg(struct stm32h7_qspidev_s *priv, bool wr, + uint32_t value, uint32_t address) +{ + if (wr == priv->wrlast && /* Same kind of access? */ + value == priv->valuelast && /* Same value? */ + address == priv->addresslast) /* Same address? */ + { + /* Yes, then just keep a count of the number of times we did this. */ + + priv->ntimes++; + return false; + } + else + { + /* Did we do the previous operation more than once? */ + + if (priv->ntimes > 0) + { + /* Yes... show how many times we did it */ + + spiinfo("...[Repeats %d times]...\n", priv->ntimes); + } + + /* Save information about the new access */ + + priv->wrlast = wr; + priv->valuelast = value; + priv->addresslast = address; + priv->ntimes = 0; + } + + /* Return true if this is the first time that we have done this operation */ + + return true; +} +#endif + +/**************************************************************************** + * Name: qspi_getreg + * + * Description: + * Read an QSPI register + * + ****************************************************************************/ + +static inline uint32_t qspi_getreg(struct stm32h7_qspidev_s *priv, + unsigned int offset) +{ + uint32_t address = priv->base + offset; + uint32_t value = getreg32(address); + +#ifdef CONFIG_STM32H7_QSPI_REGDEBUG + if (qspi_checkreg(priv, false, value, address)) + { + spiinfo("%08x->%08x\n", address, value); + } +#endif + + return value; +} + +/**************************************************************************** + * Name: qspi_putreg + * + * Description: + * Write a value to an QSPI register + * + ****************************************************************************/ + +static inline void qspi_putreg(struct stm32h7_qspidev_s *priv, uint32_t value, + unsigned int offset) +{ + uint32_t address = priv->base + offset; + +#ifdef CONFIG_STM32H7_QSPI_REGDEBUG + if (qspi_checkreg(priv, true, value, address)) + { + spiinfo("%08x<-%08x\n", address, value); + } +#endif + + putreg32(value, address); +} + +/**************************************************************************** + * Name: qspi_dumpregs + * + * Description: + * Dump the contents of all QSPI registers + * + * Input Parameters: + * priv - The QSPI controller to dump + * msg - Message to print before the register data + * + * Returned Value: + * None + * + ****************************************************************************/ + +#ifdef CONFIG_DEBUG_SPI_INFO +static void qspi_dumpregs(struct stm32h7_qspidev_s *priv, const char *msg) +{ + uint32_t regval; + spiinfo("%s:\n", msg); + +#if 0 + /* this extra verbose output may be helpful in some cases; you'll need + * to make sure your syslog is large enough to accommodate the extra output. + */ + + regval = getreg32(priv->base + STM32_QUADSPI_CR_OFFSET); /* Control Register */ + spiinfo("CR:%08x\n", regval); + spiinfo(" EN:%1d ABORT:%1d DMAEN:%1d TCEN:%1d SSHIFT:%1d\n" + " FTHRES: %d\n" + " TEIE:%1d TCIE:%1d FTIE:%1d SMIE:%1d TOIE:%1d APMS:%1d PMM:%1d\n" + " PRESCALER: %d\n", + (regval & QSPI_CR_EN) ? 1 : 0, + (regval & QSPI_CR_ABORT) ? 1 : 0, + (regval & QSPI_CR_DMAEN) ? 1 : 0, + (regval & QSPI_CR_TCEN) ? 1 : 0, + (regval & QSPI_CR_SSHIFT) ? 1 : 0, + (regval & QSPI_CR_FTHRES_MASK) >> QSPI_CR_FTHRES_SHIFT, + (regval & QSPI_CR_TEIE) ? 1 : 0, + (regval & QSPI_CR_TCIE) ? 1 : 0, + (regval & QSPI_CR_FTIE) ? 1 : 0, + (regval & QSPI_CR_SMIE) ? 1 : 0, + (regval & QSPI_CR_TOIE) ? 1 : 0, + (regval & QSPI_CR_APMS) ? 1 : 0, + (regval & QSPI_CR_PMM) ? 1 : 0, + (regval & QSPI_CR_PRESCALER_MASK) >> QSPI_CR_PRESCALER_SHIFT); + + regval = getreg32(priv->base + STM32_QUADSPI_DCR_OFFSET); /* Device Configuration Register */ + spiinfo("DCR:%08x\n", regval); + spiinfo(" CKMODE:%1d CSHT:%d FSIZE:%d\n", + (regval & QSPI_DCR_CKMODE) ? 1 : 0, + (regval & QSPI_DCR_CSHT_MASK) >> QSPI_DCR_CSHT_SHIFT, + (regval & QSPI_DCR_FSIZE_MASK) >> QSPI_DCR_FSIZE_SHIFT); + + regval = getreg32(priv->base + STM32_QUADSPI_CCR_OFFSET); /* Communication Configuration Register */ + spiinfo("CCR:%08x\n", regval); + spiinfo(" INST:%02x IMODE:%d ADMODE:%d ADSIZE:%d ABMODE:%d\n" + " ABSIZE:%d DCYC:%d DMODE:%d FMODE:%d\n" + " SIOO:%1d DDRM:%1d\n", + (regval & QSPI_CCR_INSTRUCTION_MASK) >> QSPI_CCR_INSTRUCTION_SHIFT, + (regval & QSPI_CCR_IMODE_MASK) >> QSPI_CCR_IMODE_SHIFT, + (regval & QSPI_CCR_ADMODE_MASK) >> QSPI_CCR_ADMODE_SHIFT, + (regval & QSPI_CCR_ADSIZE_MASK) >> QSPI_CCR_ABSIZE_SHIFT, + (regval & QSPI_CCR_ABMODE_MASK) >> QSPI_CCR_ABMODE_SHIFT, + (regval & QSPI_CCR_ABSIZE_MASK) >> QSPI_CCR_ABSIZE_SHIFT, + (regval & QSPI_CCR_DCYC_MASK) >> QSPI_CCR_DCYC_SHIFT, + (regval & QSPI_CCR_DMODE_MASK) >> QSPI_CCR_DMODE_SHIFT, + (regval & QSPI_CCR_FMODE_MASK) >> QSPI_CCR_FMODE_SHIFT, + (regval & QSPI_CCR_SIOO) ? 1 : 0, + (regval & QSPI_CCR_DDRM) ? 1 : 0); + + regval = getreg32(priv->base + STM32_QUADSPI_SR_OFFSET); /* Status Register */ + spiinfo("SR:%08x\n", regval); + spiinfo(" TEF:%1d TCF:%1d FTF:%1d SMF:%1d TOF:%1d BUSY:%1d FLEVEL:%d\n", + (regval & QSPI_SR_TEF) ? 1 : 0, + (regval & QSPI_SR_TCF) ? 1 : 0, + (regval & QSPI_SR_FTF) ? 1 : 0, + (regval & QSPI_SR_SMF) ? 1 : 0, + (regval & QSPI_SR_TOF) ? 1 : 0, + (regval & QSPI_SR_BUSY) ? 1 : 0, + (regval & QSPI_SR_FLEVEL_MASK) >> QSPI_SR_FLEVEL_SHIFT); + +#else + spiinfo(" CR:%08x DCR:%08x CCR:%08x SR:%08x\n", + getreg32(priv->base + STM32_QUADSPI_CR_OFFSET), /* Control Register */ + getreg32(priv->base + STM32_QUADSPI_DCR_OFFSET), /* Device Configuration Register */ + getreg32(priv->base + STM32_QUADSPI_CCR_OFFSET), /* Communication Configuration Register */ + getreg32(priv->base + STM32_QUADSPI_SR_OFFSET)); /* Status Register */ + spiinfo(" DLR:%08x ABR:%08x PSMKR:%08x PSMAR:%08x\n", + getreg32(priv->base + STM32_QUADSPI_DLR_OFFSET), /* Data Length Register */ + getreg32(priv->base + STM32_QUADSPI_ABR_OFFSET), /* Alternate Bytes Register */ + getreg32(priv->base + STM32_QUADSPI_PSMKR_OFFSET), /* Polling Status mask Register */ + getreg32(priv->base + STM32_QUADSPI_PSMAR_OFFSET)); /* Polling Status match Register */ + spiinfo(" PIR:%08x LPTR:%08x\n", + getreg32(priv->base + STM32_QUADSPI_PIR_OFFSET), /* Polling Interval Register */ + getreg32(priv->base + STM32_QUADSPI_LPTR_OFFSET)); /* Low-Power Timeout Register */ + (void)regval; +#endif +} +#endif + +#if defined(CONFIG_DEBUG_SPI_INFO) && defined(CONFIG_DEBUG_GPIO) +static void qspi_dumpgpioconfig(const char *msg) +{ + uint32_t regval; + spiinfo("%s:\n", msg); + + /* Port B */ + + regval = getreg32(STM32_GPIOB_MODER); + spiinfo("B_MODER:%08x\n", regval); + + regval = getreg32(STM32_GPIOB_OTYPER); + spiinfo("B_OTYPER:%08x\n", regval); + + regval = getreg32(STM32_GPIOB_OSPEED); + spiinfo("B_OSPEED:%08x\n", regval); + + regval = getreg32(STM32_GPIOB_PUPDR); + spiinfo("B_PUPDR:%08x\n", regval); + + regval = getreg32(STM32_GPIOB_AFRL); + spiinfo("B_AFRL:%08x\n", regval); + + regval = getreg32(STM32_GPIOB_AFRH); + spiinfo("B_AFRH:%08x\n", regval); + + /* Port D */ + + regval = getreg32(STM32_GPIOD_MODER); + spiinfo("D_MODER:%08x\n", regval); + + regval = getreg32(STM32_GPIOD_OTYPER); + spiinfo("D_OTYPER:%08x\n", regval); + + regval = getreg32(STM32_GPIOD_OSPEED); + spiinfo("D_OSPEED:%08x\n", regval); + + regval = getreg32(STM32_GPIOD_PUPDR); + spiinfo("D_PUPDR:%08x\n", regval); + + regval = getreg32(STM32_GPIOD_AFRL); + spiinfo("D_AFRL:%08x\n", regval); + + regval = getreg32(STM32_GPIOD_AFRH); + spiinfo("D_AFRH:%08x\n", regval); + + /* Port E */ + + regval = getreg32(STM32_GPIOE_MODER); + spiinfo("E_MODER:%08x\n", regval); + + regval = getreg32(STM32_GPIOE_OTYPER); + spiinfo("E_OTYPER:%08x\n", regval); + + regval = getreg32(STM32_GPIOE_OSPEED); + spiinfo("E_OSPEED:%08x\n", regval); + + regval = getreg32(STM32_GPIOE_PUPDR); + spiinfo("E_PUPDR:%08x\n", regval); + + regval = getreg32(STM32_GPIOE_AFRL); + spiinfo("E_AFRL:%08x\n", regval); + + regval = getreg32(STM32_GPIOE_AFRH); + spiinfo("E_AFRH:%08x\n", regval); +} +#endif + +#ifdef CONFIG_STM32H7_QSPI_DMADEBUG +/**************************************************************************** + * Name: qspi_dma_sampleinit + * + * Description: + * Initialize sampling of DMA registers + * + * Input Parameters: + * priv - QSPI driver instance + * + * Returned Value: + * None + * + ****************************************************************************/ + +static void qspi_dma_sampleinit(struct stm32h7_qspidev_s *priv) +{ + /* Put contents of register samples into a known state */ + + memset(priv->dmaregs, 0xff, + DMA_NSAMPLES * sizeof(struct stm32h7_dmaregs_s)); + + /* Then get the initial samples */ + + stm32h7_dmasample(priv->dmach, &priv->dmaregs[DMA_INITIAL]); +} + +/**************************************************************************** + * Name: qspi_dma_sampledone + * + * Description: + * Dump sampled DMA registers + * + * Input Parameters: + * priv - QSPI driver instance + * + * Returned Value: + * None + * + ****************************************************************************/ + +static void qspi_dma_sampledone(struct stm32h7_qspidev_s *priv) +{ + /* Sample the final registers */ + + stm32h7_dmasample(priv->dmach, &priv->dmaregs[DMA_END_TRANSFER]); + + /* Then dump the sampled DMA registers */ + + /* Initial register values */ + + stm32h7_dmadump(priv->dmach, &priv->dmaregs[DMA_INITIAL], + "Initial Registers"); + + /* Register values after DMA setup */ + + stm32h7_dmadump(priv->dmach, &priv->dmaregs[DMA_AFTER_SETUP], + "After DMA Setup"); + + /* Register values after DMA start */ + + stm32h7_dmadump(priv->dmach, &priv->dmaregs[DMA_AFTER_START], + "After DMA Start"); + + /* Register values at the time of the TX and RX DMA callbacks + * -OR- DMA timeout. + * + * If the DMA timed out, then there will not be any RX DMA + * callback samples. There is probably no TX DMA callback + * samples either, but we don't know for sure. + */ + + if (priv->result == -ETIMEDOUT) + { + stm32h7_dmadump(priv->dmach, &priv->dmaregs[DMA_TIMEOUT], + "At DMA timeout"); + } + else + { + stm32h7_dmadump(priv->dmach, &priv->dmaregs[DMA_CALLBACK], + "At DMA callback"); + } + + stm32h7_dmadump(priv->dmach, &priv->dmaregs[DMA_END_TRANSFER], + "At End-of-Transfer"); +} +#endif + +/**************************************************************************** + * Name: qspi_setupxctnfromcmd + * + * Description: + * Setup our transaction descriptor from a command info structure + * + * Input Parameters: + * xctn - the transaction descriptor we setup + * cmdinfo - the command info (originating from the MTD device) + * + * Returned Value: + * OK, or -errno if invalid + * + ****************************************************************************/ + +static int qspi_setupxctnfromcmd(struct qspi_xctnspec_s *xctn, + const struct qspi_cmdinfo_s *cmdinfo) +{ + DEBUGASSERT(xctn != NULL && cmdinfo != NULL); + +#ifdef CONFIG_DEBUG_SPI_INFO + spiinfo("Transfer:\n"); + spiinfo(" flags: %02x\n", cmdinfo->flags); + spiinfo(" cmd: %04x\n", cmdinfo->cmd); + + if (QSPICMD_ISADDRESS(cmdinfo->flags)) + { + spiinfo(" address/length: %08lx/%d\n", + (unsigned long)cmdinfo->addr, cmdinfo->addrlen); + } + + if (QSPICMD_ISDATA(cmdinfo->flags)) + { + spiinfo(" %s Data:\n", + QSPICMD_ISWRITE(cmdinfo->flags) ? "Write" : "Read"); + spiinfo(" buffer/length: %p/%d\n", + cmdinfo->buffer, cmdinfo->buflen); + } +#endif + + DEBUGASSERT(cmdinfo->cmd < 256); + + /* Specify the instruction as per command info */ + + /* XXX III instruction mode, single dual quad option bits */ + + xctn->instrmode = CCR_IMODE_SINGLE; + xctn->instr = cmdinfo->cmd; + + /* XXX III option bits for 'send instruction only once' */ + + xctn->issioo = 0; + + /* XXX III options for alt bytes, dummy cycles */ + + xctn->altbytesmode = CCR_ABMODE_NONE; + xctn->altbytessize = CCR_ABSIZE_8; + xctn->altbytes = 0; + xctn->dummycycles = 0; + + /* Specify the address size as needed */ + + if (QSPICMD_ISADDRESS(cmdinfo->flags)) + { + /* XXX III address mode mode, single, dual, quad option bits */ + + xctn->addrmode = CCR_ADMODE_SINGLE; + if (cmdinfo->addrlen == 1) + { + xctn->addrsize = CCR_ADSIZE_8; + } + else if (cmdinfo->addrlen == 2) + { + xctn->addrsize = CCR_ADSIZE_16; + } + else if (cmdinfo->addrlen == 3) + { + xctn->addrsize = CCR_ADSIZE_24; + } + else if (cmdinfo->addrlen == 4) + { + xctn->addrsize = CCR_ADSIZE_32; + } + else + { + return -EINVAL; + } + + xctn->addr = cmdinfo->addr; + } + else + { + xctn->addrmode = CCR_ADMODE_NONE; + xctn->addrsize = 0; + xctn->addr = cmdinfo->addr; + } + + /* Specify the data as needed */ + + xctn->buffer = cmdinfo->buffer; + if (QSPICMD_ISDATA(cmdinfo->flags)) + { + /* XXX III data mode mode, single, dual, quad option bits */ + + xctn->datamode = CCR_DMODE_SINGLE; + xctn->datasize = cmdinfo->buflen; + + /* XXX III double data rate option bits */ + + xctn->isddr = 0; + } + else + { + xctn->datamode = CCR_DMODE_NONE; + xctn->datasize = 0; + xctn->isddr = 0; + } + +#if defined(CONFIG_STM32H7_QSPI_INTERRUPTS) + xctn->function = QSPICMD_ISWRITE(cmdinfo->flags) ? CCR_FMODE_INDWR : + CCR_FMODE_INDRD; + xctn->disposition = - EIO; + xctn->idxnow = 0; +#endif + + return OK; +} + +/**************************************************************************** + * Name: qspi_setupxctnfrommem + * + * Description: + * Setup our transaction descriptor from a memory info structure + * + * Input Parameters: + * xctn - the transaction descriptor we setup + * meminfo - the memory info (originating from the MTD device) + * + * Returned Value: + * OK, or -errno if invalid + * + ****************************************************************************/ + +static int qspi_setupxctnfrommem(struct qspi_xctnspec_s *xctn, + const struct qspi_meminfo_s *meminfo) +{ + DEBUGASSERT(xctn != NULL && meminfo != NULL); + +#ifdef CONFIG_DEBUG_SPI_INFO + spiinfo("Transfer:\n"); + spiinfo(" flags: %02x\n", meminfo->flags); + spiinfo(" cmd: %04x\n", meminfo->cmd); + spiinfo(" address/length: %08lx/%d\n", + (unsigned long)meminfo->addr, meminfo->addrlen); + spiinfo(" %s Data:\n", QSPIMEM_ISWRITE(meminfo->flags) ? "Write" : "Read"); + spiinfo(" buffer/length: %p/%d\n", meminfo->buffer, meminfo->buflen); +#endif + + DEBUGASSERT(meminfo->cmd < 256); + + /* Specify the instruction as per command info */ + + /* XXX III instruction mode, single dual quad option bits */ + + xctn->instrmode = CCR_IMODE_SINGLE; + xctn->instr = meminfo->cmd; + + /* XXX III option bits for 'send instruction only once' */ + + xctn->issioo = 0; + + /* XXX III options for alt bytes */ + + xctn->altbytesmode = CCR_ABMODE_NONE; + xctn->altbytessize = CCR_ABSIZE_8; + xctn->altbytes = 0; + + xctn->dummycycles = meminfo->dummies; + + /* Specify the address size as needed */ + + /* XXX III there should be a separate flags for single/dual/quad for each + * of i,a,d + */ + + if (QSPIMEM_ISDUALIO(meminfo->flags)) + { + xctn->addrmode = CCR_ADMODE_DUAL; + } + else if (QSPIMEM_ISQUADIO(meminfo->flags)) + { + xctn->addrmode = CCR_ADMODE_QUAD; + } + else + { + xctn->addrmode = CCR_ADMODE_SINGLE; + } + + if (meminfo->addrlen == 1) + { + xctn->addrsize = CCR_ADSIZE_8; + } + else if (meminfo->addrlen == 2) + { + xctn->addrsize = CCR_ADSIZE_16; + } + else if (meminfo->addrlen == 3) + { + xctn->addrsize = CCR_ADSIZE_24; + } + else if (meminfo->addrlen == 4) + { + xctn->addrsize = CCR_ADSIZE_32; + } + else + { + return -EINVAL; + } + + xctn->addr = meminfo->addr; + + /* Specify the data as needed */ + + xctn->buffer = meminfo->buffer; + + /* XXX III there should be a separate flags for single/dual/quad for each + * of i,a,d + */ + + if (QSPIMEM_ISDUALIO(meminfo->flags)) + { + xctn->datamode = CCR_DMODE_DUAL; + } + else if (QSPIMEM_ISQUADIO(meminfo->flags)) + { + xctn->datamode = CCR_DMODE_QUAD; + } + else + { + xctn->datamode = CCR_DMODE_SINGLE; + } + + xctn->datasize = meminfo->buflen; + + /* XXX III double data rate option bits */ + + xctn->isddr = 0; + +#if defined(CONFIG_STM32H7_QSPI_INTERRUPTS) + xctn->function = QSPIMEM_ISWRITE(meminfo->flags) ? CCR_FMODE_INDWR : + CCR_FMODE_INDRD; + xctn->disposition = - EIO; + xctn->idxnow = 0; +#endif + + return OK; +} + +/**************************************************************************** + * Name: qspi_waitstatusflags + * + * Description: + * Spin wait for specified status flags to be set as desired + * + * Input Parameters: + * priv - The QSPI controller to dump + * mask - bits to check, can be multiple + * polarity - true wait if any set, false to wait if all reset + * + * Returned Value: + * None + * + ****************************************************************************/ + +static void qspi_waitstatusflags(struct stm32h7_qspidev_s *priv, + uint32_t mask, int polarity) +{ + uint32_t regval; + + if (polarity) + { + while (!((regval = qspi_getreg(priv, STM32_QUADSPI_SR_OFFSET)) & mask)); + } + else + { + while (((regval = qspi_getreg(priv, STM32_QUADSPI_SR_OFFSET)) & mask)); + } +} + +/**************************************************************************** + * Name: qspi_abort + * + * Description: + * Abort any transaction in progress + * + * Input Parameters: + * priv - The QSPI controller to dump + * + * Returned Value: + * None + * + ****************************************************************************/ + +static void qspi_abort(struct stm32h7_qspidev_s *priv) +{ + uint32_t regval; + + regval = qspi_getreg(priv, STM32_QUADSPI_CR_OFFSET); + regval |= QSPI_CR_ABORT; + qspi_putreg(priv, regval, STM32_QUADSPI_CR_OFFSET); +} + +/**************************************************************************** + * Name: qspi_ccrconfig + * + * Description: + * Do common Communications Configuration Register setup + * + * Input Parameters: + * priv - The QSPI controller to dump + * xctn - the transaction descriptor; CCR setup + * fctn - 'functional mode'; 0=indwrite, 1=indread, 2=autopoll, 3=memmmap + * + * Returned Value: + * None + * + ****************************************************************************/ + +static void qspi_ccrconfig(struct stm32h7_qspidev_s *priv, + struct qspi_xctnspec_s *xctn, + uint8_t fctn) +{ + uint32_t regval; + + /* If we have data, and it's not memory mapped, write the length */ + + if (CCR_DMODE_NONE != xctn->datamode && CCR_FMODE_MEMMAP != fctn) + { + qspi_putreg(priv, xctn->datasize - 1, STM32_QUADSPI_DLR_OFFSET); + } + + /* If we have alternate bytes, stick them in now */ + + if (CCR_ABMODE_NONE != xctn->altbytesmode) + { + qspi_putreg(priv, xctn->altbytes, STM32_QUADSPI_ABR_OFFSET); + } + + /* Build the CCR value and set it */ + + regval = QSPI_CCR_INST(xctn->instr) | + QSPI_CCR_IMODE(xctn->instrmode) | + QSPI_CCR_ADMODE(xctn->addrmode) | + QSPI_CCR_ADSIZE(xctn->addrsize) | + QSPI_CCR_ABMODE(xctn->altbytesmode) | + QSPI_CCR_ABSIZE(xctn->altbytessize) | + QSPI_CCR_DCYC(xctn->dummycycles) | + QSPI_CCR_DMODE(xctn->datamode) | + QSPI_CCR_FMODE(fctn) | + (xctn->isddr ? QSPI_CCR_SIOO : 0) | + (xctn->issioo ? QSPI_CCR_DDRM : 0); + qspi_putreg(priv, regval, STM32_QUADSPI_CCR_OFFSET); + + /* If we have and need and address, set that now, too */ + + if (CCR_ADMODE_NONE != xctn->addrmode && CCR_FMODE_MEMMAP != fctn) + { + qspi_putreg(priv, xctn->addr, STM32_QUADSPI_AR_OFFSET); + } +} + +#if defined(CONFIG_STM32H7_QSPI_INTERRUPTS) +/**************************************************************************** + * Name: qspi0_interrupt + * + * Description: + * Interrupt handler; we handle all QSPI cases -- reads, writes, + * automatic status polling, etc. + * + * Input Parameters: + * irq - + * context - + * + * Returned Value: + * OK means we handled it + * + ****************************************************************************/ + +static int qspi0_interrupt(int irq, void *context, FAR void *arg) +{ + uint32_t status; + uint32_t cr; + uint32_t regval; + + /* Let's find out what is going on */ + + status = qspi_getreg(&g_qspi0dev, STM32_QUADSPI_SR_OFFSET); + cr = qspi_getreg(&g_qspi0dev, STM32_QUADSPI_CR_OFFSET); + + /* Is it 'FIFO Threshold'? */ + + if ((status & QSPI_SR_FTF) && (cr & QSPI_CR_FTIE)) + { + volatile uint32_t *datareg = + (volatile uint32_t *)(g_qspi0dev.base + STM32_QUADSPI_DR_OFFSET); + + if (g_qspi0dev.xctn->function == CCR_FMODE_INDWR) + { + /* Write data until we have no more or have no place to put it */ + + while (((regval = qspi_getreg(&g_qspi0dev, STM32_QUADSPI_SR_OFFSET)) & + QSPI_SR_FTF) != 0) + { + if (g_qspi0dev.xctn->idxnow < g_qspi0dev.xctn->datasize) + { + *(volatile uint8_t *)datareg = + ((uint8_t *)g_qspi0dev.xctn->buffer)[g_qspi0dev.xctn->idxnow]; + ++g_qspi0dev.xctn->idxnow; + } + else + { + /* Fresh out of data to write */ + + break; + } + } + } + else if (g_qspi0dev.xctn->function == CCR_FMODE_INDRD) + { + /* Read data until we have no more or have no place to put it */ + + while (((regval = qspi_getreg(&g_qspi0dev, STM32_QUADSPI_SR_OFFSET)) & + QSPI_SR_FTF) != 0) + { + if (g_qspi0dev.xctn->idxnow < g_qspi0dev.xctn->datasize) + { + ((uint8_t *)g_qspi0dev.xctn->buffer)[g_qspi0dev.xctn->idxnow] = + *(volatile uint8_t *)datareg; + ++g_qspi0dev.xctn->idxnow; + } + else + { + /* no room at the inn */ + + break; + } + } + } + } + + /* Is it 'Transfer Complete'? */ + + if ((status & QSPI_SR_TCF) && (cr & QSPI_CR_TCIE)) + { + /* Acknowledge interrupt */ + + qspi_putreg(&g_qspi0dev, QSPI_FCR_CTCF, STM32_QUADSPI_FCR_OFFSET); + + /* Disable the QSPI FIFO Threshold, Transfer Error and Transfer + * complete Interrupts + */ + + regval = qspi_getreg(&g_qspi0dev, STM32_QUADSPI_CR_OFFSET); + regval &= ~(QSPI_CR_TEIE | QSPI_CR_TCIE | QSPI_CR_FTIE); + qspi_putreg(&g_qspi0dev, regval, STM32_QUADSPI_CR_OFFSET); + + /* Do the last bit of read if needed */ + + if (g_qspi0dev.xctn->function == CCR_FMODE_INDRD) + { + volatile uint32_t *datareg = + (volatile uint32_t *)(g_qspi0dev.base + STM32_QUADSPI_DR_OFFSET); + + /* Read any remaining data */ + + while (((regval = qspi_getreg(&g_qspi0dev, STM32_QUADSPI_SR_OFFSET)) & + QSPI_SR_FLEVEL_MASK) != 0) + { + if (g_qspi0dev.xctn->idxnow < g_qspi0dev.xctn->datasize) + { + ((uint8_t *)g_qspi0dev.xctn->buffer)[g_qspi0dev.xctn->idxnow] = + *(volatile uint8_t *)datareg; + ++g_qspi0dev.xctn->idxnow; + } + else + { + /* No room at the inn */ + + break; + } + } + } + + /* Use 'abort' to ditch any stray fifo contents and clear BUSY flag */ + + qspi_abort(&g_qspi0dev); + + /* Set success status */ + + g_qspi0dev.xctn->disposition = OK; + + /* Signal complete */ + + nxsem_post(&g_qspi0dev.op_sem); + } + + /* Is it 'Status Match'? */ + + if ((status & QSPI_SR_SMF) && (cr & QSPI_CR_SMIE)) + { + /* Acknowledge interrupt */ + + qspi_putreg(&g_qspi0dev, QSPI_FCR_CSMF, STM32_QUADSPI_FCR_OFFSET); + + /* If 'automatic poll mode stop' is activated, we're done */ + + if (cr & QSPI_CR_APMS) + { + /* Disable the QSPI Transfer Error and Status Match Interrupts */ + + regval = qspi_getreg(&g_qspi0dev, STM32_QUADSPI_CR_OFFSET); + regval &= ~(QSPI_CR_TEIE | QSPI_CR_SMIE); + qspi_putreg(&g_qspi0dev, regval, STM32_QUADSPI_CR_OFFSET); + + /* Set success status */ + + g_qspi0dev.xctn->disposition = OK; + + /* Signal complete */ + + nxsem_post(&g_qspi0dev.op_sem); + } + else + { + /* XXX if it's NOT auto stop; something needs to happen here; a callback? */ + } + } + + /* Is it' Transfer Error'? :( */ + + if ((status & QSPI_SR_TEF) && (cr & QSPI_CR_TEIE)) + { + /* Acknowledge interrupt */ + + qspi_putreg(&g_qspi0dev, QSPI_FCR_CTEF, STM32_QUADSPI_FCR_OFFSET); + + /* Disable all the QSPI Interrupts */ + + regval = qspi_getreg(&g_qspi0dev, STM32_QUADSPI_CR_OFFSET); + regval &= ~(QSPI_CR_TEIE | QSPI_CR_TCIE | QSPI_CR_FTIE | + QSPI_CR_SMIE | QSPI_CR_TOIE); + qspi_putreg(&g_qspi0dev, regval, STM32_QUADSPI_CR_OFFSET); + + /* Set error status; 'transfer error' means that, in 'indirect mode', + * an invalid address is attempted to be accessed. 'Invalid' is + * presumably relative to the FSIZE field in CCR; the manual is not + * explicit, but what else could it be? + */ + + g_qspi0dev.xctn->disposition = - EIO; + + /* Signal complete */ + + nxsem_post(&g_qspi0dev.op_sem); + } + + /* Is it 'Timeout'? */ + + if ((status & QSPI_SR_TOF) && (cr & QSPI_CR_TOIE)) + { + /* Acknowledge interrupt */ + + qspi_putreg(&g_qspi0dev, QSPI_FCR_CTOF, STM32_QUADSPI_FCR_OFFSET); + + /* XXX this interrupt simply means that, in 'memory mapped mode', + * the QSPI memory has not been accessed for a while, and the + * IP block was configured to automatically de-assert CS after + * a timeout. And now we're being informed that has happened. + * + * But who cares? If someone does, perhaps a user callback is + * appropriate, or some signal? Either way, realize the xctn + * member is /not/ valid, so you can't set the disposition + * field. Also, note signaling completion has no meaning here + * because in memory mapped mode no one holds the semaphore. + */ + } + + return OK; +} + +#elif defined(CONFIG_STM32H7_QSPI_DMA) +/**************************************************************************** + * Name: qspi_dma_timeout + * + * Description: + * The watchdog timeout setup when a has expired without completion of a + * DMA. + * + * Input Parameters: + * argc - The number of arguments (should be 1) + * arg - The argument (state structure reference cast to uint32_t) + * + * Returned Value: + * None + * + * Assumptions: + * Always called from the interrupt level with interrupts disabled. + * + ****************************************************************************/ + +static void qspi_dma_timeout(int argc, uint32_t arg) +{ + struct stm32h7_qspidev_s *priv = (struct stm32h7_qspidev_s *)arg; + DEBUGASSERT(priv != NULL); + + /* Sample DMA registers at the time of the timeout */ + + qspi_dma_sample(priv, DMA_CALLBACK); + + /* Report timeout result, perhaps overwriting any failure reports from + * the TX callback. + */ + + priv->result = -ETIMEDOUT; + + /* Then wake up the waiting thread */ + + nxsem_post(&priv->dmawait); +} + +/**************************************************************************** + * Name: qspi_dma_callback + * + * Description: + * This callback function is invoked at the completion of the QSPI DMA. + * + * Input Parameters: + * handle - The DMA handler + * isr - source of the DMA interrupt + * arg - A pointer to the chip select structure + * + * Returned Value: + * None + * + ****************************************************************************/ + +static void qspi_dma_callback(DMA_HANDLE handle, uint8_t isr, void *arg) +{ + struct stm32h7_qspidev_s *priv = (struct stm32h7_qspidev_s *)arg; + DEBUGASSERT(priv != NULL); + + /* Cancel the watchdog timeout */ + + (void)wd_cancel(priv->dmadog); + + /* Sample DMA registers at the time of the callback */ + + qspi_dma_sample(priv, DMA_CALLBACK); + + /* Report the result of the transfer only if the callback has not already + * reported an error. + */ + + if (priv->result == -EBUSY) + { + /* Save the result of the transfer if no error was previously reported */ + + if (isr & DMA_STREAM_TCIF_BIT) + { + priv->result = OK; + } + else if (isr & DMA_STREAM_TEIF_BIT) + { + priv->result = -EIO; + } + else + { + priv->result = OK; + } + } + + /* Then wake up the waiting thread */ + + nxsem_post(&priv->dmawait); +} + +/**************************************************************************** + * Name: qspi_regaddr + * + * Description: + * Return the address of an QSPI register + * + ****************************************************************************/ + +static inline uintptr_t qspi_regaddr(struct stm32h7_qspidev_s *priv, + unsigned int offset) +{ + return priv->base + offset; +} + +/**************************************************************************** + * Name: qspi_memory_dma + * + * Description: + * Perform one QSPI memory transfer using DMA + * + * Input Parameters: + * priv - Device-specific state data + * meminfo - Describes the memory transfer to be performed. + * xctn - Describes the transaction context. + * + * Returned Value: + * Zero (OK) on SUCCESS, a negated errno on value of failure + * + ****************************************************************************/ + +static int qspi_memory_dma(struct stm32h7_qspidev_s *priv, + struct qspi_meminfo_s *meminfo, + struct qspi_xctnspec_s *xctn) +{ + uint32_t dmaflags; + uint32_t regval; + int ret; + + /* Initialize register sampling */ + + qspi_dma_sampleinit(priv); + + /* Determine DMA flags and setup the DMA */ + + if (QSPIMEM_ISWRITE(meminfo->flags)) + { + /* Setup the DMA (memory-to-peripheral) */ + + dmaflags = (QSPI_DMA_PRIO | DMA_SCR_MSIZE_8BITS | + DMA_SCR_PSIZE_8BITS | DMA_SCR_MINC | DMA_SCR_DIR_M2P); + + up_clean_dcache((uintptr_t)meminfo->buffer, + (uintptr_t)meminfo->buffer + meminfo->buflen); + } + else + { + /* Setup the DMA (peripheral-to-memory) */ + + dmaflags = (QSPI_DMA_PRIO | DMA_SCR_MSIZE_8BITS | + DMA_SCR_PSIZE_8BITS | DMA_SCR_MINC | DMA_SCR_DIR_P2M); + } + + stm32_dmasetup(priv->dmach, qspi_regaddr(priv, STM32_QUADSPI_DR_OFFSET), + (uint32_t)meminfo->buffer, meminfo->buflen, dmaflags); + + qspi_dma_sample(priv, DMA_AFTER_SETUP); + + /* Enable the memory transfer */ + + regval = qspi_getreg(priv, STM32_QUADSPI_CR_OFFSET); + regval |= QSPI_CR_DMAEN; + qspi_putreg(priv, regval, STM32_QUADSPI_CR_OFFSET); + + /* Set up the Communications Configuration Register as per command info */ + + qspi_ccrconfig(priv, xctn, + QSPIMEM_ISWRITE(meminfo->flags) ? CCR_FMODE_INDWR : + CCR_FMODE_INDRD); + + /* Start the DMA */ + + priv->result = -EBUSY; + stm32_dmastart(priv->dmach, qspi_dma_callback, priv, false); + + qspi_dma_sample(priv, DMA_AFTER_START); + + /* Wait for DMA completion. This is done in a loop because there may be + * false alarm semaphore counts that cause nxsem_wait() not fail to wait + * or to wake-up prematurely (for example due to the receipt of a signal). + * We know that the DMA has completed when the result is anything other + * that -EBUSY. + */ + + do + { + /* Start (or re-start) the watchdog timeout */ + + ret = wd_start(priv->dmadog, DMA_TIMEOUT_TICKS, + (wdentry_t)qspi_dma_timeout, 1, (uint32_t)priv); + if (ret < 0) + { + spierr("ERROR: wd_start failed: %d\n", ret); + } + + /* Wait for the DMA complete */ + + ret = nxsem_wait(&priv->dmawait); + + if (QSPIMEM_ISREAD(meminfo->flags)) + { + up_invalidate_dcache((uintptr_t)meminfo->buffer, + (uintptr_t)meminfo->buffer + meminfo->buflen); + } + + /* Cancel the watchdog timeout */ + + (void)wd_cancel(priv->dmadog); + + /* Check if we were awakened by an error of some kind */ + + if (ret < 0) + { + /* EINTR is not a failure. That simply means that the wait + * was awakened by a signal. + */ + + if (ret != -EINTR) + { + DEBUGPANIC(); + regval = qspi_getreg(priv, STM32_QUADSPI_CR_OFFSET); + regval &= ~QSPI_CR_DMAEN; + qspi_putreg(priv, regval, STM32_QUADSPI_CR_OFFSET); + return ret; + } + } + + /* Note that we might be awakened before the wait is over due to + * residual counts on the semaphore. So, to handle, that case, + * we loop until something changes the DMA result to any value other + * than -EBUSY. + */ + } + while (priv->result == -EBUSY); + + /* Wait for Transfer complete, and not busy */ + + qspi_waitstatusflags(priv, QSPI_SR_TCF, 1); + qspi_waitstatusflags(priv, QSPI_SR_BUSY, 0); + MEMORY_SYNC(); + + /* Dump the sampled DMA registers */ + + qspi_dma_sampledone(priv); + + /* Make sure that the DMA is stopped (it will be stopped automatically + * on normal transfers, but not necessarily when the transfer terminates + * on an error condition). + */ + + stm32_dmastop(priv->dmach); + + regval = qspi_getreg(priv, STM32_QUADSPI_CR_OFFSET); + regval &= ~QSPI_CR_DMAEN; + qspi_putreg(priv, regval, STM32_QUADSPI_CR_OFFSET); + + /* Complain if the DMA fails */ + + if (priv->result) + { + spierr("ERROR: DMA failed with result: %d\n", priv->result); + } + + return priv->result; +} +#endif + +#if !defined(CONFIG_STM32H7_QSPI_INTERRUPTS) +/**************************************************************************** + * Name: qspi_receive_blocking + * + * Description: + * Do common data receive in a blocking (status polling) way + * + * Input Parameters: + * priv - The QSPI controller to dump + * xctn - the transaction descriptor + * + * Returned Value: + * OK, or -errno on error + * + ****************************************************************************/ + +static int qspi_receive_blocking(struct stm32h7_qspidev_s *priv, + struct qspi_xctnspec_s *xctn) +{ + int ret = OK; + volatile uint32_t *datareg = + (volatile uint32_t *)(priv->base + STM32_QUADSPI_DR_OFFSET); + uint8_t *dest = (uint8_t *)xctn->buffer; + uint32_t addrval; + uint32_t regval; + + addrval = qspi_getreg(priv, STM32_QUADSPI_AR_OFFSET); + if (dest != NULL) + { + /* Counter of remaining data */ + + uint32_t remaining = xctn->datasize; + + /* Ensure CCR register specifies indirect read */ + + regval = qspi_getreg(priv, STM32_QUADSPI_CCR_OFFSET); + regval &= ~QSPI_CCR_FMODE_MASK; + regval |= QSPI_CCR_FMODE(CCR_FMODE_INDRD); + qspi_putreg(priv, regval, STM32_QUADSPI_CCR_OFFSET); + + /* Start the transfer by re-writing the address in AR register */ + + qspi_putreg(priv, addrval, STM32_QUADSPI_AR_OFFSET); + + /* Transfer loop */ + + while (remaining > 0) + { + /* Wait for Fifo Threshold, or Transfer Complete, to read data */ + + qspi_waitstatusflags(priv, QSPI_SR_FTF | QSPI_SR_TCF, 1); + + *dest = *(volatile uint8_t *)datareg; + dest++; + remaining--; + } + + if (ret == OK) + { + /* Wait for transfer complete, then clear it */ + + qspi_waitstatusflags(priv, QSPI_SR_TCF, 1); + qspi_putreg(priv, QSPI_FCR_CTCF, STM32_QUADSPI_FCR_OFFSET); + + /* Use Abort to clear the busy flag, and ditch any extra bytes in fifo */ + + qspi_abort(priv); + } + } + else + { + ret = -EINVAL; + } + + return ret; +} + +/**************************************************************************** + * Name: qspi_transmit_blocking + * + * Description: + * Do common data transmit in a blocking (status polling) way + * + * Input Parameters: + * priv - The QSPI controller to dump + * xctn - the transaction descriptor + * + * Returned Value: + * OK, or -errno on error + * + ****************************************************************************/ + +static int qspi_transmit_blocking(struct stm32h7_qspidev_s *priv, + struct qspi_xctnspec_s *xctn) +{ + int ret = OK; + volatile uint32_t *datareg = + (volatile uint32_t *)(priv->base + STM32_QUADSPI_DR_OFFSET); + uint8_t *src = (uint8_t *)xctn->buffer; + + if (src != NULL) + { + /* Counter of remaining data */ + + uint32_t remaining = xctn->datasize; + + /* Transfer loop */ + + while (remaining > 0) + { + /* Wait for Fifo Threshold to write data */ + + qspi_waitstatusflags(priv, QSPI_SR_FTF, 1); + + *(volatile uint8_t *)datareg = *src++; + remaining--; + } + + if (ret == OK) + { + /* Wait for transfer complete, then clear it */ + + qspi_waitstatusflags(priv, QSPI_SR_TCF, 1); + qspi_putreg(priv, QSPI_FCR_CTCF, STM32_QUADSPI_FCR_OFFSET); + + /* Use Abort to clear the Busy flag */ + + qspi_abort(priv); + } + } + else + { + ret = -EINVAL; + } + + return ret; +} + +#endif + +/**************************************************************************** + * Name: qspi_lock + * + * Description: + * On QSPI buses where there are multiple devices, it will be necessary to + * lock QSPI to have exclusive access to the buses for a sequence of + * transfers. The bus should be locked before the chip is selected. After + * locking the QSPI bus, the caller should then also call the setfrequency, + * setbits, and setmode methods to make sure that the QSPI is properly + * configured for the device. If the QSPI bus is being shared, then it + * may have been left in an incompatible state. + * + * Input Parameters: + * dev - Device-specific state data + * lock - true: Lock QSPI bus, false: unlock QSPI bus + * + * Returned Value: + * None + * + ****************************************************************************/ + +static int qspi_lock(struct qspi_dev_s *dev, bool lock) +{ + struct stm32h7_qspidev_s *priv = (struct stm32h7_qspidev_s *)dev; + int ret; + + spiinfo("lock=%d\n", lock); + if (lock) + { + /* Take the semaphore (perhaps waiting) */ + + do + { + ret = nxsem_wait(&priv->exclsem); + + /* The only case that an error should occur here is if the wait + * was awakened by a signal. + */ + + DEBUGASSERT(ret == OK || ret == -EINTR); + } + while (ret == -EINTR); + } + else + { + (void)nxsem_post(&priv->exclsem); + ret = OK; + } + + return ret; +} + +/**************************************************************************** + * Name: qspi_setfrequency + * + * Description: + * Set the QSPI frequency. + * + * Input Parameters: + * dev - Device-specific state data + * frequency - The QSPI frequency requested + * + * Returned Value: + * Returns the actual frequency selected + * + ****************************************************************************/ + +static uint32_t qspi_setfrequency(struct qspi_dev_s *dev, uint32_t frequency) +{ + struct stm32h7_qspidev_s *priv = (struct stm32h7_qspidev_s *)dev; + uint32_t actual; + uint32_t prescaler; + uint32_t regval; + + if (priv->memmap) + { + /* XXX we have no better return here, but the caller will find out + * in their subsequent calls. + */ + + return 0; + } + + spiinfo("frequency=%d\n", frequency); + DEBUGASSERT(priv); + + /* Wait till BUSY flag reset */ + + qspi_abort(priv); + qspi_waitstatusflags(priv, QSPI_SR_BUSY, 0); + + /* Check if the requested frequency is the same as the frequency selection */ + + if (priv->frequency == frequency) + { + /* We are already at this frequency. Return the actual. */ + + return priv->actual; + } + + /* Configure QSPI to a frequency as close as possible to the requested + * frequency. + * + * QSCK frequency = STL32F7_QSPI_CLOCK / prescaler, or + * prescaler = STL32F7_QSPI_CLOCK / frequency + * + * Where prescaler can have the range 1 to 256 and the + * STM32_QUADSPI_CR_OFFSET register field holds prescaler - 1. + * NOTE that a "ceiling" type of calculation is performed. + * 'frequency' is treated as a not-to-exceed value. + */ + + prescaler = (frequency + STL32F7_QSPI_CLOCK - 1) / frequency; + + /* Make sure that the divider is within range */ + + if (prescaler < 1) + { + prescaler = 1; + } + else if (prescaler > 256) + { + prescaler = 256; + } + + /* Save the new prescaler value (minus one) */ + + regval = qspi_getreg(priv, STM32_QUADSPI_CR_OFFSET); + regval &= ~(QSPI_CR_PRESCALER_MASK); + regval |= (prescaler - 1) << QSPI_CR_PRESCALER_SHIFT; + qspi_putreg(priv, regval, STM32_QUADSPI_CR_OFFSET); + + /* Calculate the new actual frequency */ + + actual = STL32F7_QSPI_CLOCK / prescaler; + spiinfo("prescaler=%d actual=%d\n", prescaler, actual); + + /* Save the frequency setting */ + + priv->frequency = frequency; + priv->actual = actual; + + spiinfo("Frequency %d->%d\n", frequency, actual); + return actual; +} + +/**************************************************************************** + * Name: qspi_setmode + * + * Description: + * Set the QSPI mode. Optional. See enum qspi_mode_e for mode definitions. + * NOTE: the STM32H7 QSPI supports only modes 0 and 3. + * + * Input Parameters: + * dev - Device-specific state data + * mode - The QSPI mode requested + * + * Returned Value: + * none + * + ****************************************************************************/ + +static void qspi_setmode(struct qspi_dev_s *dev, enum qspi_mode_e mode) +{ + struct stm32h7_qspidev_s *priv = (struct stm32h7_qspidev_s *)dev; + uint32_t regval; + + if (priv->memmap) + { + /* XXX we have no better return here, but the caller will find out + * in their subsequent calls. + */ + + return; + } + + spiinfo("mode=%d\n", mode); + + /* Has the mode changed? */ + + if (mode != priv->mode) + { + /* Yes... Set the mode appropriately: + * + * QSPI CPOL CPHA + * MODE + * 0 0 0 + * 1 0 1 + * 2 1 0 + * 3 1 1 + */ + + regval = qspi_getreg(priv, STM32_QUADSPI_DCR_OFFSET); + regval &= ~(QSPI_DCR_CKMODE); + + switch (mode) + { + case QSPIDEV_MODE0: /* CPOL=0; CPHA=0 */ + break; + + case QSPIDEV_MODE3: /* CPOL=1; CPHA=1 */ + regval |= (QSPI_DCR_CKMODE); + break; + + case QSPIDEV_MODE1: /* CPOL=0; CPHA=1 */ + case QSPIDEV_MODE2: /* CPOL=1; CPHA=0 */ + spiinfo("unsupported mode=%d\n", mode); + default: + DEBUGASSERT(FALSE); + return; + } + + qspi_putreg(priv, regval, STM32_QUADSPI_DCR_OFFSET); + spiinfo("DCR=%08x\n", regval); + + /* Save the mode so that subsequent re-configurations will be faster */ + + priv->mode = mode; + } +} + +/**************************************************************************** + * Name: qspi_setbits + * + * Description: + * Set the number if bits per word. + * NOTE: the STM32H7 QSPI only supports 8 bits, so this does nothing. + * + * Input Parameters: + * dev - Device-specific state data + * nbits - The number of bits requests + * + * Returned Value: + * none + * + ****************************************************************************/ + +static void qspi_setbits(struct qspi_dev_s *dev, int nbits) +{ + /* Not meaningful for the STM32H7x6 */ + + if (8 != nbits) + { + spiinfo("unsupported nbits=%d\n", nbits); + DEBUGASSERT(FALSE); + } +} + +/**************************************************************************** + * Name: qspi_command + * + * Description: + * Perform one QSPI data transfer + * + * Input Parameters: + * dev - Device-specific state data + * cmdinfo - Describes the command transfer to be performed. + * + * Returned Value: + * Zero (OK) on SUCCESS, a negated errno on value of failure + * + ****************************************************************************/ + +static int qspi_command(struct qspi_dev_s *dev, + struct qspi_cmdinfo_s *cmdinfo) +{ + struct stm32h7_qspidev_s *priv = (struct stm32h7_qspidev_s *)dev; + struct qspi_xctnspec_s xctn; + int ret; + + /* Reject commands issued while in memory mapped mode, which will + * automatically cancel the memory mapping. You must exit the + * memory mapped mode first. + */ + + if (priv->memmap) + { + return -EBUSY; + } + + /* Set up the transaction descriptor as per command info */ + + ret = qspi_setupxctnfromcmd(&xctn, cmdinfo); + if (OK != ret) + { + return ret; + } + + /* Prepare for transaction */ + + /* Wait 'till non-busy */ + + qspi_abort(priv); + qspi_waitstatusflags(priv, QSPI_SR_BUSY, 0); + + /* Clear flags */ + + qspi_putreg(priv, + QSPI_FCR_CTEF | QSPI_FCR_CTCF | QSPI_FCR_CSMF | QSPI_FCR_CTOF, + STM32_QUADSPI_FCR_OFFSET); + +#ifdef CONFIG_STM32H7_QSPI_INTERRUPTS + /* interrupt mode will need access to the transaction context */ + + priv->xctn = &xctn; + + if (QSPICMD_ISDATA(cmdinfo->flags)) + { + DEBUGASSERT(cmdinfo->buffer != NULL && cmdinfo->buflen > 0); + DEBUGASSERT(IS_ALIGNED(cmdinfo->buffer)); + + if (QSPICMD_ISWRITE(cmdinfo->flags)) + { + uint32_t regval; + + /* Set up the Communications Configuration Register as per command + * info + */ + + qspi_ccrconfig(priv, &xctn, CCR_FMODE_INDWR); + + /* Enable 'Transfer Error' 'FIFO Threshhold' and 'Transfer Complete' + * interrupts. + */ + + regval = qspi_getreg(priv, STM32_QUADSPI_CR_OFFSET); + regval |= (QSPI_CR_TEIE | QSPI_CR_FTIE | QSPI_CR_TCIE); + qspi_putreg(priv, regval, STM32_QUADSPI_CR_OFFSET); + } + else + { + uint32_t regval; + uint32_t addrval; + + addrval = qspi_getreg(priv, STM32_QUADSPI_AR_OFFSET); + + /* Set up the Communications Configuration Register as per command + * info + */ + + qspi_ccrconfig(priv, &xctn, CCR_FMODE_INDRD); + + /* Start the transfer by re-writing the address in AR register */ + + qspi_putreg(priv, addrval, STM32_QUADSPI_AR_OFFSET); + + /* Enable 'Transfer Error' 'FIFO Threshhold' and 'Transfer Complete' + * interrupts + */ + + regval = qspi_getreg(priv, STM32_QUADSPI_CR_OFFSET); + regval |= (QSPI_CR_TEIE | QSPI_CR_FTIE | QSPI_CR_TCIE); + qspi_putreg(priv, regval, STM32_QUADSPI_CR_OFFSET); + } + } + else + { + uint32_t regval; + + /* We have no data phase, the command will execute as soon as we emit + * the CCR + */ + + /* Enable 'Transfer Error' and 'Transfer Complete' interrupts */ + + regval = qspi_getreg(priv, STM32_QUADSPI_CR_OFFSET); + regval |= (QSPI_CR_TEIE | QSPI_CR_TCIE); + qspi_putreg(priv, regval, STM32_QUADSPI_CR_OFFSET); + + /* Set up the Communications Configuration Register as per command + * info + */ + + qspi_ccrconfig(priv, &xctn, CCR_FMODE_INDRD); + } + + /* Wait for the interrupt routine to finish it's magic */ + + (void)nxsem_wait(&priv->op_sem); + MEMORY_SYNC(); + + /* Convey the result */ + + ret = xctn.disposition; + + /* because command transfers are so small, we're not going to use + * DMA for them, only interrupts or polling + */ + +#else + /* Polling mode */ + + /* Set up the Communications Configuration Register as per command info */ + + qspi_ccrconfig(priv, &xctn, CCR_FMODE_INDWR); + + /* That may be it, unless there is also data to transfer */ + + if (QSPICMD_ISDATA(cmdinfo->flags)) + { + DEBUGASSERT(cmdinfo->buffer != NULL && cmdinfo->buflen > 0); + DEBUGASSERT(IS_ALIGNED(cmdinfo->buffer)); + + if (QSPICMD_ISWRITE(cmdinfo->flags)) + { + ret = qspi_transmit_blocking(priv, &xctn); + } + else + { + ret = qspi_receive_blocking(priv, &xctn); + } + + MEMORY_SYNC(); + } + else + { + ret = OK; + } + + /* Wait for Transfer complete, and not busy */ + + qspi_waitstatusflags(priv, QSPI_SR_TCF, 1); + qspi_waitstatusflags(priv, QSPI_SR_BUSY, 0); + +#endif + + return ret; +} + +/**************************************************************************** + * Name: qspi_memory + * + * Description: + * Perform one QSPI memory transfer + * + * Input Parameters: + * dev - Device-specific state data + * meminfo - Describes the memory transfer to be performed. + * + * Returned Value: + * Zero (OK) on SUCCESS, a negated errno on value of failure + * + ****************************************************************************/ + +static int qspi_memory(struct qspi_dev_s *dev, + struct qspi_meminfo_s *meminfo) +{ + struct stm32h7_qspidev_s *priv = (struct stm32h7_qspidev_s *)dev; + struct qspi_xctnspec_s xctn; + int ret; + + /* Reject commands issued while in memory mapped mode, which will + * automatically cancel the memory mapping. You must exit the + * memory mapped mode first. + */ + + if (priv->memmap) + { + return -EBUSY; + } + + /* Set up the transaction descriptor as per command info */ + + ret = qspi_setupxctnfrommem(&xctn, meminfo); + if (OK != ret) + { + return ret; + } + + /* Prepare for transaction */ + + /* Wait 'till non-busy */ + + qspi_abort(priv); + qspi_waitstatusflags(priv, QSPI_SR_BUSY, 0); + + /* Clear flags */ + + qspi_putreg(priv, + QSPI_FCR_CTEF | QSPI_FCR_CTCF | QSPI_FCR_CSMF | QSPI_FCR_CTOF, + STM32_QUADSPI_FCR_OFFSET); + +#ifdef CONFIG_STM32H7_QSPI_INTERRUPTS + /* interrupt mode will need access to the transaction context */ + + priv->xctn = &xctn; + + DEBUGASSERT(meminfo->buffer != NULL && meminfo->buflen > 0); + DEBUGASSERT(IS_ALIGNED(meminfo->buffer)); + + if (QSPIMEM_ISWRITE(meminfo->flags)) + { + uint32_t regval; + + /* Set up the Communications Configuration Register as per command + * info + */ + + qspi_ccrconfig(priv, &xctn, CCR_FMODE_INDWR); + + /* Enable 'Transfer Error' 'FIFO Threshhold' and 'Transfer Complete' + * interrupts + */ + + regval = qspi_getreg(priv, STM32_QUADSPI_CR_OFFSET); + regval |= (QSPI_CR_TEIE | QSPI_CR_FTIE | QSPI_CR_TCIE); + qspi_putreg(priv, regval, STM32_QUADSPI_CR_OFFSET); + } + else + { + uint32_t regval; + uint32_t addrval; + + addrval = qspi_getreg(priv, STM32_QUADSPI_AR_OFFSET); + + /* Set up the Communications Configuration Register as per command + * info + */ + + qspi_ccrconfig(priv, &xctn, CCR_FMODE_INDRD); + + /* Start the transfer by re-writing the address in AR register */ + + qspi_putreg(priv, addrval, STM32_QUADSPI_AR_OFFSET); + + /* Enable 'Transfer Error' 'FIFO Threshhold' and 'Transfer Complete' + * interrupts + */ + + regval = qspi_getreg(priv, STM32_QUADSPI_CR_OFFSET); + regval |= (QSPI_CR_TEIE | QSPI_CR_FTIE | QSPI_CR_TCIE); + qspi_putreg(priv, regval, STM32_QUADSPI_CR_OFFSET); + } + + /* Wait for the interrupt routine to finish it's magic */ + + (void)nxsem_wait(&priv->op_sem); + MEMORY_SYNC(); + + /* convey the result */ + + ret = xctn.disposition; + +#elif defined(CONFIG_STM32H7_QSPI_DMA) + /* Can we perform DMA? Should we perform DMA? */ + + if (priv->candma && + meminfo->buflen > CONFIG_STM32H7_QSPI_DMATHRESHOLD && + IS_ALIGNED((uintptr_t)meminfo->buffer) && + IS_ALIGNED(meminfo->buflen)) + { + ret = qspi_memory_dma(priv, meminfo, &xctn); + } + else + { + /* polling mode */ + + /* Set up the Communications Configuration Register as per command info */ + + qspi_ccrconfig(priv, &xctn, + QSPIMEM_ISWRITE(meminfo->flags) ? CCR_FMODE_INDWR : + CCR_FMODE_INDRD); + + /* Transfer data */ + + DEBUGASSERT(meminfo->buffer != NULL && meminfo->buflen > 0); + DEBUGASSERT(IS_ALIGNED(meminfo->buffer)); + + if (QSPIMEM_ISWRITE(meminfo->flags)) + { + ret = qspi_transmit_blocking(priv, &xctn); + } + else + { + ret = qspi_receive_blocking(priv, &xctn); + } + + /* Wait for Transfer complete, and not busy */ + + qspi_waitstatusflags(priv, QSPI_SR_TCF, 1); + qspi_waitstatusflags(priv, QSPI_SR_BUSY, 0); + + MEMORY_SYNC(); + } + +#else + /* polling mode */ + + /* Set up the Communications Configuration Register as per command info */ + + qspi_ccrconfig(priv, &xctn, + QSPIMEM_ISWRITE(meminfo->flags) ? CCR_FMODE_INDWR : + CCR_FMODE_INDRD); + + /* Transfer data */ + + DEBUGASSERT(meminfo->buffer != NULL && meminfo->buflen > 0); + DEBUGASSERT(IS_ALIGNED(meminfo->buffer)); + + if (QSPIMEM_ISWRITE(meminfo->flags)) + { + ret = qspi_transmit_blocking(priv, &xctn); + } + else + { + ret = qspi_receive_blocking(priv, &xctn); + } + + /* Wait for Transfer complete, and not busy */ + + qspi_waitstatusflags(priv, QSPI_SR_TCF, 1); + qspi_waitstatusflags(priv, QSPI_SR_BUSY, 0); + + MEMORY_SYNC(); + +#endif + + return ret; +} + +/**************************************************************************** + * Name: qspi_alloc + * + * Description: + * Allocate a buffer suitable for DMA data transfer + * + * Input Parameters: + * dev - Device-specific state data + * buflen - Buffer length to allocate in bytes + * + * Returned Value: + * Address of tha allocated memory on success; NULL is returned on any + * failure. + * + ****************************************************************************/ + +static FAR void *qspi_alloc(FAR struct qspi_dev_s *dev, size_t buflen) +{ + /* Here we exploit the carnal knowledge the kmm_malloc() will return memory + * aligned to 64-bit addresses. The buffer length must be large enough to + * hold the rested buflen in units a 32-bits. + */ + + return kmm_malloc(ALIGN_UP(buflen)); +} + +/**************************************************************************** + * Name: QSPI_FREE + * + * Description: + * Free memory returned by QSPI_ALLOC + * + * Input Parameters: + * dev - Device-specific state data + * buffer - Buffer previously allocated via QSPI_ALLOC + * + * Returned Value: + * None. + * + ****************************************************************************/ + +static void qspi_free(FAR struct qspi_dev_s *dev, FAR void *buffer) +{ + if (buffer) + { + kmm_free(buffer); + } +} + +/**************************************************************************** + * Name: qspi_hw_initialize + * + * Description: + * Initialize the QSPI peripheral from hardware reset. + * + * Input Parameters: + * priv - Device state structure. + * + * Returned Value: + * Zero (OK) on SUCCESS, a negated errno on value of failure + * + ****************************************************************************/ + +static int qspi_hw_initialize(struct stm32h7_qspidev_s *priv) +{ + uint32_t regval; + + /* Disable the QSPI; abort anything happening, disable, wait for not busy */ + + qspi_abort(priv); + + regval = 0; + regval &= ~(QSPI_CR_EN); + qspi_putreg(priv, regval, STM32_QUADSPI_CR_OFFSET); + + /* Wait till BUSY flag reset */ + + qspi_waitstatusflags(priv, QSPI_SR_BUSY, 0); + + /* Disable all interrupt sources for starters */ + + regval = qspi_getreg(priv, STM32_QUADSPI_CR_OFFSET); + regval &= ~(QSPI_CR_TEIE | QSPI_CR_TCIE | QSPI_CR_FTIE | QSPI_CR_SMIE | + QSPI_CR_TOIE | QSPI_CR_FSEL | QSPI_CR_DFM); + +#if defined(CONFIG_STM32H7_QSPI_MODE_BANK2) + regval |= QSPI_CR_FSEL; +#endif + +#if defined(CONFIG_STM32H7_QSPI_MODE_DUAL) + regval |= QSPI_CR_DFM; +#endif + + /* Configure QSPI FIFO Threshold */ + + regval &= ~(QSPI_CR_FTHRES_MASK); + regval |= ((CONFIG_STM32H7_QSPI_FIFO_THESHOLD - 1) << QSPI_CR_FTHRES_SHIFT); + qspi_putreg(priv, regval, STM32_QUADSPI_CR_OFFSET); + + /* Wait till BUSY flag reset */ + + qspi_waitstatusflags(priv, QSPI_SR_BUSY, 0); + + /* Configure QSPI Clock Prescaler and Sample Shift */ + + regval = qspi_getreg(priv, STM32_QUADSPI_CR_OFFSET); + regval &= ~(QSPI_CR_PRESCALER_MASK | QSPI_CR_SSHIFT); + regval |= (0x01 << QSPI_CR_PRESCALER_SHIFT); + regval |= (0x00); + qspi_putreg(priv, regval, STM32_QUADSPI_CR_OFFSET); + + /* Configure QSPI Flash Size, CS High Time and Clock Mode */ + + regval = qspi_getreg(priv, STM32_QUADSPI_DCR_OFFSET); + regval &= ~(QSPI_DCR_CKMODE | QSPI_DCR_CSHT_MASK | QSPI_DCR_FSIZE_MASK); + regval |= (0x00); + regval |= ((CONFIG_STM32H7_QSPI_CSHT - 1) << QSPI_DCR_CSHT_SHIFT); + if (0 != CONFIG_STM32H7_QSPI_FLASH_SIZE) + { + unsigned int nsize = CONFIG_STM32H7_QSPI_FLASH_SIZE; + int nlog2size = 31; + + while ((nsize & 0x80000000) == 0) + { + --nlog2size; + nsize <<= 1; + } + + regval |= ((nlog2size - 1) << QSPI_DCR_FSIZE_SHIFT); + } + + qspi_putreg(priv, regval, STM32_QUADSPI_DCR_OFFSET); + + /* Enable QSPI */ + + regval = qspi_getreg(priv, STM32_QUADSPI_CR_OFFSET); + regval |= QSPI_CR_EN; + qspi_putreg(priv, regval, STM32_QUADSPI_CR_OFFSET); + + /* Wait till BUSY flag reset */ + + qspi_waitstatusflags(priv, QSPI_SR_BUSY, 0); + + qspi_dumpregs(priv, "After initialization"); + qspi_dumpgpioconfig("GPIO"); + + return OK; +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stm32h7_qspi_initialize + * + * Description: + * Initialize the selected QSPI port in master mode + * + * Input Parameters: + * intf - Interface number(must be zero) + * + * Returned Value: + * Valid QSPI device structure reference on success; a NULL on failure + * + ****************************************************************************/ + +struct qspi_dev_s *stm32h7_qspi_initialize(int intf) +{ + struct stm32h7_qspidev_s *priv; + uint32_t regval; + int ret; + + /* The STM32H7 has only a single QSPI port */ + + spiinfo("intf: %d\n", intf); + DEBUGASSERT(intf == 0); + + /* Select the QSPI interface */ + + if (intf == 0) + { + /* If this function is called multiple times, the following operations + * will be performed multiple times. + */ + + /* Select QSPI0 */ + + priv = &g_qspi0dev; + + /* Enable clocking to the QSPI peripheral */ + + regval = getreg32(STM32_RCC_AHB3ENR); + regval |= RCC_AHB3ENR_QSPIEN; + putreg32(regval, STM32_RCC_AHB3ENR); + + /* Reset the QSPI peripheral */ + + regval = getreg32(STM32_RCC_AHB3RSTR); + regval |= RCC_AHB3RSTR_QSPIRST; + putreg32(regval, STM32_RCC_AHB3RSTR); + regval &= ~RCC_AHB3RSTR_QSPIRST; + putreg32(regval, STM32_RCC_AHB3RSTR); + + /* Configure multiplexed pins as connected on the board. */ + + stm32_configgpio(GPIO_QSPI_CS); + stm32_configgpio(GPIO_QSPI_IO0); + stm32_configgpio(GPIO_QSPI_IO1); + stm32_configgpio(GPIO_QSPI_IO2); + stm32_configgpio(GPIO_QSPI_IO3); + stm32_configgpio(GPIO_QSPI_SCK); + } + else + { + spierr("ERROR: QSPI%d not supported\n", intf); + return NULL; + } + + /* Has the QSPI hardware been initialized? */ + + if (!priv->initialized) + { + /* Now perform one time initialization. + * + * Initialize the QSPI semaphore that enforces mutually exclusive + * access to the QSPI registers. + */ + + nxsem_init(&priv->exclsem, 0, 1); + +#ifdef CONFIG_STM32H7_QSPI_DMA + /* Pre-allocate DMA channels. */ + + if (priv->candma) + { + priv->dmach = stm32_dmachannel(DMACHAN_QUADSPI); + if (!priv->dmach) + { + spierr("ERROR: Failed to allocate the DMA channel\n"); + priv->candma = false; + } + } + + /* Initialize the QSPI semaphore that is used to wake up the waiting + * thread when the DMA transfer completes. This semaphore is used for + * signaling and, hence, should not have priority inheritance enabled. + */ + + nxsem_init(&priv->dmawait, 0, 0); + nxsem_setprotocol(&priv->dmawait, SEM_PRIO_NONE); + + /* Create a watchdog time to catch DMA timeouts */ + + priv->dmadog = wd_create(); + if (priv->dmadog == NULL) + { + spierr("ERROR: Failed to create wdog\n"); + goto errout_with_dmahandles; + } +#endif + +#ifdef CONFIG_STM32H7_QSPI_INTERRUPTS + /* Attach the interrupt handler */ + + ret = irq_attach(priv->irq, priv->handler, NULL); + if (ret < 0) + { + spierr("ERROR: Failed to attach irq %d\n", priv->irq); + goto errout_with_dmadog; + } + + /* Initialize the semaphore that blocks until the operation completes. + * This semaphore is used for signaling and, hence, should not have + * priority inheritance enabled. + */ + + nxsem_init(&priv->op_sem, 0, 0); + nxsem_setprotocol(&priv->op_sem, SEM_PRIO_NONE); +#endif + + /* Perform hardware initialization. Puts the QSPI into an active + * state. + */ + + ret = qspi_hw_initialize(priv); + if (ret < 0) + { + spierr("ERROR: Failed to initialize QSPI hardware\n"); + goto errout_with_irq; + } + + /* Enable interrupts at the NVIC */ + + priv->initialized = true; + priv->memmap = false; +#ifdef CONFIG_STM32H7_QSPI_INTERRUPTS + up_enable_irq(priv->irq); +#endif + } + + return &priv->qspi; + +errout_with_irq: +#ifdef CONFIG_STM32H7_QSPI_INTERRUPTS + irq_detach(priv->irq); + +errout_with_dmadog: +#endif +#ifdef CONFIG_STM32H7_QSPI_DMA + wd_delete(priv->dmadog); + +errout_with_dmahandles: + nxsem_destroy(&priv->dmawait); + + if (priv->dmach) + { + stm32_dmafree(priv->dmach); + priv->dmach = NULL; + } +#endif + + nxsem_destroy(&priv->exclsem); + return NULL; +} + +/**************************************************************************** + * Name: stm32h7_qspi_enter_memorymapped + * + * Description: + * Put the QSPI device into memory mapped mode + * + * Input Parameters: + * dev - QSPI device + * meminfo - parameters like for a memory transfer used for reading + * + * Returned Value: + * None + * + ****************************************************************************/ + +void stm32h7_qspi_enter_memorymapped(struct qspi_dev_s *dev, + const struct qspi_meminfo_s *meminfo, + uint32_t lpto) +{ + struct stm32h7_qspidev_s *priv = (struct stm32h7_qspidev_s *)dev; + uint32_t regval; + struct qspi_xctnspec_s xctn; + + /* lock during this mode change */ + + qspi_lock(dev, true); + + if (priv->memmap) + { + qspi_lock(dev, false); + return; + } + + /* Abort anything in-progress */ + + qspi_abort(priv); + + /* Wait till BUSY flag reset */ + + qspi_waitstatusflags(priv, QSPI_SR_BUSY, 0); + + /* if we want the 'low-power timeout counter' */ + + if (lpto > 0) + { + /* Set the Low Power Timeout value (automatically de-assert + * CS if memory is not accessed for a while) + */ + + qspi_putreg(priv, lpto, STM32_QUADSPI_LPTR_OFFSET); + + /* Clear Timeout interrupt */ + + qspi_putreg(&g_qspi0dev, QSPI_FCR_CTOF, STM32_QUADSPI_FCR_OFFSET); + +#ifdef CONFIG_STM32H7_QSPI_INTERRUPTS + /* Enable Timeout interrupt */ + + regval = qspi_getreg(priv, STM32_QUADSPI_CR_OFFSET); + regval |= (QSPI_CR_TCEN | QSPI_CR_TOIE); + qspi_putreg(priv, regval, STM32_QUADSPI_CR_OFFSET); +#endif + } + else + { + regval = qspi_getreg(priv, STM32_QUADSPI_CR_OFFSET); + regval &= ~QSPI_CR_TCEN; + qspi_putreg(priv, regval, STM32_QUADSPI_CR_OFFSET); + } + + /* create a transaction object */ + + qspi_setupxctnfrommem(&xctn, meminfo); + +#ifdef CONFIG_STM32H7_QSPI_INTERRUPTS + priv->xctn = NULL; +#endif + + /* set it into the ccr */ + + qspi_ccrconfig(priv, &xctn, CCR_FMODE_MEMMAP); + priv->memmap = true; + + /* we should be in memory mapped mode now */ + + qspi_dumpregs(priv, "After memory mapped:"); + + /* finished this mode change */ + + qspi_lock(dev, false); +} + +/**************************************************************************** + * Name: stm32h7_qspi_exit_memorymapped + * + * Description: + * Take the QSPI device out of memory mapped mode + * + * Input Parameters: + * dev - QSPI device + * + * Returned Value: + * None + * + ****************************************************************************/ + +void stm32h7_qspi_exit_memorymapped(struct qspi_dev_s *dev) +{ + struct stm32h7_qspidev_s *priv = (struct stm32h7_qspidev_s *)dev; + + qspi_lock(dev, true); + + /* A simple abort is sufficient */ + + qspi_abort(priv); + priv->memmap = false; + + qspi_lock(dev, false); +} + +#endif /* CONFIG_STM32H7_QSPI */ diff --git a/arch/arm/src/stm32h7/stm32_qspi.h b/arch/arm/src/stm32h7/stm32_qspi.h new file mode 100644 index 00000000000..bbb774c5778 --- /dev/null +++ b/arch/arm/src/stm32h7/stm32_qspi.h @@ -0,0 +1,144 @@ +/**************************************************************************** + * arch/arm/src/stm32h7/stm32_qspi.h + * + * Copyright (C) 2016, 2019 Gregory Nutt. All rights reserved. + * Author: dev@ziggurat29.com + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#ifndef __ARCH_ARM_SRC_STM32_STM32H7_QSPI_H +#define __ARCH_ARM_SRC_STM32_STM32H7_QSPI_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include + +#include +#include + +#include "chip.h" + +#ifdef CONFIG_STM32H7_QUADSPI + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Public Types + ****************************************************************************/ + +/**************************************************************************** + * Inline Functions + ****************************************************************************/ + +#ifndef __ASSEMBLY__ + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +#undef EXTERN +#if defined(__cplusplus) +#define EXTERN extern "C" +extern "C" +{ +#else +#define EXTERN extern +#endif + +/**************************************************************************** + * Public Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Name: stm32l4_qspi_initialize + * + * Description: + * Initialize the selected QSPI port in master mode + * + * Input Parameters: + * intf - Interface number(must be zero) + * + * Returned Value: + * Valid SPI device structure reference on success; a NULL on failure + * + ****************************************************************************/ + +struct qspi_dev_s; +FAR struct qspi_dev_s *stm32h7_qspi_initialize(int intf); + +/**************************************************************************** + * Name: stm32l4_qspi_enter_memorymapped + * + * Description: + * Put the QSPI device into memory mapped mode + * + * Input Parameters: + * dev - QSPI device + * meminfo - parameters like for a memory transfer used for reading + * lpto - number of cycles to wait to automatically de-assert CS + * + * Returned Value: + * None + * + ****************************************************************************/ + +void stm32h7_qspi_enter_memorymapped(struct qspi_dev_s *dev, + const struct qspi_meminfo_s *meminfo, + uint32_t lpto); + +/**************************************************************************** + * Name: stm32l4_qspi_exit_memorymapped + * + * Description: + * Take the QSPI device out of memory mapped mode + * + * Input Parameters: + * dev - QSPI device + * + * Returned Value: + * None + * + ****************************************************************************/ + +void stm32h7_qspi_exit_memorymapped(struct qspi_dev_s *dev); + +#undef EXTERN +#if defined(__cplusplus) +} +#endif + +#endif /* __ASSEMBLY__ */ +#endif /* CONFIG_STM32H7_QSPI */ +#endif /* __ARCH_ARM_SRC_STM32_STM32H7_QSPI_H */ From 3b9efc95a2e0e923f34a857c06b45596beb23552 Mon Sep 17 00:00:00 2001 From: Xiang Xiao Date: Mon, 6 Jan 2020 00:29:59 +0800 Subject: [PATCH 3/4] Format all shell scripts in tools folder Change-Id: Ieef2eb93d56c03972b4dc63a1c55aabf1fb0d169 Signed-off-by: Xiang Xiao --- tools/configure.bat | 6 +- tools/configure.sh | 156 +++++++++--------- tools/copydir.bat | 4 +- tools/copydir.sh | 41 +++-- tools/define.bat | 18 +-- tools/define.sh | 252 +++++++++++++++-------------- tools/incdir.bat | 22 +-- tools/incdir.sh | 240 ++++++++++++++-------------- tools/indent.sh | 132 +++++++-------- tools/kconfig.bat | 11 +- tools/link.bat | 8 +- tools/link.sh | 65 ++++---- tools/mkconfigvars.sh | 66 ++++---- tools/mkctags.sh | 2 +- tools/mkexport.sh | 354 ++++++++++++++++++++-------------------- tools/mkromfsimg.sh | 104 ++++++------ tools/refresh.sh | 96 +++++------ tools/sethost.sh | 218 ++++++++++++------------- tools/testbuild.sh | 364 +++++++++++++++++++++--------------------- tools/unlink.bat | 2 +- tools/unlink.sh | 34 ++-- tools/version.sh | 116 +++++++------- tools/zipme.sh | 151 +++++++++--------- 23 files changed, 1227 insertions(+), 1235 deletions(-) diff --git a/tools/configure.bat b/tools/configure.bat index 23096bafb94..64f0fc1a44a 100755 --- a/tools/configure.bat +++ b/tools/configure.bat @@ -115,10 +115,10 @@ echo -f: echo Informs the tool that it should use POSIX style paths like /usr/local/bin. echo By default, Windows style paths like C:\\Program Files are used. echo -l selects the Linux (l) host environment. The [-c^|u^|n] options -echo select one of the Windows environments. Default: Use host setup -echo in the defconfig file +echo select one of the Windows environments. Default: Use host setup +echo in the defconfig file echo [-c^|u^|n] selects the Windows host and a Windows environment: Cygwin (c), -echo Ubuntu under Windows 10 (u), or Windows native (n). Default Cygwin +echo Ubuntu under Windows 10 (u), or Windows native (n). Default Cygwin echo -a ^: echo Informs the configuration tool where the application build echo directory. This is a relative path from the top-level NuttX diff --git a/tools/configure.sh b/tools/configure.sh index 321e08787e2..b91b3915cb4 100755 --- a/tools/configure.sh +++ b/tools/configure.sh @@ -75,52 +75,52 @@ skip=0 while [ ! -z "$1" ]; do case "$1" in - -a ) - shift - appdir=$1 - ;; - -c ) - host=windows - wenv=cygwin - ;; - -d ) - debug=y - set -x - ;; - -g ) - host=windows - wenv=msys - ;; - -h ) + -a ) + shift + appdir=$1 + ;; + -c ) + host=windows + wenv=cygwin + ;; + -d ) + debug=y + set -x + ;; + -g ) + host=windows + wenv=msys + ;; + -h ) + echo "$USAGE" + exit 0 + ;; + -l ) + host=linux + ;; + -m ) + host=macos + ;; + -n ) + host=windows + wenv=native + ;; + -s ) + skip=1 + ;; + -u ) + host=windows + wenv=ubuntu + ;; + *) + if [ ! -z "${boardconfig}" ]; then + echo "" + echo " defined twice" echo "$USAGE" - exit 0 - ;; - -l ) - host=linux - ;; - -m ) - host=macos - ;; - -n ) - host=windows - wenv=native - ;; - -s ) - skip=1 - ;; - -u ) - host=windows - wenv=ubuntu - ;; - *) - if [ ! -z "${boardconfig}" ]; then - echo "" - echo " defined twice" - echo "$USAGE" - exit 1 - fi - boardconfig=$1 - ;; + exit 1 + fi + boardconfig=$1 + ;; esac shift done @@ -330,43 +330,43 @@ if [ ! -z "$host" ]; then sed -i -e "/CONFIG_SIM_X8664_SYSTEMV/d" ${dest_config} case "$host" in - "linux") - echo " Select CONFIG_HOST_LINUX=y" - echo "CONFIG_HOST_LINUX=y" >> "${dest_config}" - echo "CONFIG_SIM_X8664_SYSTEMV=y" >> "${dest_config}" + "linux") + echo " Select CONFIG_HOST_LINUX=y" + echo "CONFIG_HOST_LINUX=y" >> "${dest_config}" + echo "CONFIG_SIM_X8664_SYSTEMV=y" >> "${dest_config}" + ;; + + "macos") + echo " Select CONFIG_HOST_MACOS=y" + echo "CONFIG_HOST_MACOS=y" >> "${dest_config}" + ;; + + "windows") + echo " Select CONFIG_HOST_WINDOWS=y" + echo "CONFIG_HOST_WINDOWS=y" >> "${dest_config}" + echo "CONFIG_SIM_X8664_MICROSOFT=y" >> "${dest_config}" + + case "$wenv" in + "cygwin") + echo " Select CONFIG_WINDOWS_CYGWIN=y" + echo "CONFIG_WINDOWS_CYGWIN=y" >> "${dest_config}" ;; - "macos") - echo " Select CONFIG_HOST_MACOS=y" - echo "CONFIG_HOST_MACOS=y" >> "${dest_config}" + "msys") + echo " Select CONFIG_WINDOWS_MSYS=y" + echo "CONFIG_WINDOWS_MSYS=y" >> "${dest_config}" ;; - "windows") - echo " Select CONFIG_HOST_WINDOWS=y" - echo "CONFIG_HOST_WINDOWS=y" >> "${dest_config}" - echo "CONFIG_SIM_X8664_MICROSOFT=y" >> "${dest_config}" - - case "$wenv" in - "cygwin") - echo " Select CONFIG_WINDOWS_CYGWIN=y" - echo "CONFIG_WINDOWS_CYGWIN=y" >> "${dest_config}" - ;; - - "msys") - echo " Select CONFIG_WINDOWS_MSYS=y" - echo "CONFIG_WINDOWS_MSYS=y" >> "${dest_config}" - ;; - - "ubuntu") - echo " Select CONFIG_WINDOWS_UBUNTU=y" - echo "CONFIG_WINDOWS_UBUNTU=y" >> "${dest_config}" - ;; - - *) - echo " Select CONFIG_WINDOWS_NATIVE=y" - echo "CONFIG_WINDOWS_NATIVE=y" >> "${dest_config}" - ;; - esac + "ubuntu") + echo " Select CONFIG_WINDOWS_UBUNTU=y" + echo "CONFIG_WINDOWS_UBUNTU=y" >> "${dest_config}" + ;; + + *) + echo " Select CONFIG_WINDOWS_NATIVE=y" + echo "CONFIG_WINDOWS_NATIVE=y" >> "${dest_config}" + ;; + esac esac fi diff --git a/tools/copydir.bat b/tools/copydir.bat index 2857c415f04..8f824313429 100755 --- a/tools/copydir.bat +++ b/tools/copydir.bat @@ -96,7 +96,7 @@ goto :End :ShowUsage echo USAGE: %0 ^ ^ echo Where: -echo ^ is the source directory to be copied -echo ^ is the destination directory to be created +echo ^ is the source directory to be copied +echo ^ is the destination directory to be created :End diff --git a/tools/copydir.sh b/tools/copydir.sh index d3dca213f27..01ce3831b5c 100755 --- a/tools/copydir.sh +++ b/tools/copydir.sh @@ -52,8 +52,8 @@ dest=$2 # Verify that arguments were provided if [ -z "${src}" -o -z "${dest}" ]; then - echo "Missing src and/or dest arguments" - exit 1 + echo "Missing src and/or dest arguments" + exit 1 fi # Check if something already exists at the destination path replace it with @@ -62,40 +62,39 @@ fi # report that it does not exist. if [ -h "${dest}" ]; then - rm -f "${dest}" + rm -f "${dest}" else - # If the path exists and is a directory that contains the "fake link" - # mark, then treat it like a soft link (i.e., remove the directory) + # If the path exists and is a directory that contains the "fake link" + # mark, then treat it like a soft link (i.e., remove the directory) - if [ -d "${dest}" -a -f "${dest}/.fakelnk" ]; then - rm -rf "${dest}" - else + if [ -d "${dest}" -a -f "${dest}/.fakelnk" ]; then + rm -rf "${dest}" + else - # Does anything exist at the destination path? + # Does anything exist at the destination path? - if [ -e "${dest}" ]; then + if [ -e "${dest}" ]; then - # It is something else (like a file) or directory that does - # not contain the "fake link" mark + # It is something else (like a file) or directory that does + # not contain the "fake link" mark - echo "${dest} already exists but is not a symbolic link" - exit 1 - fi - fi + echo "${dest} already exists but is not a symbolic link" + exit 1 + fi + fi fi # Verify that a directory exists at the source path if [ ! -d "${src}" ]; then - echo "No directory at ${src}" - exit 1 + echo "No directory at ${src}" + exit 1 fi # Copy the directory cp -a "${src}" "${dest}" || \ - { echo "Failed to create link: $dest" ; rm -rf ${dest} ; exit 1 ; } + { echo "Failed to create link: $dest" ; rm -rf ${dest} ; exit 1 ; } touch "${dest}/.fakelnk" || \ - { echo "Failed to touch ${dest}/.fakelnk" ; rm -rf ${dest} ; exit 1 ; } - + { echo "Failed to touch ${dest}/.fakelnk" ; rm -rf ${dest} ; exit 1 ; } diff --git a/tools/define.bat b/tools/define.bat index 13d29ac319c..df7bc266847 100755 --- a/tools/define.bat +++ b/tools/define.bat @@ -165,14 +165,14 @@ echo definitions arguments for a variety of diffent ccpaths in a variety of echo compilation environments" echo USAGE:%progname% [-h] ^ [-val ^<^val1^>] [^ [-val ^] [^ [-val ^] ...]] echo Where:" -echo ^ -echo The full path to your ccpath -echo ^ ^ ^ ... -echo A list of pre-preprocesser variable names to be defined. -echo [-val ^] [-val ^] [-val ^] ... -echo optional values to be assigned to each pre-processor variable. -echo If not supplied, the variable will be defined with no explicit value. -echo -h -echo Show this text and exit +echo ^ +echo The full path to your ccpath +echo ^ ^ ^ ... +echo A list of pre-preprocesser variable names to be defined. +echo [-val ^] [-val ^] [-val ^] ... +echo optional values to be assigned to each pre-processor variable. +echo If not supplied, the variable will be defined with no explicit value. +echo -h +echo Show this text and exit :End diff --git a/tools/define.sh b/tools/define.sh index a7d5dcf3ca1..e927d2c5b4a 100755 --- a/tools/define.sh +++ b/tools/define.sh @@ -42,39 +42,39 @@ usage="USAGE: $progname [-w] [-d] [-h] [=val1] [[=va advice="Try '$progname -h' for more information" while [ ! -z "$1" ]; do - case $1 in - -d ) - set -x - ;; - -w ) - wintool=y - ;; - -h ) - echo "$progname is a tool for flexible generation of command line pre-processor" - echo "definitions arguments for a variety of diffent compilers in a variety of" - echo "compilation environments" - echo "" - echo $usage - echo "" - echo "Where:" - echo " " - echo " The full path to your compiler" - echo " [ ..." - echo " A list of pre-preprocesser variable names to be defined." - echo " [=val1] [=val2] [=val3]" - echo " optional values to be assigned to each pre-processor variable." - echo " If not supplied, the variable will be defined with no explicit value." - echo " -w" - echo " The compiler is a Windows native tool and requires Windows" - echo " style pathnames like C:\\Program Files" - echo " -d" - echo " Enable script debug" - ;; - * ) - break; - ;; - esac - shift + case $1 in + -d ) + set -x + ;; + -w ) + wintool=y + ;; + -h ) + echo "$progname is a tool for flexible generation of command line pre-processor" + echo "definitions arguments for a variety of diffent compilers in a variety of" + echo "compilation environments" + echo "" + echo $usage + echo "" + echo "Where:" + echo " " + echo " The full path to your compiler" + echo " [ ..." + echo " A list of pre-preprocesser variable names to be defined." + echo " [=val1] [=val2] [=val3]" + echo " optional values to be assigned to each pre-processor variable." + echo " If not supplied, the variable will be defined with no explicit value." + echo " -w" + echo " The compiler is a Windows native tool and requires Windows" + echo " style pathnames like C:\\Program Files" + echo " -d" + echo " Enable script debug" + ;; + * ) + break; + ;; + esac + shift done ccpath=$1 @@ -82,17 +82,17 @@ shift varlist=$@ if [ -z "$ccpath" ]; then - echo "Missing compiler path" - echo $usage - echo $advice - exit 1 + echo "Missing compiler path" + echo $usage + echo $advice + exit 1 fi if [ -z "$varlist" ]; then - echo "Missing definition list" - echo $usage - echo $advice - exit 1 + echo "Missing definition list" + echo $usage + echo $advice + exit 1 fi # @@ -121,37 +121,37 @@ gcc=`echo $ccpath | grep gcc` sdcc=`echo $ccpath | grep sdcc` if [ "X$os" = "XCygwin" ]; then - # - # We can treat Cygwin native toolchains just like Linux native - # toolchains in the Linux. Let's assume: - # 1. GCC or SDCC are the only possible Cygwin native compilers - # 2. If this is a Window native GCC version, then -w provided - # on the command line (wintool=y) - - if [ -z "$gcc" -a -z "$sdcc" ]; then - # - # Not GCC or SDCC, must be Windows native - # - compiler=`cygpath -u "$ccpath"` - else - if [ "X$wintool" == "Xy" ]; then - # - # It is a native GCC or SDCC compiler - # - compiler=`cygpath -u "$ccpath"` - else - # - # GCC or SDCC and not for Windows - # - compiler="$ccpath" - fi - fi + # + # We can treat Cygwin native toolchains just like Linux native + # toolchains in the Linux. Let's assume: + # 1. GCC or SDCC are the only possible Cygwin native compilers + # 2. If this is a Window native GCC version, then -w provided + # on the command line (wintool=y) + + if [ -z "$gcc" -a -z "$sdcc" ]; then + # + # Not GCC or SDCC, must be Windows native + # + compiler=`cygpath -u "$ccpath"` + else + if [ "X$wintool" == "Xy" ]; then + # + # It is a native GCC or SDCC compiler + # + compiler=`cygpath -u "$ccpath"` + else + # + # GCC or SDCC and not for Windows + # + compiler="$ccpath" + fi + fi else - # - # Otherwise, we must be in a Linux environment where there are - # only Linux native toolchains - # - compiler="$ccpath" + # + # Otherwise, we must be in a Linux environment where there are + # only Linux native toolchains + # + compiler="$ccpath" fi exefile=`basename "$compiler"` @@ -159,9 +159,9 @@ exefile=`basename "$compiler"` # a special output format as well as special paths if [ "X$exefile" = "Xez8cc.exe" -o "X$exefile" = "Xzneocc.exe" -o "X$exefile" = "Xez80cc.exe" ]; then - fmt=define + fmt=define else - fmt=std + fmt=std fi # Now process each definition in the definition list @@ -169,60 +169,58 @@ fi unset response for vardef in $varlist; do - varname=`echo $vardef | cut -d'=' -f1` - if [ "X$varname" != "X$vardef" ]; then - varvalue=`echo $vardef | cut -d'=' -f2` - else - unset varvalue - fi - - # Handle the output depending on if there is a value for the variable or not - - if [ -z "$varvalue" ]; then - - # Handle the output using the selected format - - if [ "X$fmt" = "Xdefine" ]; then - # Treat the first definition differently - - if [ -z "$response" ]; then - response="-define:"$varname - else - response=$response" -define:$varname" - fi - else - # Treat the first definition differently - - if [ -z "$response" ]; then - response=-D$varname - else - response=$response" -D$varname" - fi - fi - else - - # Handle the output using the selected format - - if [ "X$fmt" = "Xdefine" ]; then - # Treat the first definition differently - - if [ -z "$response" ]; then - response="-define:"$varname=$varvalue - else - response=$response" -define:$varname=$varvalue" - fi - else - # Treat the first definition differently - - if [ -z "$response" ]; then - response=-D$varname=$varvalue - else - response=$response" -D$varname=$varvalue" - fi - fi - fi + varname=`echo $vardef | cut -d'=' -f1` + if [ "X$varname" != "X$vardef" ]; then + varvalue=`echo $vardef | cut -d'=' -f2` + else + unset varvalue + fi + + # Handle the output depending on if there is a value for the variable or not + + if [ -z "$varvalue" ]; then + + # Handle the output using the selected format + + if [ "X$fmt" = "Xdefine" ]; then + # Treat the first definition differently + + if [ -z "$response" ]; then + response="-define:"$varname + else + response=$response" -define:$varname" + fi + else + # Treat the first definition differently + + if [ -z "$response" ]; then + response=-D$varname + else + response=$response" -D$varname" + fi + fi + else + + # Handle the output using the selected format + + if [ "X$fmt" = "Xdefine" ]; then + # Treat the first definition differently + + if [ -z "$response" ]; then + response="-define:"$varname=$varvalue + else + response=$response" -define:$varname=$varvalue" + fi + else + # Treat the first definition differently + + if [ -z "$response" ]; then + response=-D$varname=$varvalue + else + response=$response" -D$varname=$varvalue" + fi + fi + fi done echo $response - - diff --git a/tools/incdir.bat b/tools/incdir.bat index f7383fc9a5c..81b5c6ef2e4 100755 --- a/tools/incdir.bat +++ b/tools/incdir.bat @@ -151,15 +151,15 @@ echo %progname% is a tool for flexible generation of include path arguments for echo variety of different compilers in a variety of compilation environments echo USAGE: %progname% [-w] [-d] [-s] [-h] ^ ^ [^ [^ ...]] echo Where: -echo ^ -echo The full path to your compiler -echo ^ [^ [^ ...]] -echo A list of include directories -echo -w, -d -echo For compatibility with incdir.sh (ignored) -echo -s -echo Generate standard, system header file paths instead of normal user -echo header file paths. -echo -h -echo Shows this help text and exits. +echo ^ +echo The full path to your compiler +echo ^ [^ [^ ...]] +echo A list of include directories +echo -w, -d +echo For compatibility with incdir.sh (ignored) +echo -s +echo Generate standard, system header file paths instead of normal user +echo header file paths. +echo -h +echo Shows this help text and exits. :End diff --git a/tools/incdir.sh b/tools/incdir.sh index 3c3d487b604..d486a1f23f6 100755 --- a/tools/incdir.sh +++ b/tools/incdir.sh @@ -41,44 +41,44 @@ usage="USAGE: $progname [-w] [-d] [-h] [ [ .. advice="Try '$progname -h' for more information" while [ ! -z "$1" ]; do - case $1 in - -d ) - set -x - ;; - -w ) - wintool=y - ;; - -s ) - pathtype=system - ;; - -h ) - echo "$progname is a tool for flexible generation of include path arguments for a" - echo "variety of different compilers in a variety of compilation environments" - echo "" - echo $usage - echo "" - echo "Where:" - echo " " - echo " The full path to your compiler" - echo " [ [ ...]]" - echo " A list of include directories" - echo " -w" - echo " The compiler is a Windows native tool and requires Windows" - echo " style pathnames like C:\\Program Files" - echo " -s" - echo " Generate standard, system header file paths instead of normal user" - echo " header file paths." - echo " -d" - echo " Enable script debug" - echo " -h" - echo " Shows this help text and exits." - exit 0 - ;; - * ) - break; - ;; - esac - shift + case $1 in + -d ) + set -x + ;; + -w ) + wintool=y + ;; + -s ) + pathtype=system + ;; + -h ) + echo "$progname is a tool for flexible generation of include path arguments for a" + echo "variety of different compilers in a variety of compilation environments" + echo "" + echo $usage + echo "" + echo "Where:" + echo " " + echo " The full path to your compiler" + echo " [ [ ...]]" + echo " A list of include directories" + echo " -w" + echo " The compiler is a Windows native tool and requires Windows" + echo " style pathnames like C:\\Program Files" + echo " -s" + echo " Generate standard, system header file paths instead of normal user" + echo " header file paths." + echo " -d" + echo " Enable script debug" + echo " -h" + echo " Shows this help text and exits." + exit 0 + ;; + * ) + break; + ;; + esac + shift done ccpath=$1 @@ -86,17 +86,17 @@ shift dirlist=$@ if [ -z "$ccpath" ]; then - echo "Missing compiler path" - echo $usage - echo $advice - exit 1 + echo "Missing compiler path" + echo $usage + echo $advice + exit 1 fi if [ -z "$dirlist" ]; then - echo "Missing include directory list" - echo $usage - echo $advice - exit 1 + echo "Missing include directory list" + echo $usage + echo $advice + exit 1 fi # @@ -132,32 +132,32 @@ fi sdcc=`echo $ccpath | grep sdcc` if [ "X$os" = "XCygwin" ]; then - # We can treat Cygwin native toolchains just like Linux native - # toolchains in the Linux. Let's assume: - # 1. GCC or SDCC are the only possible Cygwin native compilers - # 2. If this is a Window native GCC version, then -w must be - # provided on the command line (wintool=y) - - if [ -z "$gcc" -a -z "$sdcc" ]; then - # Not GCC or SDCC, must be Windows native - windows=yes - compiler=`cygpath -u "$ccpath"` - else - if [ "X$wintool" == "Xy" ]; then - # It is a native GCC or SDCC compiler - windows=yes - compiler=`cygpath -u "$ccpath"` - else - # GCC or SDCC and not for Windows - windows=no - compiler="$ccpath" - fi - fi + # We can treat Cygwin native toolchains just like Linux native + # toolchains in the Linux. Let's assume: + # 1. GCC or SDCC are the only possible Cygwin native compilers + # 2. If this is a Window native GCC version, then -w must be + # provided on the command line (wintool=y) + + if [ -z "$gcc" -a -z "$sdcc" ]; then + # Not GCC or SDCC, must be Windows native + windows=yes + compiler=`cygpath -u "$ccpath"` + else + if [ "X$wintool" == "Xy" ]; then + # It is a native GCC or SDCC compiler + windows=yes + compiler=`cygpath -u "$ccpath"` + else + # GCC or SDCC and not for Windows + windows=no + compiler="$ccpath" + fi + fi else - # Otherwise, we must be in a Linux environment where there are - # only Linux native toolchains - windows=no - compiler="$ccpath" + # Otherwise, we must be in a Linux environment where there are + # only Linux native toolchains + windows=no + compiler="$ccpath" fi exefile=`basename "$compiler"` @@ -165,25 +165,25 @@ exefile=`basename "$compiler"` # a special output format as well as special paths if [ "X$exefile" = "Xez8cc.exe" -o "X$exefile" = "Xzneocc.exe" -o "X$exefile" = "Xez80cc.exe" ]; then - fmt=zds + fmt=zds else - fmt=std + fmt=std fi # Select system or user header file path command line option if [ "X$fmt" = "Xzds" ]; then - if [ "X$pathtype" = "Xsystem" ]; then - cmdarg=-stdinc: - else - cmdarg=-usrinc: - fi + if [ "X$pathtype" = "Xsystem" ]; then + cmdarg=-stdinc: + else + cmdarg=-usrinc: + fi else - if [ "X$pathtype" = "Xsystem" ]; then - cmdarg=-isystem - else - cmdarg=-I - fi + if [ "X$pathtype" = "Xsystem" ]; then + cmdarg=-isystem + else + cmdarg=-I + fi fi # Now process each directory in the directory list @@ -191,47 +191,45 @@ fi unset response for dir in $dirlist; do - # Verify that the include directory exists - - if [ ! -d $dir ]; then - echo "Include path '$dir' does not exist" - echo $showusage - exit 1 - fi - - # Check if the path needs to be extended for Windows-based tools under Cygwin - - if [ "X$windows" = "Xyes" ]; then - path=`cygpath -w $dir` - else - path=$dir - fi - - # Handle the output using the selected format - - if [ "X$fmt" = "Xzds" ]; then - # Treat the first directory differently - - if [ -z "$response" ]; then - response="${cmdarg}'"${path} - else - response=${response}";${path}" - fi - else - # Treat the first directory differently - - if [ -z "$response" ]; then - response="${cmdarg} \"$path\"" - else - response="${response} ${cmdarg} \"$path\"" - fi - fi + # Verify that the include directory exists + + if [ ! -d $dir ]; then + echo "Include path '$dir' does not exist" + echo $showusage + exit 1 + fi + + # Check if the path needs to be extended for Windows-based tools under Cygwin + + if [ "X$windows" = "Xyes" ]; then + path=`cygpath -w $dir` + else + path=$dir + fi + + # Handle the output using the selected format + + if [ "X$fmt" = "Xzds" ]; then + # Treat the first directory differently + + if [ -z "$response" ]; then + response="${cmdarg}'"${path} + else + response=${response}";${path}" + fi + else + # Treat the first directory differently + + if [ -z "$response" ]; then + response="${cmdarg} \"$path\"" + else + response="${response} ${cmdarg} \"$path\"" + fi + fi done if [ "X$fmt" = "Xzds" ]; then - response=$response"'" + response=$response"'" fi echo $response - - diff --git a/tools/indent.sh b/tools/indent.sh index 4aa06262d67..caebb1b451e 100755 --- a/tools/indent.sh +++ b/tools/indent.sh @@ -70,66 +70,66 @@ mode=inplace fca=-fca while [ ! -z "${1}" ]; do - case ${1} in - -d ) - set -x - ;; - -p ) - fca=-nfca - ;; - -o ) - shift - outfile=${1} - mode=copy - ;; - -h ) - echo "$0 is a tool for generation of proper version files for the NuttX build" - echo "" - echo "USAGE:" - echo " $0 [-d] [-p] -o " - echo " $0 [-d] [-p] " - echo " $0 [-d] -h" - echo "" - echo "Where:" - echo " -" - echo " A single, unformatted input file" - echo " -" - echo " A list of unformatted input files that will be reformatted in place." - echo " -o " - echo " Write the single, reformatted to . " - echo " will not be modified." - echo " -d" - echo " Enable script debug" - echo " -p" - echo " Comments are pre-formatted. Do not reformat." - echo " -h" - echo " Show this help message and exit" - exit 0 - ;; - * ) - if [ ! -r ${1} ]; then - echo "Readable ${1} does not exist" - echo ${advice} - exit 1 - fi - if [ -z "${filelist}" ]; then - filelist="${1}" - files=single - else - filelist="${filelist} ${1}" - files=multiple - fi - ;; - esac - shift + case ${1} in + -d ) + set -x + ;; + -p ) + fca=-nfca + ;; + -o ) + shift + outfile=${1} + mode=copy + ;; + -h ) + echo "$0 is a tool for generation of proper version files for the NuttX build" + echo "" + echo "USAGE:" + echo " $0 [-d] [-p] -o " + echo " $0 [-d] [-p] " + echo " $0 [-d] -h" + echo "" + echo "Where:" + echo " -" + echo " A single, unformatted input file" + echo " -" + echo " A list of unformatted input files that will be reformatted in place." + echo " -o " + echo " Write the single, reformatted to . " + echo " will not be modified." + echo " -d" + echo " Enable script debug" + echo " -p" + echo " Comments are pre-formatted. Do not reformat." + echo " -h" + echo " Show this help message and exit" + exit 0 + ;; + * ) + if [ ! -r ${1} ]; then + echo "Readable ${1} does not exist" + echo ${advice} + exit 1 + fi + if [ -z "${filelist}" ]; then + filelist="${1}" + files=single + else + filelist="${filelist} ${1}" + files=multiple + fi + ;; + esac + shift done # Verify that at least one input file was provided if [ "X${files}" == "Xnone" ]; then - echo "ERROR: Neither nor provided" - echo ${advice} - exit 1 + echo "ERROR: Neither nor provided" + echo ${advice} + exit 1 fi # Options @@ -139,16 +139,16 @@ options="-nbad -bap -bbb -nbbo -nbc -bl -bl2 -bls -nbs -cbi2 -ncdw -nce -ci2 -cl # Perform the indentation if [ "X${mode}" == "Xcopy" ]; then - if [ "X${files}" == "Xmultiple" ]; then - echo "ERROR: Only a single can be used with the -o option" - echo ${advice} - exit 1 - fi - if [ -f $outfile ]; then - echo "Removing old $outfile" - rm $outfile || { echo "Failed to remove $outfile" ; exit 1 ; } - fi - indent $options $filelist -o $outfile + if [ "X${files}" == "Xmultiple" ]; then + echo "ERROR: Only a single can be used with the -o option" + echo ${advice} + exit 1 + fi + if [ -f $outfile ]; then + echo "Removing old $outfile" + rm $outfile || { echo "Failed to remove $outfile" ; exit 1 ; } + fi + indent $options $filelist -o $outfile else - indent $options $filelist + indent $options $filelist fi diff --git a/tools/kconfig.bat b/tools/kconfig.bat index db01e751510..b5b712d6f6b 100755 --- a/tools/kconfig.bat +++ b/tools/kconfig.bat @@ -118,14 +118,13 @@ echo ERROR: Missing required argument :ShowUsage echo USAGE: %0 ^ [-a ^] [-c ^] echo Where: -echo ^ is one of config, oldconf, or menuconfig -echo ^ is the relative path to the apps\ directory. -echo This defaults to ..\apps -echo ^ is the relative path to the Cygwin installation -echo directory. This defaults to C:\Cygwin +echo ^ is one of config, oldconf, or menuconfig +echo ^ is the relative path to the apps\ directory. +echo This defaults to ..\apps +echo ^ is the relative path to the Cygwin installation +echo directory. This defaults to C:\Cygwin rem Restore the original PATH settings :End set PATH=%oldpath% - diff --git a/tools/link.bat b/tools/link.bat index 21baa6c03ef..fbf9c5b33d3 100755 --- a/tools/link.bat +++ b/tools/link.bat @@ -35,7 +35,7 @@ rem set usemklink= if "%1"=="-m" ( -set usemklink="y" + set usemklink="y" shift ) @@ -84,7 +84,7 @@ rem Copy the directory :MkLink if "%usemklink%"=="y" ( -/user:administrator mklink /d %src% %link% + /user:administrator mklink /d %src% %link% goto :End ) @@ -95,7 +95,7 @@ goto :End :ShowUsage echo USAGE: %0 ^ ^ echo Where: -echo ^ is the source directory to be linked -echo ^ is the link to be created +echo ^ is the source directory to be linked +echo ^ is the link to be created :End diff --git a/tools/link.sh b/tools/link.sh index 0254ba159bc..496d19ed160 100755 --- a/tools/link.sh +++ b/tools/link.sh @@ -41,8 +41,8 @@ dest=$2 # Verify that arguments were provided if [ -z "${src}" -o -z "${dest}" ]; then - echo "Missing src and/or dest arguments" - exit 1 + echo "Missing src and/or dest arguments" + exit 1 fi # Check if something already exists at the destination path replace it with @@ -52,61 +52,60 @@ fi if [ -h "${dest}" ]; then - # If the link is already created (and matches the request) do nothing + # If the link is already created (and matches the request) do nothing - if [ "$(readlink ${dest})" = "${src}" ]; then - exit 0 - fi + if [ "$(readlink ${dest})" = "${src}" ]; then + exit 0 + fi - # Otherwise, remove the link + # Otherwise, remove the link - rm -f "${dest}" + rm -f "${dest}" else - # If the path exists and is a directory that contains the "fake link" - # mark, then treat it like a soft link (i.e., remove the directory) + # If the path exists and is a directory that contains the "fake link" + # mark, then treat it like a soft link (i.e., remove the directory) - if [ -d "${dest}" -a -f "${dest}/.fakelnk" ]; then - rm -rf "${dest}" - else + if [ -d "${dest}" -a -f "${dest}/.fakelnk" ]; then + rm -rf "${dest}" + else - # Does anything exist at the destination path? + # Does anything exist at the destination path? - if [ -e "${dest}" ]; then + if [ -e "${dest}" ]; then - # It is something else (like a file) or directory that does - # not contain the "fake link" mark + # It is something else (like a file) or directory that does + # not contain the "fake link" mark - echo "${dest} already exists but is not a symbolic link" - exit 1 - fi - fi + echo "${dest} already exists but is not a symbolic link" + exit 1 + fi + fi fi # Verify that a directory exists at the source path if [ ! -d "${src}" ]; then - echo "No directory at ${src}" - exit 1 + echo "No directory at ${src}" + exit 1 fi # Create the soft link ln -s "${src}" "${dest}" || \ - { echo "Failed to create link: $dest" ; exit 1 ; } + { echo "Failed to create link: $dest" ; exit 1 ; } # Verify that the link was created if [ ! -h ${dest} ]; then - # The MSYS 'ln' command actually does a directory copy + # The MSYS 'ln' command actually does a directory copy - if [ -d ${dest} ]; then - # Create the .fakelnk for unlink.sh + if [ -d ${dest} ]; then + # Create the .fakelnk for unlink.sh - touch ${dest}/.fakelnk - else - echo "Error: link at ${dest} not created." - exit 1 - fi + touch ${dest}/.fakelnk + else + echo "Error: link at ${dest} not created." + exit 1 + fi fi - diff --git a/tools/mkconfigvars.sh b/tools/mkconfigvars.sh index efcab4f27e0..4a5077a7c0f 100755 --- a/tools/mkconfigvars.sh +++ b/tools/mkconfigvars.sh @@ -38,37 +38,37 @@ ADVICE="Try '$0 -h' for more information" unset VERSION while [ ! -z "$1" ]; do - case $1 in - -v ) - shift - VERSION=$1 - ;; - -d ) - set -x - ;; - -h ) - echo "$0 is a tool for generation of configuration variable documentation" - echo "" - echo $USAGE - echo "" - echo "Where:" - echo " -v " - echo " The NuttX version number expressed as a major and minor number separated" - echo " by a period" - echo " -d" - echo " Enable script debug" - echo " -h" - echo " show this help message and exit" - exit 0 - ;; - * ) - echo "Unrecognized option: ${1}" - echo $USAGE - echo $ADVICE - exit 1 - ;; - esac + case $1 in + -v ) shift + VERSION=$1 + ;; + -d ) + set -x + ;; + -h ) + echo "$0 is a tool for generation of configuration variable documentation" + echo "" + echo $USAGE + echo "" + echo "Where:" + echo " -v " + echo " The NuttX version number expressed as a major and minor number separated" + echo " by a period" + echo " -d" + echo " Enable script debug" + echo " -h" + echo " show this help message and exit" + exit 0 + ;; + * ) + echo "Unrecognized option: ${1}" + echo $USAGE + echo $ADVICE + exit 1 + ;; + esac + shift done # Find the directory we were executed from and were we expect to @@ -84,12 +84,12 @@ HTMLFILE=Documentation/NuttXConfigVariables.html BKUPFILE=Documentation/NuttXConfigVariables.bkp if [ -x ./${MYNAME} ] ; then - cd .. || { echo "ERROR: cd .. failed" ; exit 1 ; } + cd .. || { echo "ERROR: cd .. failed" ; exit 1 ; } fi if [ ! -x tools/${MYNAME} ] ; then - echo "ERROR: This file must be executed from the top-level NuttX directory: $PWD" - exit 1 + echo "ERROR: This file must be executed from the top-level NuttX directory: $PWD" + exit 1 fi WD=${PWD} diff --git a/tools/mkctags.sh b/tools/mkctags.sh index 8a2977179e3..36bc6f9a0cc 100755 --- a/tools/mkctags.sh +++ b/tools/mkctags.sh @@ -35,7 +35,7 @@ WD=`pwd` if [[ "$WD" =~ "nuttx/tools" ]] then - cd .. + cd .. fi find .. -type f -iname "*.[chs]" -o -iname "*.cxx" -o -iname "*.hxx" | xargs ctags -a diff --git a/tools/mkexport.sh b/tools/mkexport.sh index d8992488a7e..1727b83c24a 100755 --- a/tools/mkexport.sh +++ b/tools/mkexport.sh @@ -45,97 +45,97 @@ WINTOOL=n LIBEXT=.a while [ ! -z "$1" ]; do - case $1 in - -a ) - shift - APPDIR="$1" - ;; - -d ) - set -x - ;; - -l ) - shift - LIBLIST=$1 - ;; - -m ) - shift - MAKE="$1" - ;; - -wy ) - WINTOOL=y - ;; - -w | -wn ) - WINTOOL=n - ;; - -t ) - shift - TOPDIR=$1 - ;; - -u ) - USRONLY=y - ;; - -x ) - shift - LIBEXT=$1 - ;; - -z ) - TGZ=y - ;; - -h ) - echo $USAGE - exit 0 - ;; - * ) - echo "Unrecognized argument: $1" - echo $USAGE - exit 1 - ;; - esac - shift + case $1 in + -a ) + shift + APPDIR="$1" + ;; + -d ) + set -x + ;; + -l ) + shift + LIBLIST=$1 + ;; + -m ) + shift + MAKE="$1" + ;; + -wy ) + WINTOOL=y + ;; + -w | -wn ) + WINTOOL=n + ;; + -t ) + shift + TOPDIR=$1 + ;; + -u ) + USRONLY=y + ;; + -x ) + shift + LIBEXT=$1 + ;; + -z ) + TGZ=y + ;; + -h ) + echo $USAGE + exit 0 + ;; + * ) + echo "Unrecognized argument: $1" + echo $USAGE + exit 1 + ;; + esac + shift done # Check arguments if [ -z "${TOPDIR}" -o -z "${LIBLIST}" ]; then - echo "MK: Missing required arguments" - echo $USAGE - exit 1 + echo "MK: Missing required arguments" + echo $USAGE + exit 1 fi if [ ! -d "${TOPDIR}" ]; then - echo "MK: Directory ${TOPDIR} does not exist" - exit 1 + echo "MK: Directory ${TOPDIR} does not exist" + exit 1 fi # Check configuration # Verify that we have Make.defs, .config, and .version files. if [ ! -f "${TOPDIR}/Make.defs" ]; then - echo "MK: Directory ${TOPDIR}/Make.defs does not exist" - exit 1 + echo "MK: Directory ${TOPDIR}/Make.defs does not exist" + exit 1 fi if [ ! -f "${TOPDIR}/.config" ]; then - echo "MK: Directory ${TOPDIR}/.config does not exist" - exit 1 + echo "MK: Directory ${TOPDIR}/.config does not exist" + exit 1 fi if [ ! -f "${TOPDIR}/.version" ]; then - echo "MK: File ${TOPDIR}/.version does not exist" - exit 1 + echo "MK: File ${TOPDIR}/.version does not exist" + exit 1 fi # Check if the make environment variable has been defined if [ -z "${MAKE}" ]; then - MAKE=`which make` + MAKE=`which make` fi # Get the version string source "${TOPDIR}/.version" if [ ! -z "${CONFIG_VERSION_STRING}" -a "${CONFIG_VERSION_STRING}" != "0.0" ]; then - VERSION="-${CONFIG_VERSION_STRING}" + VERSION="-${CONFIG_VERSION_STRING}" fi # Create the export directory @@ -146,8 +146,8 @@ EXPORTDIR="${TOPDIR}/${EXPORTSUBDIR}" # If the export directory already exists, then remove it and create a new one if [ -d "${EXPORTDIR}" ]; then - echo "MK: Removing old export directory" - rm -rf "${EXPORTDIR}" + echo "MK: Removing old export directory" + rm -rf "${EXPORTDIR}" fi # Remove any possible previous results @@ -187,8 +187,8 @@ rm -f "${EXPORTDIR}/Make.defs" # Verify the build info that we got from makeinfo.sh if [ ! -d "${ARCHDIR}" ]; then - echo "MK: Directory ${ARCHDIR} does not exist" - exit 1 + echo "MK: Directory ${ARCHDIR} does not exist" + exit 1 fi # Copy the default linker script @@ -198,27 +198,27 @@ cp -f "${TOPDIR}/binfmt/libelf/gnu-elf.ld" "${EXPORTDIR}/scripts/." # Is there a linker script in this configuration? if [ "X${USRONLY}" != "Xy" ]; then - if [ ! -z "${LDPATH}" ]; then + if [ ! -z "${LDPATH}" ]; then - # Apparently so. Verify that the script exists + # Apparently so. Verify that the script exists - if [ ! -f "${LDPATH}" ]; then - echo "MK: File ${LDPATH} does not exist" - exit 1 - fi + if [ ! -f "${LDPATH}" ]; then + echo "MK: File ${LDPATH} does not exist" + exit 1 + fi - # Copy the linker script + # Copy the linker script - cp -p "${LDPATH}" "${EXPORTDIR}/scripts/." || \ - { echo "MK: cp ${LDPATH} failed"; exit 1; } + cp -p "${LDPATH}" "${EXPORTDIR}/scripts/." || \ + { echo "MK: cp ${LDPATH} failed"; exit 1; } - # Copy addtional ld scripts + # Copy addtional ld scripts - LDDIR="$(dirname "${LDPATH}")" - for f in "${LDDIR}"/*.ld ; do - [ -f "${f}" ] && cp -f "${f}" "${EXPORTDIR}/scripts/." - done - fi + LDDIR="$(dirname "${LDPATH}")" + for f in "${LDDIR}"/*.ld ; do + [ -f "${f}" ] && cp -f "${f}" "${EXPORTDIR}/scripts/." + done + fi fi # Save the compilation options @@ -258,20 +258,20 @@ echo "LDSCRIPT = ${LDSCRIPT}" >>"${EXPORTDIR}/scripts/Make.defs" # Additional compilation options when the kernel is built if [ "X${USRONLY}" != "Xy" ]; then - echo "LDFLAGS = ${LDFLAGS}" >>"${EXPORTDIR}/scripts/Make.defs" - echo "HEAD_OBJ = ${HEAD_OBJ}" >>"${EXPORTDIR}/scripts/Make.defs" - echo "EXTRA_OBJS = ${EXTRA_OBJS}" >>"${EXPORTDIR}/scripts/Make.defs" - echo "LDSTARTGROUP = ${LDSTARTGROUP}" >>"${EXPORTDIR}/scripts/Make.defs" - echo "LDLIBS = ${LDLIBS}" >>"${EXPORTDIR}/scripts/Make.defs" - echo "EXTRA_LIBS = ${EXTRA_LIBS}" >>"${EXPORTDIR}/scripts/Make.defs" - echo "LIBGCC = ${LIBGCC}" >>"${EXPORTDIR}/scripts/Make.defs" - echo "LDENDGROUP = ${LDENDGROUP}" >>"${EXPORTDIR}/scripts/Make.defs" + echo "LDFLAGS = ${LDFLAGS}" >>"${EXPORTDIR}/scripts/Make.defs" + echo "HEAD_OBJ = ${HEAD_OBJ}" >>"${EXPORTDIR}/scripts/Make.defs" + echo "EXTRA_OBJS = ${EXTRA_OBJS}" >>"${EXPORTDIR}/scripts/Make.defs" + echo "LDSTARTGROUP = ${LDSTARTGROUP}" >>"${EXPORTDIR}/scripts/Make.defs" + echo "LDLIBS = ${LDLIBS}" >>"${EXPORTDIR}/scripts/Make.defs" + echo "EXTRA_LIBS = ${EXTRA_LIBS}" >>"${EXPORTDIR}/scripts/Make.defs" + echo "LIBGCC = ${LIBGCC}" >>"${EXPORTDIR}/scripts/Make.defs" + echo "LDENDGROUP = ${LDENDGROUP}" >>"${EXPORTDIR}/scripts/Make.defs" fi # Copy the system map file(s) if [ -r ${TOPDIR}/System.map ]; then - cp -a "${TOPDIR}/System.map" "${EXPORTDIR}/." + cp -a "${TOPDIR}/System.map" "${EXPORTDIR}/." fi if [ -r ${TOPDIR}/User.map ]; then @@ -281,7 +281,7 @@ fi # Copy the NuttX include directory (retaining attributes and following symbolic links) cp -LR -p "${TOPDIR}/include" "${EXPORTDIR}/." || \ - { echo "MK: 'cp ${TOPDIR}/include' failed"; exit 1; } + { echo "MK: 'cp ${TOPDIR}/include' failed"; exit 1; } # Copy the startup object file(s) @@ -303,112 +303,112 @@ cp -f "${ARCHDIR}"/*.h "${EXPORTDIR}"/arch/. 2>/dev/null # those directories into the EXPORTDIR if [ "X${USRONLY}" != "Xy" ]; then - ARCH_HDRDIRS="arm armv7-m avr avr32 board common chip mips32" - for hdir in $ARCH_HDRDIRS; do + ARCH_HDRDIRS="arm armv7-m avr avr32 board common chip mips32" + for hdir in $ARCH_HDRDIRS; do - # Does the directory (or symbolic link) exist? + # Does the directory (or symbolic link) exist? - if [ -d "${ARCHDIR}/${hdir}" -o -h "${ARCHDIR}/${hdir}" ]; then + if [ -d "${ARCHDIR}/${hdir}" -o -h "${ARCHDIR}/${hdir}" ]; then - # Yes.. create a export sub-directory of the same name + # Yes.. create a export sub-directory of the same name - mkdir "${EXPORTDIR}/arch/${hdir}" || \ - { echo "MK: 'mkdir ${EXPORTDIR}/arch/${hdir}' failed"; exit 1; } + mkdir "${EXPORTDIR}/arch/${hdir}" || \ + { echo "MK: 'mkdir ${EXPORTDIR}/arch/${hdir}' failed"; exit 1; } - # Then copy the header files (only) into the new directory + # Then copy the header files (only) into the new directory - cp -f "${ARCHDIR}"/${hdir}/*.h "${EXPORTDIR}"/arch/${hdir}/. 2>/dev/null + cp -f "${ARCHDIR}"/${hdir}/*.h "${EXPORTDIR}"/arch/${hdir}/. 2>/dev/null - # Most architectures have low directory called "hardware" that - # holds the header files + # Most architectures have low directory called "hardware" that + # holds the header files - if [ -d "${ARCHDIR}/${hdir}/hardware" ]; then + if [ -d "${ARCHDIR}/${hdir}/hardware" ]; then - # Yes.. create a export sub-directory of the same name + # Yes.. create a export sub-directory of the same name - mkdir "${EXPORTDIR}/arch/${hdir}/hardware" || \ - { echo "MK: 'mkdir ${EXPORTDIR}/arch/${hdir}/hardware' failed"; exit 1; } + mkdir "${EXPORTDIR}/arch/${hdir}/hardware" || \ + { echo "MK: 'mkdir ${EXPORTDIR}/arch/${hdir}/hardware' failed"; exit 1; } - # Then copy the header files (only) into the new directory + # Then copy the header files (only) into the new directory - cp -f "${ARCHDIR}"/${hdir}/hardware/*.h "${EXPORTDIR}"/arch/${hdir}/hardware/. 2>/dev/null - fi - fi - done + cp -f "${ARCHDIR}"/${hdir}/hardware/*.h "${EXPORTDIR}"/arch/${hdir}/hardware/. 2>/dev/null + fi + fi + done - # Copy OS internal header files as well. They are used by some architecture- - # specific header files. + # Copy OS internal header files as well. They are used by some architecture- + # specific header files. - mkdir "${EXPORTDIR}/arch/os" || \ - { echo "MK: 'mkdir ${EXPORTDIR}/arch/os' failed"; exit 1; } + mkdir "${EXPORTDIR}/arch/os" || \ + { echo "MK: 'mkdir ${EXPORTDIR}/arch/os' failed"; exit 1; } - OSDIRS="clock environ errno group init irq mqueue paging pthread sched semaphore signal task timer wdog" + OSDIRS="clock environ errno group init irq mqueue paging pthread sched semaphore signal task timer wdog" - for dir in ${OSDIRS}; do - mkdir "${EXPORTDIR}/arch/os/${dir}" || \ - { echo "MK: 'mkdir ${EXPORTDIR}/arch/os/${dir}' failed"; exit 1; } - cp -f "${TOPDIR}"/sched/${dir}/*.h "${EXPORTDIR}"/arch/os/${dir}/. 2>/dev/null - done + for dir in ${OSDIRS}; do + mkdir "${EXPORTDIR}/arch/os/${dir}" || \ + { echo "MK: 'mkdir ${EXPORTDIR}/arch/os/${dir}' failed"; exit 1; } + cp -f "${TOPDIR}"/sched/${dir}/*.h "${EXPORTDIR}"/arch/os/${dir}/. 2>/dev/null + done - # Add the board library to the list of libraries + # Add the board library to the list of libraries - if [ -f "${ARCHDIR}/board/libboard${LIBEXT}" ]; then - LIBLIST="${LIBLIST} ${ARCHSUBDIR}/board/libboard${LIBEXT}" - fi + if [ -f "${ARCHDIR}/board/libboard${LIBEXT}" ]; then + LIBLIST="${LIBLIST} ${ARCHSUBDIR}/board/libboard${LIBEXT}" + fi fi # Then process each library AR=${CROSSDEV}ar for lib in ${LIBLIST}; do - if [ ! -f "${TOPDIR}/${lib}" ]; then - echo "MK: Library ${TOPDIR}/${lib} does not exist" - exit 1 - fi - - # Get some shorter names for the library - - libname=`basename ${lib} ${LIBEXT}` - shortname=`echo ${libname} | sed -e "s/^lib//g"` - - # Copy the application library unmodified - - if [ "X${libname}" = "Xlibapps" ]; then - cp -p "${TOPDIR}/${lib}" "${EXPORTDIR}/libs/." || \ - { echo "MK: cp ${TOPDIR}/${lib} failed"; exit 1; } - else - - # Create a temporary directory and extract all of the objects there - # Hmmm.. this probably won't work if the archiver is not 'ar' - - mkdir "${EXPORTDIR}/tmp" || \ - { echo "MK: 'mkdir ${EXPORTDIR}/tmp' failed"; exit 1; } - cd "${EXPORTDIR}/tmp" || \ - { echo "MK: 'cd ${EXPORTDIR}/tmp' failed"; exit 1; } - if [ "X${WINTOOL}" = "Xy" ]; then - WLIB=`cygpath -w "${TOPDIR}/${lib}"` - ${AR} x "${WLIB}" - else - ${AR} x "${TOPDIR}/${lib}" - fi - - # Rename each object file (to avoid collision when they are combined) - # and add the file to libnuttx - - for file in `ls`; do - mv "${file}" "${shortname}-${file}" - if [ "X${WINTOOL}" = "Xy" ]; then - WLIB=`cygpath -w "${EXPORTDIR}/libs/libnuttx${LIBEXT}"` - ${AR} rcs "${WLIB}" "${shortname}-${file}" - else - ${AR} rcs "${EXPORTDIR}/libs/libnuttx${LIBEXT}" "${shortname}-${file}" - fi - done - - cd "${TOPDIR}" || \ - { echo "MK: 'cd ${TOPDIR}' failed"; exit 1; } - rm -rf "${EXPORTDIR}/tmp" - fi + if [ ! -f "${TOPDIR}/${lib}" ]; then + echo "MK: Library ${TOPDIR}/${lib} does not exist" + exit 1 + fi + + # Get some shorter names for the library + + libname=`basename ${lib} ${LIBEXT}` + shortname=`echo ${libname} | sed -e "s/^lib//g"` + + # Copy the application library unmodified + + if [ "X${libname}" = "Xlibapps" ]; then + cp -p "${TOPDIR}/${lib}" "${EXPORTDIR}/libs/." || \ + { echo "MK: cp ${TOPDIR}/${lib} failed"; exit 1; } + else + + # Create a temporary directory and extract all of the objects there + # Hmmm.. this probably won't work if the archiver is not 'ar' + + mkdir "${EXPORTDIR}/tmp" || \ + { echo "MK: 'mkdir ${EXPORTDIR}/tmp' failed"; exit 1; } + cd "${EXPORTDIR}/tmp" || \ + { echo "MK: 'cd ${EXPORTDIR}/tmp' failed"; exit 1; } + if [ "X${WINTOOL}" = "Xy" ]; then + WLIB=`cygpath -w "${TOPDIR}/${lib}"` + ${AR} x "${WLIB}" + else + ${AR} x "${TOPDIR}/${lib}" + fi + + # Rename each object file (to avoid collision when they are combined) + # and add the file to libnuttx + + for file in `ls`; do + mv "${file}" "${shortname}-${file}" + if [ "X${WINTOOL}" = "Xy" ]; then + WLIB=`cygpath -w "${EXPORTDIR}/libs/libnuttx${LIBEXT}"` + ${AR} rcs "${WLIB}" "${shortname}-${file}" + else + ${AR} rcs "${EXPORTDIR}/libs/libnuttx${LIBEXT}" "${shortname}-${file}" + fi + done + + cd "${TOPDIR}" || \ + { echo "MK: 'cd ${TOPDIR}' failed"; exit 1; } + rm -rf "${EXPORTDIR}/tmp" + fi done # Copy the essential build script file(s) @@ -427,18 +427,18 @@ cp -f "${TOPDIR}/tools/unlink.sh" "${EXPORTDIR}/tools/" # Now tar up the whole export directory cd "${TOPDIR}" || \ - { echo "MK: 'cd ${TOPDIR}' failed"; exit 1; } + { echo "MK: 'cd ${TOPDIR}' failed"; exit 1; } if [ -e "${APPDIR}/Makefile" ]; then - "${MAKE}" -C "${TOPDIR}/${APPDIR}" EXPORTDIR="$(cd "${EXPORTSUBDIR}" ; pwd )" TOPDIR="${TOPDIR}" export || \ - { echo "MK: call make export for APPDIR not supported"; } + "${MAKE}" -C "${TOPDIR}/${APPDIR}" EXPORTDIR="$(cd "${EXPORTSUBDIR}" ; pwd )" TOPDIR="${TOPDIR}" export || \ + { echo "MK: call make export for APPDIR not supported"; } fi if [ "X${TGZ}" = "Xy" ]; then - tar cvf "${EXPORTSUBDIR}.tar" "${EXPORTSUBDIR}" 1>/dev/null 2>&1 - gzip -f "${EXPORTSUBDIR}.tar" + tar cvf "${EXPORTSUBDIR}.tar" "${EXPORTSUBDIR}" 1>/dev/null 2>&1 + gzip -f "${EXPORTSUBDIR}.tar" else - zip -r "${EXPORTSUBDIR}.zip" "${EXPORTSUBDIR}" 1>/dev/null 2>&1 + zip -r "${EXPORTSUBDIR}.zip" "${EXPORTSUBDIR}" 1>/dev/null 2>&1 fi # Clean up after ourselves diff --git a/tools/mkromfsimg.sh b/tools/mkromfsimg.sh index 351490fad9e..54bb2b2c067 100755 --- a/tools/mkromfsimg.sh +++ b/tools/mkromfsimg.sh @@ -53,16 +53,16 @@ usage="USAGE: $0 [-nofat] " # Verify if we have the optional "-nofat" if [ "$nofat" == "-nofat" ]; then - echo "We will not mount a FAT/RAMDISK!" - usefat=false + echo "We will not mount a FAT/RAMDISK!" + usefat=false else - topdir=$1 + topdir=$1 fi if [ -z "$topdir" -o ! -d "$topdir" ]; then - echo "The full path to the NuttX base directory must be provided on the command line" - echo $usage - exit 1 + echo "The full path to the NuttX base directory must be provided on the command line" + echo $usage + exit 1 fi # Extract all values from the .config in the $topdir that contains all of the NuttX @@ -71,9 +71,9 @@ fi # to make that practical if [ ! -r $topdir/.config ]; then - echo "No readable file at $topdir/.config" - echo "Has NuttX been configured?" - exit 1 + echo "No readable file at $topdir/.config" + echo "Has NuttX been configured?" + exit 1 fi romfsetc=`grep CONFIG_NSH_ROMFSETC= $topdir/.config | cut -d'=' -f2` @@ -102,42 +102,42 @@ fi # Mountpoint support must be enabled if [ "X$disablempt" = "Xy" ]; then - echo "Mountpoint support is required for this feature" - echo "Set CONFIG_DISABLE_MOUNTPOINT=n to continue" - exit 1 + echo "Mountpoint support is required for this feature" + echo "Set CONFIG_DISABLE_MOUNTPOINT=n to continue" + exit 1 fi # Scripting support must be enabled if [ "X$disablescript" = "Xy" ]; then - echo "NSH scripting support is required for this feature" - echo "Set CONFIG_NSH_DISABLESCRIPT=n to continue" - exit 1 + echo "NSH scripting support is required for this feature" + echo "Set CONFIG_NSH_DISABLESCRIPT=n to continue" + exit 1 fi # We need at least 5 file descriptors: One for the ROMFS mount and one for # FAT mount performed in rcS, plus three for stdio. if [ -z "$ndescriptors" -o "$ndescriptors" -lt 5 ]; then - echo "Insufficient file descriptors have been allocated" - echo "Set CONFIG_NFILE_DESCRIPTORS to value greater than 4" - exit 1 + echo "Insufficient file descriptors have been allocated" + echo "Set CONFIG_NFILE_DESCRIPTORS to value greater than 4" + exit 1 fi # ROMFS support is required, of course if [ "X$romfs" != "Xy" ]; then - echo "ROMFS support is disabled in the NuttX configuration" - echo "Set CONFIG_FS_ROMFS=y to continue" - exit 0 + echo "ROMFS support is disabled in the NuttX configuration" + echo "Set CONFIG_FS_ROMFS=y to continue" + exit 0 fi # If it is the default rcS.template, then it also requires FAT FS support if [ "$usefat" = true -a "X$fatfs" != "Xy" ]; then - echo "FAT FS support is disabled in the NuttX configuration" - echo "Set CONFIG_FS_FAT=y to continue" - exit 0 + echo "FAT FS support is disabled in the NuttX configuration" + echo "Set CONFIG_FS_FAT=y to continue" + exit 0 fi # Verify that genromfs has been installed @@ -151,16 +151,16 @@ genromfs -h 1>/dev/null 2>&1 || { \ # Supply defaults for all un-defined ROMFS settings if [ -z "$romfsmpt" ]; then - romfsmpt="/etc" + romfsmpt="/etc" fi if [ -z "$initscript" ]; then - initscript="init.d/rcS" + initscript="init.d/rcS" fi if [ -z "$romfsdevno" ]; then - romfsdevno=0 + romfsdevno=0 fi if [ -z "$romfssectsize" ]; then - romfssectsize=64 + romfssectsize=64 fi # If FAT FS is a requirement @@ -170,16 +170,16 @@ if [ "$usefat" = true ]; then # Supply defaults for all un-defined FAT FS settings if [ -z "$fatdevno" ]; then - fatdevno=1 + fatdevno=1 fi if [ -z "$fatsectsize" ]; then - fatsectsize=512 + fatsectsize=512 fi if [ -z "$fatnsectors" ]; then - fatnsectors=1024 + fatnsectors=1024 fi if [ -z "$fatmpt" ]; then - fatmpt="/tmp" + fatmpt="/tmp" fi fi @@ -187,50 +187,50 @@ fi # /., /./*, /.., or /../* if [ ${romfsmpt:0:1} != "\"" ]; then - echo "CONFIG_NSH_ROMFSMOUNTPT must be a string" - echo "Change it so that it is enclosed in quotes." - exit 1 + echo "CONFIG_NSH_ROMFSMOUNTPT must be a string" + echo "Change it so that it is enclosed in quotes." + exit 1 fi uromfsmpt=`echo $romfsmpt | sed -e "s/\"//g"` if [ ${uromfsmpt:0:1} != "/" ]; then - echo "CONFIG_NSH_ROMFSMOUNTPT must be an absolute path in the target FS" - echo "Change it so that it begins with the character '/'. Eg. /etc" - exit 1 + echo "CONFIG_NSH_ROMFSMOUNTPT must be an absolute path in the target FS" + echo "Change it so that it begins with the character '/'. Eg. /etc" + exit 1 fi tmpdir=$uromfsmpt while [ ${tmpdir:0:1} == "/" ]; do - tmpdir=${tmpdir:1} + tmpdir=${tmpdir:1} done if [ -z "$tmpdir" -o "X$tmpdir" = "Xdev" -o "X$tmpdir" = "." -o \ ${tmpdir:0:2} = "./" -o "X$tmpdir" = ".." -o ${tmpdir:0:3} = "../" ]; then - echo "Invalid CONFIG_NSH_ROMFSMOUNTPT selection." - exit 1 + echo "Invalid CONFIG_NSH_ROMFSMOUNTPT selection." + exit 1 fi # Verify that the path to the init file is a relative path and not ., ./*, .., or ../* if [ ${initscript:0:1} != "\"" ]; then - echo "CONFIG_NSH_INITSCRIPT must be a string" - echo "Change it so that it is enclosed in quotes." - exit 1 + echo "CONFIG_NSH_INITSCRIPT must be a string" + echo "Change it so that it is enclosed in quotes." + exit 1 fi uinitscript=`echo $initscript | sed -e "s/\"//g"` if [ ${uinitscript:0:1} == "/" ]; then - echo "CONFIG_NSH_INITSCRIPT must be an relative path in under $romfsmpt" - echo "Change it so that it begins with the character '/'. Eg. init.d/rcS. " - exit 1 + echo "CONFIG_NSH_INITSCRIPT must be an relative path in under $romfsmpt" + echo "Change it so that it begins with the character '/'. Eg. init.d/rcS. " + exit 1 fi if [ "X$uinitscript" = "." -o ${uinitscript:0:2} = "./" -o \ "X$uinitscript" = ".." -o ${uinitscript:0:3} = "../" ]; then - echo "Invalid CONFIG_NSH_INITSCRIPT selection. Must not begin with . or .." - exit 1 + echo "Invalid CONFIG_NSH_INITSCRIPT selection. Must not begin with . or .." + exit 1 fi # Create a working directory @@ -241,9 +241,9 @@ mkdir -p $workingdir || { echo "Failed to created the new $workingdir"; exit 1; # Create the rcS file from the rcS.template if [ ! -r $rcstemplate ]; then - echo "$rcstemplate does not exist" - rmdir $workingdir - exit 1 + echo "$rcstemplate does not exist" + rmdir $workingdir + exit 1 fi # If we are using FAT FS with RAMDISK we need to setup it diff --git a/tools/refresh.sh b/tools/refresh.sh index 9bff24990d8..3e7c7af2c73 100755 --- a/tools/refresh.sh +++ b/tools/refresh.sh @@ -44,51 +44,51 @@ defaults=n prompt=y while [ ! -z "$1" ]; do - case $1 in - --debug ) - set -x - ;; - --silent ) - silent=y - defaults=y - prompt=n - ;; - --prompt ) - prompt=y - ;; - --defaults ) - defaults=y - ;; - --help ) - echo "$0 is a tool for refreshing board configurations" - echo "" - echo $USAGE - echo "" - echo "Where [options] include:" - echo " --debug" - echo " Enable script debug" - echo " --silent" - echo " Update board configuration without interaction. Implies --defaults." - echo " Assumes no prompt for save. Use --silent --prompt to prompt before saving." - echo " --prompt" - echo " Prompt before updating and overwriting the defconfig file. Default is to" - echo " prompt unless --silent" - echo " --defaults" - echo " Do not prompt for new default selections; accept all recommended default values" - echo " --help" - echo " Show this help message and exit" - echo " " - echo " The board directory under nuttx/boards" - echo " " - echo " The board configuration directory under nuttx/boards//configs" - exit 0 - ;; - * ) - CONFIG=$1 - break - ;; - esac - shift + case $1 in + --debug ) + set -x + ;; + --silent ) + silent=y + defaults=y + prompt=n + ;; + --prompt ) + prompt=y + ;; + --defaults ) + defaults=y + ;; + --help ) + echo "$0 is a tool for refreshing board configurations" + echo "" + echo $USAGE + echo "" + echo "Where [options] include:" + echo " --debug" + echo " Enable script debug" + echo " --silent" + echo " Update board configuration without interaction. Implies --defaults." + echo " Assumes no prompt for save. Use --silent --prompt to prompt before saving." + echo " --prompt" + echo " Prompt before updating and overwriting the defconfig file. Default is to" + echo " prompt unless --silent" + echo " --defaults" + echo " Do not prompt for new default selections; accept all recommended default values" + echo " --help" + echo " Show this help message and exit" + echo " " + echo " The board directory under nuttx/boards" + echo " " + echo " The board configuration directory under nuttx/boards//configs" + exit 0 + ;; + * ) + CONFIG=$1 + break + ;; + esac + shift done # Get the board configuration @@ -153,12 +153,12 @@ fi MYNAME=`basename $0` if [ -x ./${MYNAME} ] ; then - cd .. || { echo "ERROR: cd .. failed" ; exit 1 ; } + cd .. || { echo "ERROR: cd .. failed" ; exit 1 ; } fi if [ ! -x tools/${MYNAME} ] ; then - echo "ERROR: This file must be executed from the top-level NuttX directory: $PWD" - exit 1 + echo "ERROR: This file must be executed from the top-level NuttX directory: $PWD" + exit 1 fi # Set up the environment diff --git a/tools/sethost.sh b/tools/sethost.sh index 37e80729d67..a9187c9cb3e 100755 --- a/tools/sethost.sh +++ b/tools/sethost.sh @@ -41,70 +41,70 @@ hsize=64 unset configfile function showusage { - echo "" - echo "USAGE: $progname [-w|l|m] [-c|u|g|n] [-32|64] []" - echo " $progname -h" - echo "" - echo "Where:" - echo " -w|l|m selects Windows (w), Linux (l), or macOS (m). Default: Linux" - echo " -c|u|g|n selects Windows environment option: Cygwin (c), Ubuntu under" - echo " Windows 10 (u), MSYS/MSYS2 (g) or Windows native (n). Default Cygwin" - echo " -32|64 selects 32- or 64-bit host. Default 64" - echo " -h will show this help test and terminate" - echo " selects configuration file. Default: .config" - exit 1 + echo "" + echo "USAGE: $progname [-w|l|m] [-c|u|g|n] [-32|64] []" + echo " $progname -h" + echo "" + echo "Where:" + echo " -w|l|m selects Windows (w), Linux (l), or macOS (m). Default: Linux" + echo " -c|u|g|n selects Windows environment option: Cygwin (c), Ubuntu under" + echo " Windows 10 (u), MSYS/MSYS2 (g) or Windows native (n). Default Cygwin" + echo " -32|64 selects 32- or 64-bit host. Default 64" + echo " -h will show this help test and terminate" + echo " selects configuration file. Default: .config" + exit 1 } # Parse command line while [ ! -z "$1" ]; do - case $1 in - -w ) - host=windows - ;; - -l ) - host=linux - ;; - -c ) - host=windows - wenv=cygwin - ;; - -g ) - host=windows - wenv=msys - ;; - -u ) - host=windows - wenv=ubuntu - ;; - -m ) - host=macos - ;; - -n ) - host=windows - wenv=native - ;; - -32 ) - hsize=32 - ;; - -64 ) - hsize=32 - ;; - -h ) - showusage - ;; - * ) - configfile="$1" - shift - break; - ;; + case $1 in + -w ) + host=windows + ;; + -l ) + host=linux + ;; + -c ) + host=windows + wenv=cygwin + ;; + -g ) + host=windows + wenv=msys + ;; + -u ) + host=windows + wenv=ubuntu + ;; + -m ) + host=macos + ;; + -n ) + host=windows + wenv=native + ;; + -32 ) + hsize=32 + ;; + -64 ) + hsize=32 + ;; + -h ) + showusage + ;; + * ) + configfile="$1" + shift + break; + ;; esac shift done if [ ! -z "$1" ]; then - echo "ERROR: Garbage at the end of line" - showusage + echo "ERROR: Garbage at the end of line" + showusage fi if [ -x sethost.sh ]; then @@ -178,82 +178,82 @@ fi if [ "X$host" == "Xlinux" -o "X$host" == "Xmacos" ]; then - # Enable Linux or macOS + # Enable Linux or macOS - if [ "X$host" == "Xlinux" ]; then - echo " Select CONFIG_HOST_LINUX=y" + if [ "X$host" == "Xlinux" ]; then + echo " Select CONFIG_HOST_LINUX=y" - kconfig-tweak --file $nuttx/.config --enable CONFIG_HOST_LINUX - kconfig-tweak --file $nuttx/.config --disable CONFIG_HOST_MACOS - else - echo " Select CONFIG_HOST_MACOS=y" + kconfig-tweak --file $nuttx/.config --enable CONFIG_HOST_LINUX + kconfig-tweak --file $nuttx/.config --disable CONFIG_HOST_MACOS + else + echo " Select CONFIG_HOST_MACOS=y" - kconfig-tweak --file $nuttx/.config --disable CONFIG_HOST_LINUX - kconfig-tweak --file $nuttx/.config --enable CONFIG_HOST_MACOS - fi + kconfig-tweak --file $nuttx/.config --disable CONFIG_HOST_LINUX + kconfig-tweak --file $nuttx/.config --enable CONFIG_HOST_MACOS + fi - # Disable all Windows options + # Disable all Windows options - kconfig-tweak --file $nuttx/.config --disable CONFIG_HOST_WINDOWS - kconfig-tweak --file $nuttx/.config --disable CONFIG_SIM_X8664_MICROSOFT - kconfig-tweak --file $nuttx/.config --enable CONFIG_SIM_X8664_SYSTEMV + kconfig-tweak --file $nuttx/.config --disable CONFIG_HOST_WINDOWS + kconfig-tweak --file $nuttx/.config --disable CONFIG_SIM_X8664_MICROSOFT + kconfig-tweak --file $nuttx/.config --enable CONFIG_SIM_X8664_SYSTEMV - kconfig-tweak --file $nuttx/.config --disable CONFIG_WINDOWS_NATIVE - kconfig-tweak --file $nuttx/.config --disable CONFIG_WINDOWS_CYGWIN - kconfig-tweak --file $nuttx/.config --disable CONFIG_WINDOWS_UBUNTU - kconfig-tweak --file $nuttx/.config --disable CONFIG_WINDOWS_MSYS - kconfig-tweak --file $nuttx/.config --disable CONFIG_WINDOWS_OTHER + kconfig-tweak --file $nuttx/.config --disable CONFIG_WINDOWS_NATIVE + kconfig-tweak --file $nuttx/.config --disable CONFIG_WINDOWS_CYGWIN + kconfig-tweak --file $nuttx/.config --disable CONFIG_WINDOWS_UBUNTU + kconfig-tweak --file $nuttx/.config --disable CONFIG_WINDOWS_MSYS + kconfig-tweak --file $nuttx/.config --disable CONFIG_WINDOWS_OTHER - kconfig-tweak --file $nuttx/.config --enable CONFIG_SIM_X8664_SYSTEMV - kconfig-tweak --file $nuttx/.config --disable CONFIG_SIM_X8664_MICROSOFT - kconfig-tweak --file $nuttx/.config --disable CONFIG_SIM_M32 + kconfig-tweak --file $nuttx/.config --enable CONFIG_SIM_X8664_SYSTEMV + kconfig-tweak --file $nuttx/.config --disable CONFIG_SIM_X8664_MICROSOFT + kconfig-tweak --file $nuttx/.config --disable CONFIG_SIM_M32 else - echo " Select CONFIG_HOST_WINDOWS=y" + echo " Select CONFIG_HOST_WINDOWS=y" - # Enable Windows + # Enable Windows - kconfig-tweak --file $nuttx/.config --enable CONFIG_HOST_WINDOWS - kconfig-tweak --file $nuttx/.config --disable CONFIG_HOST_LINUX - kconfig-tweak --file $nuttx/.config --disable CONFIG_HOST_MACOS + kconfig-tweak --file $nuttx/.config --enable CONFIG_HOST_WINDOWS + kconfig-tweak --file $nuttx/.config --disable CONFIG_HOST_LINUX + kconfig-tweak --file $nuttx/.config --disable CONFIG_HOST_MACOS - kconfig-tweak --file $nuttx/.config --enable CONFIG_SIM_X8664_MICROSOFT - kconfig-tweak --file $nuttx/.config --disable CONFIG_SIM_X8664_SYSTEMV + kconfig-tweak --file $nuttx/.config --enable CONFIG_SIM_X8664_MICROSOFT + kconfig-tweak --file $nuttx/.config --disable CONFIG_SIM_X8664_SYSTEMV - # Enable Windows environment + # Enable Windows environment - kconfig-tweak --file $nuttx/.config --disable CONFIG_WINDOWS_OTHER - if [ "X$wenv" == "Xcygwin" ]; then - echo " Select CONFIG_WINDOWS_CYGWIN=y" - kconfig-tweak --file $nuttx/.config --enable CONFIG_WINDOWS_CYGWIN - kconfig-tweak --file $nuttx/.config --disable CONFIG_WINDOWS_MSYS + kconfig-tweak --file $nuttx/.config --disable CONFIG_WINDOWS_OTHER + if [ "X$wenv" == "Xcygwin" ]; then + echo " Select CONFIG_WINDOWS_CYGWIN=y" + kconfig-tweak --file $nuttx/.config --enable CONFIG_WINDOWS_CYGWIN + kconfig-tweak --file $nuttx/.config --disable CONFIG_WINDOWS_MSYS + kconfig-tweak --file $nuttx/.config --disable CONFIG_WINDOWS_UBUNTU + kconfig-tweak --file $nuttx/.config --disable CONFIG_WINDOWS_NATIVE + else + kconfig-tweak --file $nuttx/.config --disable CONFIG_WINDOWS_CYGWIN + if [ "X$wenv" == "Xmsys" ]; then + echo " Select CONFIG_WINDOWS_MSYS=y" + kconfig-tweak --file $nuttx/.config --enable CONFIG_WINDOWS_MSYS kconfig-tweak --file $nuttx/.config --disable CONFIG_WINDOWS_UBUNTU kconfig-tweak --file $nuttx/.config --disable CONFIG_WINDOWS_NATIVE else - kconfig-tweak --file $nuttx/.config --disable CONFIG_WINDOWS_CYGWIN - if [ "X$wenv" == "Xmsys" ]; then - echo " Select CONFIG_WINDOWS_MSYS=y" - kconfig-tweak --file $nuttx/.config --enable CONFIG_WINDOWS_MSYS - kconfig-tweak --file $nuttx/.config --disable CONFIG_WINDOWS_UBUNTU + kconfig-tweak --file $nuttx/.config --disable CONFIG_WINDOWS_MSYS + if [ "X$wenv" == "Xubuntu" ]; then + echo " Select CONFIG_WINDOWS_UBUNTU=y" + kconfig-tweak --file $nuttx/.config --enable CONFIG_WINDOWS_UBUNTU kconfig-tweak --file $nuttx/.config --disable CONFIG_WINDOWS_NATIVE else - kconfig-tweak --file $nuttx/.config --disable CONFIG_WINDOWS_MSYS - if [ "X$wenv" == "Xubuntu" ]; then - echo " Select CONFIG_WINDOWS_UBUNTU=y" - kconfig-tweak --file $nuttx/.config --enable CONFIG_WINDOWS_UBUNTU - kconfig-tweak --file $nuttx/.config --disable CONFIG_WINDOWS_NATIVE - else - echo " Select CONFIG_WINDOWS_NATIVE=y" - kconfig-tweak --file $nuttx/.config --disable CONFIG_WINDOWS_UBUNTU - kconfig-tweak --file $nuttx/.config --enable CONFIG_WINDOWS_NATIVE - fi + echo " Select CONFIG_WINDOWS_NATIVE=y" + kconfig-tweak --file $nuttx/.config --disable CONFIG_WINDOWS_UBUNTU + kconfig-tweak --file $nuttx/.config --enable CONFIG_WINDOWS_NATIVE fi fi + fi - if [ "X$hsize" == "X32" ]; then - kconfig-tweak --file $nuttx/.config --enable CONFIG_SIM_M32 - else - kconfig-tweak --file $nuttx/.config --disable CONFIG_SIM_M32 - fi + if [ "X$hsize" == "X32" ]; then + kconfig-tweak --file $nuttx/.config --enable CONFIG_SIM_M32 + else + kconfig-tweak --file $nuttx/.config --disable CONFIG_SIM_M32 + fi fi kconfig-tweak --file $nuttx/.config --disable CONFIG_HOST_MACOS diff --git a/tools/testbuild.sh b/tools/testbuild.sh index 3ddfc56eb59..3925fdffdc7 100755 --- a/tools/testbuild.sh +++ b/tools/testbuild.sh @@ -48,78 +48,78 @@ unset testfile unset JOPTION function showusage { - echo "" - echo "USAGE: $progname [-w|l] [-c|u|n] [-s] [-d] [-x] [-j ] [-a ] [-t " - echo " $progname -h" - echo "" - echo "Where:" - echo " -w|l selects Windows (w) or Linux (l). Default: Linux" - echo " -c|u|n selects Windows environment option: Cygwin (c), Ubuntu under" - echo " Windows 10 (u), or Windows native (n). Default Cygwin" - echo " -s Use C++ unsigned long size_t in new operator. Default unsigned int" - echo " -d enables script debug output" - echo " -x exit on build failures" - echo " -j passed on to make. Default: No -j make option." - echo " -a provides the relative path to the apps/ directory. Default ../apps" - echo " -t provides the absolute path to top nuttx/ directory. Default $PWD/../nuttx" - echo " -h will show this help test and terminate" - echo " selects the list of configurations to test. No default" - echo "" - echo "Your PATH variable must include the path to both the build tools and the" - echo "kconfig-frontends tools" - echo "" - exit 1 + echo "" + echo "USAGE: $progname [-w|l] [-c|u|n] [-s] [-d] [-x] [-j ] [-a ] [-t " + echo " $progname -h" + echo "" + echo "Where:" + echo " -w|l selects Windows (w) or Linux (l). Default: Linux" + echo " -c|u|n selects Windows environment option: Cygwin (c), Ubuntu under" + echo " Windows 10 (u), or Windows native (n). Default Cygwin" + echo " -s Use C++ unsigned long size_t in new operator. Default unsigned int" + echo " -d enables script debug output" + echo " -x exit on build failures" + echo " -j passed on to make. Default: No -j make option." + echo " -a provides the relative path to the apps/ directory. Default ../apps" + echo " -t provides the absolute path to top nuttx/ directory. Default $PWD/../nuttx" + echo " -h will show this help test and terminate" + echo " selects the list of configurations to test. No default" + echo "" + echo "Your PATH variable must include the path to both the build tools and the" + echo "kconfig-frontends tools" + echo "" + exit 1 } # Parse command line while [ ! -z "$1" ]; do - case $1 in - -w ) + case $1 in + -w ) host=windows ;; - -l ) + -l ) host=linux ;; - -c ) + -c ) host=windows wenv=cygwin ;; - -d ) + -d ) set -x ;; - -u ) + -u ) host=windows wenv=ubuntu ;; - -n ) + -n ) host=windows wenv=native ;; - -s ) + -s ) host=windows sizet=long ;; - -x ) + -x ) MAKE_FLAGS='--silent --no-print-directory' set -e ;; - -a ) + -a ) shift APPSDIR="$1" ;; - -j ) + -j ) shift JOPTION="-j $1" ;; - -t ) + -t ) shift nuttx="$1" ;; - -h ) + -h ) showusage ;; - * ) + * ) testfile="$1" shift break; @@ -129,133 +129,133 @@ while [ ! -z "$1" ]; do done if [ ! -z "$1" ]; then - echo "ERROR: Garbage at the end of line" - showusage + echo "ERROR: Garbage at the end of line" + showusage fi if [ -z "$testfile" ]; then - echo "ERROR: Missing test list file" - showusage + echo "ERROR: Missing test list file" + showusage fi if [ ! -r "$testfile" ]; then - echo "ERROR: No readable file exists at $testfile" - showusage + echo "ERROR: No readable file exists at $testfile" + showusage fi if [ ! -d "$nuttx" ]; then - echo "ERROR: Expected to find nuttx/ at $nuttx" - showusage + echo "ERROR: Expected to find nuttx/ at $nuttx" + showusage fi # Clean up after the last build function distclean { - cd $nuttx || { echo "ERROR: failed to CD to $nuttx"; exit 1; } - if [ -f .config ]; then - echo " Cleaning..." - ${MAKE} ${JOPTION} ${MAKE_FLAGS} distclean 1>/dev/null - fi + cd $nuttx || { echo "ERROR: failed to CD to $nuttx"; exit 1; } + if [ -f .config ]; then + echo " Cleaning..." + ${MAKE} ${JOPTION} ${MAKE_FLAGS} distclean 1>/dev/null + fi } # Configure for the next build function configure { - cd $nuttx/tools || { echo "ERROR: failed to CD to $nuttx/tools"; exit 1; } - echo " Configuring..." - ./configure.sh $config - - cd $nuttx || { echo "ERROR: failed to CD to $nuttx"; exit 1; } - - if [ "X$host" == "Xlinux" ]; then - echo " Select CONFIG_HOST_LINUX=y" - - kconfig-tweak --file $nuttx/.config --enable CONFIG_HOST_LINUX - kconfig-tweak --file $nuttx/.config --disable CONFIG_HOST_WINDOWS - - kconfig-tweak --file $nuttx/.config --disable CONFIG_WINDOWS_NATIVE - kconfig-tweak --file $nuttx/.config --disable CONFIG_WINDOWS_CYGWIN - kconfig-tweak --file $nuttx/.config --disable CONFIG_WINDOWS_MSYS - kconfig-tweak --file $nuttx/.config --disable CONFIG_WINDOWS_OTHER - - kconfig-tweak --file $nuttx/.config --enable CONFIG_SIM_X8664_SYSTEMV - kconfig-tweak --file $nuttx/.config --disable CONFIG_SIM_X8664_MICROSOFT - kconfig-tweak --file $nuttx/.config --disable CONFIG_SIM_M32 + cd $nuttx/tools || { echo "ERROR: failed to CD to $nuttx/tools"; exit 1; } + echo " Configuring..." + ./configure.sh $config + + cd $nuttx || { echo "ERROR: failed to CD to $nuttx"; exit 1; } + + if [ "X$host" == "Xlinux" ]; then + echo " Select CONFIG_HOST_LINUX=y" + + kconfig-tweak --file $nuttx/.config --enable CONFIG_HOST_LINUX + kconfig-tweak --file $nuttx/.config --disable CONFIG_HOST_WINDOWS + + kconfig-tweak --file $nuttx/.config --disable CONFIG_WINDOWS_NATIVE + kconfig-tweak --file $nuttx/.config --disable CONFIG_WINDOWS_CYGWIN + kconfig-tweak --file $nuttx/.config --disable CONFIG_WINDOWS_MSYS + kconfig-tweak --file $nuttx/.config --disable CONFIG_WINDOWS_OTHER + + kconfig-tweak --file $nuttx/.config --enable CONFIG_SIM_X8664_SYSTEMV + kconfig-tweak --file $nuttx/.config --disable CONFIG_SIM_X8664_MICROSOFT + kconfig-tweak --file $nuttx/.config --disable CONFIG_SIM_M32 + else + echo " Select CONFIG_HOST_WINDOWS=y" + kconfig-tweak --file $nuttx/.config --enable CONFIG_HOST_WINDOWS + kconfig-tweak --file $nuttx/.config --disable CONFIG_HOST_LINUX + + if [ "X$wenv" == "Xcygwin" ]; then + echo " Select CONFIG_WINDOWS_CYGWIN=y" + kconfig-tweak --file $nuttx/.config --enable CONFIG_WINDOWS_CYGWIN + kconfig-tweak --file $nuttx/.config --disable CONFIG_WINDOWS_UBUNTU + kconfig-tweak --file $nuttx/.config --disable CONFIG_WINDOWS_NATIVE else - echo " Select CONFIG_HOST_WINDOWS=y" - kconfig-tweak --file $nuttx/.config --enable CONFIG_HOST_WINDOWS - kconfig-tweak --file $nuttx/.config --disable CONFIG_HOST_LINUX - - if [ "X$wenv" == "Xcygwin" ]; then - echo " Select CONFIG_WINDOWS_CYGWIN=y" - kconfig-tweak --file $nuttx/.config --enable CONFIG_WINDOWS_CYGWIN - kconfig-tweak --file $nuttx/.config --disable CONFIG_WINDOWS_UBUNTU - kconfig-tweak --file $nuttx/.config --disable CONFIG_WINDOWS_NATIVE - else - kconfig-tweak --file $nuttx/.config --disable CONFIG_WINDOWS_CYGWIN - if [ "X$wenv" == "Xubuntu" ]; then - echo " Select CONFIG_WINDOWS_UBUNTU=y" - kconfig-tweak --file $nuttx/.config --enable CONFIG_WINDOWS_UBUNTU - kconfig-tweak --file $nuttx/.config --disable CONFIG_WINDOWS_NATIVE - else - echo " Select CONFIG_WINDOWS_NATIVE=y" - kconfig-tweak --file $nuttx/.config --disable CONFIG_WINDOWS_UBUNTU - kconfig-tweak --file $nuttx/.config --enable CONFIG_WINDOWS_NATIVE - fi - fi - - kconfig-tweak --file $nuttx/.config --disable CONFIG_WINDOWS_MSYS - kconfig-tweak --file $nuttx/.config --disable CONFIG_WINDOWS_OTHER - - kconfig-tweak --file $nuttx/.config --enable CONFIG_SIM_X8664_MICROSOFT - kconfig-tweak --file $nuttx/.config --disable CONFIG_SIM_X8664_SYSTEMV - kconfig-tweak --file $nuttx/.config --disable CONFIG_SIM_M32 + kconfig-tweak --file $nuttx/.config --disable CONFIG_WINDOWS_CYGWIN + if [ "X$wenv" == "Xubuntu" ]; then + echo " Select CONFIG_WINDOWS_UBUNTU=y" + kconfig-tweak --file $nuttx/.config --enable CONFIG_WINDOWS_UBUNTU + kconfig-tweak --file $nuttx/.config --disable CONFIG_WINDOWS_NATIVE + else + echo " Select CONFIG_WINDOWS_NATIVE=y" + kconfig-tweak --file $nuttx/.config --disable CONFIG_WINDOWS_UBUNTU + kconfig-tweak --file $nuttx/.config --enable CONFIG_WINDOWS_NATIVE + fi fi - kconfig-tweak --file $nuttx/.config --disable CONFIG_HOST_MACOS - kconfig-tweak --file $nuttx/.config --disable CONFIG_HOST_OTHER - - if [ "X$sizet" == "Xlong" ]; then - echo " Select CONFIG_CXX_NEWLONG=y" - kconfig-tweak --file $nuttx/.config --enable CONFIG_CXX_NEWLONG - else - echo " Disable CONFIG_CXX_NEWLONG" - kconfig-tweak --file $nuttx/.config --disable CONFIG_CXX_NEWLONG + kconfig-tweak --file $nuttx/.config --disable CONFIG_WINDOWS_MSYS + kconfig-tweak --file $nuttx/.config --disable CONFIG_WINDOWS_OTHER + + kconfig-tweak --file $nuttx/.config --enable CONFIG_SIM_X8664_MICROSOFT + kconfig-tweak --file $nuttx/.config --disable CONFIG_SIM_X8664_SYSTEMV + kconfig-tweak --file $nuttx/.config --disable CONFIG_SIM_M32 + fi + + kconfig-tweak --file $nuttx/.config --disable CONFIG_HOST_MACOS + kconfig-tweak --file $nuttx/.config --disable CONFIG_HOST_OTHER + + if [ "X$sizet" == "Xlong" ]; then + echo " Select CONFIG_CXX_NEWLONG=y" + kconfig-tweak --file $nuttx/.config --enable CONFIG_CXX_NEWLONG + else + echo " Disable CONFIG_CXX_NEWLONG" + kconfig-tweak --file $nuttx/.config --disable CONFIG_CXX_NEWLONG + fi + + if [ "X$toolchain" != "X" ]; then + setting=`grep TOOLCHAIN $nuttx/.config | grep -v CONFIG_ARCH_TOOLCHAIN_GNU=y | grep =y` + varname=`echo $setting | cut -d'=' -f1` + if [ ! -z "$varname" ]; then + echo " Disabling $varname" + kconfig-tweak --file $nuttx/.config --disable $varname fi - if [ "X$toolchain" != "X" ]; then - setting=`grep TOOLCHAIN $nuttx/.config | grep -v CONFIG_ARCH_TOOLCHAIN_GNU=y | grep =y` - varname=`echo $setting | cut -d'=' -f1` - if [ ! -z "$varname" ]; then - echo " Disabling $varname" - kconfig-tweak --file $nuttx/.config --disable $varname - fi - - echo " Enabling $toolchain" - kconfig-tweak --file $nuttx/.config --enable $toolchain - fi + echo " Enabling $toolchain" + kconfig-tweak --file $nuttx/.config --enable $toolchain + fi - echo " Refreshing..." - cd $nuttx || { echo "ERROR: failed to CD to $nuttx"; exit 1; } - ${MAKE} ${MAKE_FLAGS} olddefconfig 1>/dev/null 2>&1 + echo " Refreshing..." + cd $nuttx || { echo "ERROR: failed to CD to $nuttx"; exit 1; } + ${MAKE} ${MAKE_FLAGS} olddefconfig 1>/dev/null 2>&1 } # Perform the next build function build { - cd $nuttx || { echo "ERROR: failed to CD to $nuttx"; exit 1; } - echo " Building NuttX..." - echo "------------------------------------------------------------------------------------" - ${MAKE} ${JOPTION} ${MAKE_FLAGS} 1>/dev/null + cd $nuttx || { echo "ERROR: failed to CD to $nuttx"; exit 1; } + echo " Building NuttX..." + echo "------------------------------------------------------------------------------------" + ${MAKE} ${JOPTION} ${MAKE_FLAGS} 1>/dev/null } # Coordinate the steps for the next build test function dotest { - echo "------------------------------------------------------------------------------------" - distclean - configure - build + echo "------------------------------------------------------------------------------------" + distclean + configure + build } # Perform the build test for each entry in the test list file @@ -273,72 +273,72 @@ testlist=`cat $testfile` #while read -r line || [[ -n $line ]]; do for line in $testlist; do - echo "====================================================================================" - firstch=${line:0:1} - if [ "X$firstch" == "X#" ]; then - echo "Skipping: $line" - else - echo "Configuration/Tool: $line" - - # Parse the next line - - config=`echo $line | cut -d',' -f1` - configdir=`echo $config | cut -s -d':' -f2` + echo "====================================================================================" + firstch=${line:0:1} + if [ "X$firstch" == "X#" ]; then + echo "Skipping: $line" + else + echo "Configuration/Tool: $line" + + # Parse the next line + + config=`echo $line | cut -d',' -f1` + configdir=`echo $config | cut -s -d':' -f2` + if [ -z "${configdir}" ]; then + configdir=`echo $config | cut -s -d'/' -f2` if [ -z "${configdir}" ]; then - configdir=`echo $config | cut -s -d'/' -f2` - if [ -z "${configdir}" ]; then - echo "ERROR: Malformed configuration: ${config}" - showusage - else - boarddir=`echo $config | cut -d'/' -f1` - fi + echo "ERROR: Malformed configuration: ${config}" + showusage else - boarddir=`echo $config | cut -d':' -f1` + boarddir=`echo $config | cut -d'/' -f1` fi + else + boarddir=`echo $config | cut -d':' -f1` + fi - # Detect the architecture of this board. - - ARCHLIST="arm avr hc mips misoc or1k renesas risc-v sim x86 xtensa z16 z80" - CHIPLIST="a1x am335x c5471 cxd56xx dm320 efm32 imx6 imxrt kinetis kl lc823450 - lpc17xx_40xx lpc214x lpc2378 lpc31xx lpc43xx lpc54xx max326xx moxart nrf52 - nuc1xx rx65n s32k1xx sam34 sama5 samd2l2 samd5e5 samv7 stm32 stm32f0l0g0 stm32f7 stm32h7 - stm32l4 str71x tiva tms570 xmc4 at32uc3 at90usb atmega mcs92s12ne64 pic32mx - pic32mz lm32 mor1kx m32262f8 sh7032 fe310 k210 gap8 nr5m100 sim qemu esp32 z16f2811 - ez80 z180 z8 z80" - - for arch in ${ARCHLIST}; do - for chip in ${CHIPLIST}; do - if [ -f ${nuttx}/boards/${arch}/${chip}/${boarddir}/Kconfig ]; then - archdir=${arch} - chipdir=${chip} - fi - done + # Detect the architecture of this board. + + ARCHLIST="arm avr hc mips misoc or1k renesas risc-v sim x86 xtensa z16 z80" + CHIPLIST="a1x am335x c5471 cxd56xx dm320 efm32 imx6 imxrt kinetis kl lc823450 + lpc17xx_40xx lpc214x lpc2378 lpc31xx lpc43xx lpc54xx max326xx moxart nrf52 + nuc1xx rx65n s32k1xx sam34 sama5 samd2l2 samd5e5 samv7 stm32 stm32f0l0g0 stm32f7 stm32h7 + stm32l4 str71x tiva tms570 xmc4 at32uc3 at90usb atmega mcs92s12ne64 pic32mx + pic32mz lm32 mor1kx m32262f8 sh7032 fe310 k210 gap8 nr5m100 sim qemu esp32 z16f2811 + ez80 z180 z8 z80" + + for arch in ${ARCHLIST}; do + for chip in ${CHIPLIST}; do + if [ -f ${nuttx}/boards/${arch}/${chip}/${boarddir}/Kconfig ]; then + archdir=${arch} + chipdir=${chip} + fi done + done - if [ -z "${archdir}" ]; then - echo "ERROR: Architecture of ${boarddir} not found" - exit 1 - fi + if [ -z "${archdir}" ]; then + echo "ERROR: Architecture of ${boarddir} not found" + exit 1 + fi - path=$nuttx/boards/$archdir/$chipdir/$boarddir/configs/$configdir - if [ ! -r "$path/defconfig" ]; then - echo "ERROR: no configuration found at $path" - showusage - fi + path=$nuttx/boards/$archdir/$chipdir/$boarddir/configs/$configdir + if [ ! -r "$path/defconfig" ]; then + echo "ERROR: no configuration found at $path" + showusage + fi - unset toolchain; - if [ "X$config" != "X$line" ]; then - toolchain=`echo $line | cut -d',' -f2` - if [ -z "$toolchain" ]; then - echo " Warning: no tool configuration" - fi + unset toolchain; + if [ "X$config" != "X$line" ]; then + toolchain=`echo $line | cut -d',' -f2` + if [ -z "$toolchain" ]; then + echo " Warning: no tool configuration" fi + fi - # Perform the build test + # Perform the build test - dotest - fi - cd $WD || { echo "ERROR: Failed to CD to $WD"; exit 1; } + dotest + fi + cd $WD || { echo "ERROR: Failed to CD to $WD"; exit 1; } done # < $testfile echo "====================================================================================" diff --git a/tools/unlink.bat b/tools/unlink.bat index 83b3b7a8a89..81ad87aa423 100755 --- a/tools/unlink.bat +++ b/tools/unlink.bat @@ -69,6 +69,6 @@ echo Missing Argument :ShowUsage echo USAGE: %0 ^ echo Where: -echo ^ is the linked (or copied) directory to be removed +echo ^ is the linked (or copied) directory to be removed :End diff --git a/tools/unlink.sh b/tools/unlink.sh index c0535be25aa..d852e197b04 100755 --- a/tools/unlink.sh +++ b/tools/unlink.sh @@ -39,32 +39,32 @@ link=$1 # Verify that arguments were provided if [ -z "${link}" ]; then - echo "Missing link argument" - exit 1 + echo "Missing link argument" + exit 1 fi # Check if something already exists at the link path if [ -e "${link}" ]; then - # Yes, is it a symbolic link? If so, then remove it + # Yes, is it a symbolic link? If so, then remove it - if [ -h "${link}" ]; then - rm -f "${link}" - else + if [ -h "${link}" ]; then + rm -f "${link}" + else - # If the path is a directory and contains the "fake link" mark, then - # treat it like a soft link (i.e., remove the directory) + # If the path is a directory and contains the "fake link" mark, then + # treat it like a soft link (i.e., remove the directory) - if [ -d "${link}" -a -f "${link}/.fakelnk" ]; then - rm -rf "${link}" - else + if [ -d "${link}" -a -f "${link}/.fakelnk" ]; then + rm -rf "${link}" + else - # It is something else (like a file) or directory that does - # not contain the "fake link" mark + # It is something else (like a file) or directory that does + # not contain the "fake link" mark - echo "${link} already exists but is not a symbolic link" - exit 1 - fi - fi + echo "${link} already exists but is not a symbolic link" + exit 1 + fi + fi fi diff --git a/tools/version.sh b/tools/version.sh index 151bb634a8d..8e3f57b3be2 100755 --- a/tools/version.sh +++ b/tools/version.sh @@ -44,89 +44,89 @@ unset BUILD unset OUTFILE while [ ! -z "$1" ]; do - case $1 in - -b ) - shift - BUILD=$1 - ;; - -d ) - set -x - ;; - -v ) - shift - VERSION=$1 - ;; - -h ) - echo "$0 is a tool for generation of proper version files for the NuttX build" - echo "" - echo $USAGE - echo "" - echo "Where:" - echo " -b " - echo " Use this build identification string. Default: use GIT build ID" - echo " NOTE: GIT build information may not be available in a snapshot" - echo " -d" - echo " Enable script debug" - echo " -h" - echo " show this help message and exit" - echo " -v " - echo " The NuttX version number expressed as a major and minor number separated" - echo " by a period" - echo " " - echo " The full path to the version file to be created" - exit 0 - ;; - * ) - break; - ;; - esac - shift + case $1 in + -b ) + shift + BUILD=$1 + ;; + -d ) + set -x + ;; + -v ) + shift + VERSION=$1 + ;; + -h ) + echo "$0 is a tool for generation of proper version files for the NuttX build" + echo "" + echo $USAGE + echo "" + echo "Where:" + echo " -b " + echo " Use this build identification string. Default: use GIT build ID" + echo " NOTE: GIT build information may not be available in a snapshot" + echo " -d" + echo " Enable script debug" + echo " -h" + echo " show this help message and exit" + echo " -v " + echo " The NuttX version number expressed as a major and minor number separated" + echo " by a period" + echo " " + echo " The full path to the version file to be created" + exit 0 + ;; + * ) + break; + ;; + esac + shift done OUTFILE=$1 if [ -z ${VERSION} ] ; then - VERSION=`git tag --sort=taggerdate | tail -1 | cut -d'-' -f2` + VERSION=`git tag --sort=taggerdate | tail -1 | cut -d'-' -f2` fi # Make sure we know what is going on if [ -z ${VERSION} ] ; then - echo "Missing versioning information" - echo $USAGE - echo $ADVICE - exit 1 + echo "Missing versioning information" + echo $USAGE + echo $ADVICE + exit 1 fi if [ -z ${OUTFILE} ] ; then - echo "Missing path to the output file" - echo $USAGE - echo $ADVICE - exit 1 + echo "Missing path to the output file" + echo $USAGE + echo $ADVICE + exit 1 fi # Get the major and minor version numbers MAJOR=`echo ${VERSION} | cut -d'.' -f1` if [ "X${MAJOR}" = "X${VERSION}" ]; then - echo "Missing minor version number" - echo $USAGE - echo $ADVICE - exit 2 + echo "Missing minor version number" + echo $USAGE + echo $ADVICE + exit 2 fi MINOR=`echo ${VERSION} | cut -d'.' -f2` # Get GIT information (if not provided on the command line) if [ -z "${BUILD}" ]; then - BUILD=`git log --oneline -1 | cut -d' ' -f1 2>/dev/null` - if [ -z "${BUILD}" ]; then - echo "GIT version information is not available" - exit 3 - fi - if [ -n "`git diff-index --name-only HEAD | head -1`" ]; then - BUILD=${BUILD}-dirty - fi + BUILD=`git log --oneline -1 | cut -d' ' -f1 2>/dev/null` + if [ -z "${BUILD}" ]; then + echo "GIT version information is not available" + exit 3 + fi + if [ -n "`git diff-index --name-only HEAD | head -1`" ]; then + BUILD=${BUILD}-dirty + fi fi # Write a version file into the NuttX directoy. The syntax of file is such that it diff --git a/tools/zipme.sh b/tools/zipme.sh index c754996e21d..f84387e5dec 100755 --- a/tools/zipme.sh +++ b/tools/zipme.sh @@ -50,38 +50,38 @@ unset BUILD unset DEBUG while [ ! -z "$1" ]; do - case $1 in - -b ) - shift - BUILD="-b ${1}" - ;; - -d ) - set -x - DEBUG=-d - ;; - -h ) - echo "$0 is a tool for generation of release versions of NuttX" - echo "" - echo $USAGE - echo "" - echo "Where:" - echo " -b " - echo " Use this build identification string. Default: use GIT build ID" - echo " NOTE: GIT build information may not be available in a snapshot" - echo " -d" - echo " Enable script debug" - echo " -h" - echo " show this help message and exit" - echo " " - echo " The NuttX version number expressed as a major and minor number separated" - echo " by a period" - exit 0 - ;; - * ) - break; - ;; - esac + case $1 in + -b ) shift + BUILD="-b ${1}" + ;; + -d ) + set -x + DEBUG=-d + ;; + -h ) + echo "$0 is a tool for generation of release versions of NuttX" + echo "" + echo $USAGE + echo "" + echo "Where:" + echo " -b " + echo " Use this build identification string. Default: use GIT build ID" + echo " NOTE: GIT build information may not be available in a snapshot" + echo " -d" + echo " Enable script debug" + echo " -h" + echo " show this help message and exit" + echo " " + echo " The NuttX version number expressed as a major and minor number separated" + echo " by a period" + exit 0 + ;; + * ) + break; + ;; + esac + shift done # The last thing on the command line is the version number @@ -92,21 +92,21 @@ VERSIONOPT="-v ${VERSION}" # Make sure we know what is going on if [ -z ${VERSION} ] ; then - echo "You must supply a version like xx.yy as a parameter" - echo $USAGE - echo $ADVICE - exit 1; + echo "You must supply a version like xx.yy as a parameter" + echo $USAGE + echo $ADVICE + exit 1; fi if [ -z "${BUILD}" ]; then - GITINFO=`git log 2>/dev/null | head -1` - if [ -z "${GITINFO}" ]; then - echo "GIT version information is not available. Use the -b option" - echo $USAGE - echo $ADVICE - exit 1; - fi - echo "GIT: ${GITINFO}" + GITINFO=`git log 2>/dev/null | head -1` + if [ -z "${GITINFO}" ]; then + echo "GIT version information is not available. Use the -b option" + echo $USAGE + echo $ADVICE + exit 1; + fi + echo "GIT: ${GITINFO}" fi @@ -116,18 +116,18 @@ fi MYNAME=`basename $0` if [ -x ${WD}/${MYNAME} ] ; then - TRUNKDIR="${WD}/../.." + TRUNKDIR="${WD}/../.." else - if [ -x ${WD}/tools/${MYNAME} ] ; then - TRUNKDIR="${WD}/.." - else - if [ -x ${WD}/nuttx-${VERSION}/tools/${MYNAME} ] ; then - TRUNKDIR="${WD}" - else - echo "You must cd into the NUTTX directory to execute this script." - exit 1 - fi - fi + if [ -x ${WD}/tools/${MYNAME} ] ; then + TRUNKDIR="${WD}/.." + else + if [ -x ${WD}/nuttx-${VERSION}/tools/${MYNAME} ] ; then + TRUNKDIR="${WD}" + else + echo "You must cd into the NUTTX directory to execute this script." + exit 1 + fi + fi fi # Get the NuttX directory names and the path to the parent directory @@ -138,21 +138,21 @@ APPDIR=${TRUNKDIR}/apps-${VERSION} # Make sure that the versioned directory exists if [ ! -d ${TRUNKDIR} ]; then - echo "Directory ${TRUNKDIR} does not exist" - exit 1 + echo "Directory ${TRUNKDIR} does not exist" + exit 1 fi cd ${TRUNKDIR} || \ - { echo "Failed to cd to ${TRUNKDIR}" ; exit 1 ; } + { echo "Failed to cd to ${TRUNKDIR}" ; exit 1 ; } if [ ! -d nuttx-${VERSION} ] ; then - echo "Directory ${TRUNKDIR}/nuttx-${VERSION} does not exist!" - exit 1 + echo "Directory ${TRUNKDIR}/nuttx-${VERSION} does not exist!" + exit 1 fi if [ ! -d apps-${VERSION} ] ; then - echo "Directory ${TRUNKDIR}/apps-${VERSION} does not exist!" - exit 1 + echo "Directory ${TRUNKDIR}/apps-${VERSION} does not exist!" + exit 1 fi # Create the versioned tarball names @@ -179,8 +179,8 @@ cd ${NUTTX}/Documentation || \ VERSIONSH=${NUTTX}/tools/version.sh if [ ! -x "${VERSIONSH}" ]; then - echo "No executable script was found at: ${VERSIONSH}" - exit 1 + echo "No executable script was found at: ${VERSIONSH}" + exit 1 fi ${VERSIONSH} ${DEBUG} ${BUILD} ${VERSIONOPT} ${NUTTX}/.version || \ @@ -216,27 +216,27 @@ make -C ${NUTTX} distclean # Remove any previous tarballs if [ -f ${NUTTX_TARNAME} ] ; then - echo "Removing ${TRUNKDIR}/${NUTTX_TARNAME}" - rm -f ${NUTTX_TARNAME} || \ - { echo "rm ${NUTTX_TARNAME} failed!" ; exit 1 ; } + echo "Removing ${TRUNKDIR}/${NUTTX_TARNAME}" + rm -f ${NUTTX_TARNAME} || \ + { echo "rm ${NUTTX_TARNAME} failed!" ; exit 1 ; } fi if [ -f ${NUTTX_ZIPNAME} ] ; then - echo "Removing ${TRUNKDIR}/${NUTTX_ZIPNAME}" - rm -f ${NUTTX_ZIPNAME} || \ - { echo "rm ${NUTTX_ZIPNAME} failed!" ; exit 1 ; } + echo "Removing ${TRUNKDIR}/${NUTTX_ZIPNAME}" + rm -f ${NUTTX_ZIPNAME} || \ + { echo "rm ${NUTTX_ZIPNAME} failed!" ; exit 1 ; } fi if [ -f ${APPS_TARNAME} ] ; then - echo "Removing ${TRUNKDIR}/${APPS_TARNAME}" - rm -f ${APPS_TARNAME} || \ - { echo "rm ${APPS_TARNAME} failed!" ; exit 1 ; } + echo "Removing ${TRUNKDIR}/${APPS_TARNAME}" + rm -f ${APPS_TARNAME} || \ + { echo "rm ${APPS_TARNAME} failed!" ; exit 1 ; } fi if [ -f ${APPS_ZIPNAME} ] ; then - echo "Removing ${TRUNKDIR}/${APPS_ZIPNAME}" - rm -f ${APPS_ZIPNAME} || \ - { echo "rm ${APPS_ZIPNAME} failed!" ; exit 1 ; } + echo "Removing ${TRUNKDIR}/${APPS_ZIPNAME}" + rm -f ${APPS_ZIPNAME} || \ + { echo "rm ${APPS_ZIPNAME} failed!" ; exit 1 ; } fi # Then tar and zip-up the directories @@ -255,4 +255,3 @@ ${ZIP} ${APPS_TARNAME} || \ { echo "zip of ${APPS_TARNAME} failed!" ; exit 1 ; } cd ${NUTTX} - From 00df2f0fe2d6d5d900a5f73c0254288e2929e90b Mon Sep 17 00:00:00 2001 From: Pieter du Preez Date: Sun, 5 Jan 2020 21:24:16 +0000 Subject: [PATCH 4/4] Fixed a compilation error, with irq debugging for stm32f7 and stm32h7 archs. This commit fixes a compilation error that occurs when enabling the following configuration items for stm32f7 and stm32h7 architectures: CONFIG_DEBUG_FEATURES=y CONFIG_DEBUG_ERROR=y CONFIG_DEBUG_WARN=y CONFIG_DEBUG_INFO=y CONFIG_DEBUG_IRQ=y CONFIG_DEBUG_IRQ_ERROR=y CONFIG_DEBUG_IRQ_WARN=y CONFIG_DEBUG_IRQ_INFO=y The compiler error for stm32f7: make[1]: Entering directory '/home/pdupreez/dev/wingunder/nuttx/arch/arm/src' CC: chip/stm32_irq.c chip/stm32_irq.c: In function 'up_irqinitialize': chip/stm32_irq.c:497:29: error: 'STM32_IRQ_NIRQS' undeclared (first use in this function); did you mean 'STM32_IRQ_FIRST'? stm32_dumpnvic("initial", STM32_IRQ_NIRQS); ^~~~~~~~~~~~~~~ STM32_IRQ_FIRST chip/stm32_irq.c:497:29: note: each undeclared identifier is reported only once for each function it appears in make[1]: *** [Makefile:172: stm32_irq.o] Error 1 make[1]: Leaving directory '/home/pdupreez/dev/wingunder/nuttx/arch/arm/src' And the compiler error for stm32h7: make[1]: Entering directory '/home/pdupreez/dev/wingunder/nuttx/arch/arm/src' CC: chip/stm32_irq.c chip/stm32_irq.c: In function 'stm32_dumpnvic': chip/stm32_irq.c:164:4: warning: #warning Missing logic [-Wcpp] # warning Missing logic ^~~~~~~ chip/stm32_irq.c: In function 'up_irqinitialize': chip/stm32_irq.c:522:29: error: 'STM32_IRQ_NIRQS' undeclared (first use in this function); did you mean 'STM32_IRQ_CRS'? stm32_dumpnvic("initial", STM32_IRQ_NIRQS); ^~~~~~~~~~~~~~~ STM32_IRQ_CRS chip/stm32_irq.c:522:29: note: each undeclared identifier is reported only once for each function it appears in make[1]: *** [Makefile:172: stm32_irq.o] Error 1 make[1]: Leaving directory '/home/pdupreez/dev/wingunder/nuttx/arch/arm/src' This commit replaces all STM32_IRQ_NIRQS defines with the NR_IRQS define, which seems to be consistent with the rest of the code in Nuttx. --- arch/arm/include/stm32f7/stm32f76xx77xx_irq.h | 1 - arch/arm/src/stm32f7/stm32_irq.c | 2 +- arch/arm/src/stm32h7/stm32_irq.c | 2 +- 3 files changed, 2 insertions(+), 3 deletions(-) diff --git a/arch/arm/include/stm32f7/stm32f76xx77xx_irq.h b/arch/arm/include/stm32f7/stm32f76xx77xx_irq.h index 5d5f8d21209..fc6c6d1287a 100644 --- a/arch/arm/include/stm32f7/stm32f76xx77xx_irq.h +++ b/arch/arm/include/stm32f7/stm32f76xx77xx_irq.h @@ -179,7 +179,6 @@ #define STM32_IRQ_MDIOS (STM32_IRQ_FIRST + 109) /* 109: MDIO slave global interrupt */ #define STM32_IRQ_NEXTINTS 110 -#define STM32_IRQ_NIRQS (STM32_IRQ_FIRST + 110) /* EXTI interrupts (Do not use IRQ numbers) */ diff --git a/arch/arm/src/stm32f7/stm32_irq.c b/arch/arm/src/stm32f7/stm32_irq.c index b43b36f6712..aea4de9aa0c 100644 --- a/arch/arm/src/stm32f7/stm32_irq.c +++ b/arch/arm/src/stm32f7/stm32_irq.c @@ -494,7 +494,7 @@ void up_irqinitialize(void) irq_attach(STM32_IRQ_RESERVED, stm32_reserved, NULL); #endif - stm32_dumpnvic("initial", STM32_IRQ_NIRQS); + stm32_dumpnvic("initial", NR_IRQS); /* If a debugger is connected, try to prevent it from catching hardfaults. * If CONFIG_ARMV7M_USEBASEPRI, no hardfaults are expected in normal diff --git a/arch/arm/src/stm32h7/stm32_irq.c b/arch/arm/src/stm32h7/stm32_irq.c index 0e878c972d4..b050e3c5d41 100644 --- a/arch/arm/src/stm32h7/stm32_irq.c +++ b/arch/arm/src/stm32h7/stm32_irq.c @@ -519,7 +519,7 @@ void up_irqinitialize(void) irq_attach(STM32_IRQ_RESERVED, stm32_reserved, NULL); #endif - stm32_dumpnvic("initial", STM32_IRQ_NIRQS); + stm32_dumpnvic("initial", NR_IRQS); /* If a debugger is connected, try to prevent it from catching hardfaults. * If CONFIG_ARMV7M_USEBASEPRI, no hardfaults are expected in normal