Merge remote-tracking branch 'origin/master' into ieee802154
This commit is contained in:
commit
f1aa43512a
@ -75,9 +75,11 @@
|
||||
#if defined(CONFIG_STM32L4_STM32L496XX)
|
||||
# define STM32L4_SRAM1_SIZE (256*1024) /* 256Kb SRAM1 on AHB bus Matrix */
|
||||
# define STM32L4_SRAM2_SIZE (64*1024) /* 64Kb SRAM2 on AHB bus Matrix */
|
||||
#else
|
||||
#elif defined(CONFIG_STM32L4_STM32L476XX) || defined(CONFIG_STM32L4_STM32L486XX)
|
||||
# define STM32L4_SRAM1_SIZE (96*1024) /* 96Kb SRAM1 on AHB bus Matrix */
|
||||
# define STM32L4_SRAM2_SIZE (32*1024) /* 32Kb SRAM2 on AHB bus Matrix */
|
||||
#else
|
||||
# error "Unsupported STM32L4 chip"
|
||||
#endif
|
||||
|
||||
# define STM32L4_NFSMC 1 /* Have FSMC memory controller */
|
||||
|
@ -143,15 +143,34 @@
|
||||
#define STM32L4_IRQ_TSC (STM32L4_IRQ_FIRST+77) /* 77: TSC global interrupt */
|
||||
#define STM32L4_IRQ_LCD (STM32L4_IRQ_FIRST+78) /* 78: LCD global interrupt */
|
||||
#define STM32L4_IRQ_AES (STM32L4_IRQ_FIRST+79) /* 79: AES crypto global interrupt */
|
||||
#define STM32L4_IRQ_RNG (STM32L4_IRQ_FIRST+80) /* 80: Rng global interrupt */
|
||||
#define STM32L4_IRQ_RNG (STM32L4_IRQ_FIRST+80) /* 80: RNG global interrupt */
|
||||
#define STM32L4_IRQ_FPU (STM32L4_IRQ_FIRST+81) /* 81: FPU global interrupt */
|
||||
|
||||
#define NR_INTERRUPTS 82
|
||||
#define NR_VECTORS (STM32L4_IRQ_FIRST+NR_INTERRUPTS)
|
||||
/* STM32L496xx/4A6xx only: */
|
||||
|
||||
#define STM32L4_IRQ_HASH_CRS (STM32L4_IRQ_FIRST+82) /* 82: HASH and CRS global interrupt */
|
||||
#define STM32L4_IRQ_I2C4_EV (STM32L4_IRQ_FIRST+83) /* 83: I2C4 event interrupt */
|
||||
#define STM32L4_IRQ_I2C4_ER (STM32L4_IRQ_FIRST+84) /* 84: I2C4 error interrupt */
|
||||
#define STM32L4_IRQ_DCMI (STM32L4_IRQ_FIRST+85) /* 85: DCMI global interrupt */
|
||||
#define STM32L4_IRQ_CAN2TX (STM32L4_IRQ_FIRST+86) /* 86: CAN2 TX interrupts */
|
||||
#define STM32L4_IRQ_CAN2RX0 (STM32L4_IRQ_FIRST+87) /* 87: CAN2 RX0 interrupts */
|
||||
#define STM32L4_IRQ_CAN2RX1 (STM32L4_IRQ_FIRST+88) /* 88: CAN2 RX1 interrupt */
|
||||
#define STM32L4_IRQ_CAN2SCE (STM32L4_IRQ_FIRST+89) /* 89: CAN2 SCE interrupt */
|
||||
#define STM32L4_IRQ_DMA2D (STM32L4_IRQ_FIRST+90) /* 90: DMA2D global interrupt */
|
||||
|
||||
#if defined(CONFIG_STM32L4_STM32L476XX) || defined(CONFIG_STM32L4_STM32L486XX)
|
||||
# define NR_INTERRUPTS 82
|
||||
#elif defined(CONFIG_STM32L4_STM32L496XX)
|
||||
# define NR_INTERRUPTS 91
|
||||
#else
|
||||
# error "Unsupported STM32L4 chip"
|
||||
#endif
|
||||
|
||||
#define NR_VECTORS (STM32L4_IRQ_FIRST+NR_INTERRUPTS)
|
||||
|
||||
/* EXTI interrupts (Do not use IRQ numbers) */
|
||||
|
||||
#define NR_IRQS NR_VECTORS
|
||||
#define NR_IRQS NR_VECTORS
|
||||
|
||||
/****************************************************************************************************
|
||||
* Public Types
|
||||
|
@ -33,8 +33,8 @@
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
#ifndef __ARCH_ARM_SRC_STM32_STM32_RRC_H
|
||||
#define __ARCH_ARM_SRC_STM32_STM32_RRC_H
|
||||
#ifndef __ARCH_ARM_SRC_STM32_STM32_RCC_H
|
||||
#define __ARCH_ARM_SRC_STM32_STM32_RCC_H
|
||||
|
||||
/************************************************************************************
|
||||
* Included Files
|
||||
@ -299,11 +299,7 @@ void stm32_clockenable(void);
|
||||
* Name: stm32_rcc_enablelse
|
||||
*
|
||||
* Description:
|
||||
* Enable the External Low-Speed (LSE) Oscillator and, if the RTC is
|
||||
* configured, setup the LSE as the RTC clock source, and enable the RTC.
|
||||
*
|
||||
* For the STM32L15X family, this will also select the LSE as the clock source of
|
||||
* the LCD.
|
||||
* Enable the External Low-Speed (LSE) Oscillator.
|
||||
*
|
||||
* Input Parameters:
|
||||
* None
|
||||
@ -340,4 +336,4 @@ void stm32_rcc_disablelsi(void);
|
||||
}
|
||||
#endif
|
||||
#endif /* __ASSEMBLY__ */
|
||||
#endif /* __ARCH_ARM_SRC_STM32_STM32_RRC_H */
|
||||
#endif /* __ARCH_ARM_SRC_STM32_STM32_RCC_H */
|
||||
|
@ -76,4 +76,4 @@ void up_waste(void);
|
||||
#endif
|
||||
|
||||
#endif /* __ASSEMBLY__ */
|
||||
#endif /* __ARCH_ARM_SRC_STM32_STM32_RRC_H */
|
||||
#endif /* __ARCH_ARM_SRC_STM32_STM32_WASTE_H */
|
||||
|
115
arch/arm/src/stm32f0/chip/stm32f0_flash.h
Normal file
115
arch/arm/src/stm32f0/chip/stm32f0_flash.h
Normal file
@ -0,0 +1,115 @@
|
||||
/************************************************************************************
|
||||
* arch/arm/src/stm32/chip/stm32f0_flash.h
|
||||
*
|
||||
* Copyright (C) 20017 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* 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_STM32F0_CHIP_STM32F0_FLASH_H
|
||||
#define __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_FLASH_H
|
||||
|
||||
/************************************************************************************
|
||||
* Included Files
|
||||
************************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
|
||||
#include "chip.h"
|
||||
|
||||
/************************************************************************************
|
||||
* Pre-processor Definitions
|
||||
************************************************************************************/
|
||||
|
||||
/* Register Offsets *****************************************************************/
|
||||
|
||||
#define STM32_FLASH_ACR_OFFSET 0x0000
|
||||
#define STM32_FLASH_KEYR_OFFSET 0x0004
|
||||
#define STM32_FLASH_OPTKEYR_OFFSET 0x0008
|
||||
#define STM32_FLASH_SR_OFFSET 0x000c
|
||||
#define STM32_FLASH_CR_OFFSET 0x0010
|
||||
#define STM32_FLASH_AR_OFFSET 0x0014
|
||||
#define STM32_FLASH_OBR_OFFSET 0x001c
|
||||
#define STM32_FLASH_WRPR_OFFSET 0x0020
|
||||
|
||||
/* Register Addresses ***************************************************************/
|
||||
|
||||
#define STM32_FLASH_ACR (STM32F0_FLASHIF_BASE+STM32_FLASH_ACR_OFFSET)
|
||||
#define STM32_FLASH_KEYR (STM32F0_FLASHIF_BASE+STM32_FLASH_KEYR_OFFSET)
|
||||
#define STM32_FLASH_OPTKEYR (STM32F0_FLASHIF_BASE+STM32_FLASH_OPTKEYR_OFFSET)
|
||||
#define STM32_FLASH_SR (STM32F0_FLASHIF_BASE+STM32_FLASH_SR_OFFSET)
|
||||
#define STM32_FLASH_CR (STM32F0_FLASHIF_BASE+STM32_FLASH_CR_OFFSET)
|
||||
#define STM32_FLASH_AR (STM32F0_FLASHIF_BASE+STM32_FLASH_AR_OFFSET)
|
||||
#define STM32_FLASH_OBR (STM32F0_FLASHIF_BASE+STM32_FLASH_OBR_OFFSET)
|
||||
#define STM32_FLASH_WRPR (STM32F0_FLASHIF_BASE+STM32_FLASH_WRPR_OFFSET)
|
||||
|
||||
/* Register Bitfield Definitions ****************************************************/
|
||||
/* Flash Access Control Register (ACR) */
|
||||
|
||||
#define FLASH_ACR_LATENCY_SHIFT (0)
|
||||
#define FLASH_ACR_LATENCY_MASK (7 << FLASH_ACR_LATENCY_SHIFT)
|
||||
# define FLASH_ACR_LATENCY(n) ((n) << FLASH_ACR_LATENCY_SHIFT) /* n wait states */
|
||||
# define FLASH_ACR_LATENCY_0 (0 << FLASH_ACR_LATENCY_SHIFT) /* 000: Zero wait states */
|
||||
# define FLASH_ACR_LATENCY_1 (1 << FLASH_ACR_LATENCY_SHIFT) /* 001: One wait state */
|
||||
#define FLASH_ACR_PRTFBE (1 << 4) /* Bit 4: FLASH prefetch enable */
|
||||
#define FLASH_ACR_PRFTBS (1 << 5) /* Bit 5: FLASH Prefetch buffer status */
|
||||
|
||||
/* Flash Status Register (SR) */
|
||||
|
||||
#define FLASH_SR_BSY (1 << 0) /* Bit 0: Busy */
|
||||
#define FLASH_SR_PGERR (1 << 2) /* Bit 2: Programming Error */
|
||||
#define FLASH_SR_WRPRT_ERR (1 << 4) /* Bit 3: Write Protection Error */
|
||||
#define FLASH_SR_EOP (1 << 5) /* Bit 4: End of Operation */
|
||||
|
||||
/* Flash Control Register (CR) */
|
||||
|
||||
#define FLASH_CR_PG (1 << 0) /* Bit 0: Program Page */
|
||||
#define FLASH_CR_PER (1 << 1) /* Bit 1: Page Erase */
|
||||
#define FLASH_CR_MER (1 << 2) /* Bit 2: Mass Erase */
|
||||
#define FLASH_CR_OPTPG (1 << 4) /* Bit 4: Option Byte Programming */
|
||||
#define FLASH_CR_OPTER (1 << 5) /* Bit 5: Option Byte Erase */
|
||||
#define FLASH_CR_STRT (1 << 6) /* Bit 6: Start Erase */
|
||||
#define FLASH_CR_LOCK (1 << 7) /* Bit 7: Page Locked or Lock Page */
|
||||
#define FLASH_CR_OPTWRE (1 << 9) /* Bit 8: Option Bytes Write Enable */
|
||||
#define FLASH_CR_ERRIE (1 << 10) /* Bit 10: Error Interrupt Enable */
|
||||
#define FLASH_CR_EOPIE (1 << 12) /* Bit 12: End of Program Interrupt Enable */
|
||||
#define FLASH_CR_OBLLAUNCH (1 << 13) /* Bit 13: Force option byte loading */
|
||||
|
||||
/* Flash Option byte register */
|
||||
#define FLASH_OBR_ /* To be provided */
|
||||
|
||||
/************************************************************************************
|
||||
* Public Functions
|
||||
************************************************************************************/
|
||||
|
||||
void stm32_flash_lock(void);
|
||||
void stm32_flash_unlock(void);
|
||||
|
||||
#endif /* __ARCH_ARM_SRC_STM32F0_CHIP_STM32F0_FLASH_H */
|
@ -124,15 +124,17 @@
|
||||
# define RCC_CFGR_PPRE1_HCLKd4 (5 << RCC_CFGR_PPRE1_SHIFT) /* 101: HCLK divided by 4 */
|
||||
# define RCC_CFGR_PPRE1_HCLKd8 (6 << RCC_CFGR_PPRE1_SHIFT) /* 110: HCLK divided by 8 */
|
||||
# define RCC_CFGR_PPRE1_HCLKd16 (7 << RCC_CFGR_PPRE1_SHIFT) /* 111: HCLK divided by 16 */
|
||||
/* Bits 13-11: Reserve. Keep the reset value */
|
||||
/* Bits 13-11: Reserve. Keep the reset value */
|
||||
#define RCC_CFGR_ADCPRE (1 << 14) /* Bit 14: ADC prescaler, Obsolete use ADC_CFGR2 */
|
||||
#define RCC_CFGR_PLLSRC_SHIFT (15) /* Bit 15: PLL input clock source */
|
||||
#define RCC_CFGR_PLLSRC_SHIFT (15) /* Bit 15: PLL input clock source */
|
||||
#define RCC_CFGR_PLLSRC_MASK (3 << RCC_CFGR_PLLSRC_SHIFT)
|
||||
# define RCC_CFGR_PLLSRC_HSId2 (0 << RCC_CFGR_PLLSRC_SHIFT) /* 00: HSI/2 as PLL input clock */
|
||||
# define RCC_CFGR_PLLSRC_HS1_PREDIV (1 << RCC_CFGR_PLLSRC_SHIFT) /* 01: HSE/PREDIV as PLL input clock */
|
||||
# define RCC_CFGR_PLLSRC_HSE_PREDIV (2 << RCC_CFGR_PLLSRC_SHIFT) /* 10: HSE/PREDIV as PLL input clock */
|
||||
# define RCC_CFGR_PLLSRC_HSI48_PREDIV (3 << RCC_CFGR_PLLSRC_SHIFT) /* 11: HSI48/PREDIV as PLL input clock */
|
||||
#define RCC_CFGR_PLLXTPRE (1 << 17) /* Bit 17: HSE divider for PLL entry */
|
||||
#define RCC_CFGR_PLLXTPRE_MASK (1 << 17) /* Bit 17: HSE divider for PLL entry */
|
||||
# define RCC_CFGR_PLLXTPRE_DIV1 (0 << 17) /* 0=No divistion */
|
||||
# define RCC_CFGR_PLLXTPRE_DIV2 (1 << 17) /* 1=Divide by two */
|
||||
#define RCC_CFGR_PLLMUL_SHIFT (18) /* Bits 21-18: PLL Multiplication Factor */
|
||||
#define RCC_CFGR_PLLMUL_MASK (0x0f << RCC_CFGR_PLLMUL_SHIFT)
|
||||
# define RCC_CFGR_PLLMUL_CLKx2 (0 << RCC_CFGR_PLLMUL_SHIFT) /* 0000: PLL input clock x 2 */
|
||||
|
@ -51,6 +51,7 @@
|
||||
#include "stm32f0_rcc.h"
|
||||
#include "stm32f0_clockconfig.h"
|
||||
#include "chip/stm32f0_syscfg.h"
|
||||
#include "chip/stm32f0_flash.h"
|
||||
#include "chip/stm32f0_gpio.h"
|
||||
|
||||
/****************************************************************************
|
||||
@ -91,11 +92,35 @@ void stm32f0_clockconfig(void)
|
||||
putreg32(regval, STM32F0_RCC_CR);
|
||||
while ((getreg32(STM32F0_RCC_CR) & RCC_CR_PLLRDY) != 0);
|
||||
|
||||
/* Configure the PLL. Multiply the HSI to get System Clock */
|
||||
/* Enable FLASH prefetch buffer and set flash latency */
|
||||
|
||||
regval = getreg32(STM32_FLASH_ACR);
|
||||
regval &= ~FLASH_ACR_LATENCY_MASK;
|
||||
regval |= (FLASH_ACR_LATENCY_1 | FLASH_ACR_PRTFBE);
|
||||
putreg32(regval, STM32_FLASH_ACR);
|
||||
|
||||
/* Set HCLK = SYSCLK */
|
||||
|
||||
regval = getreg32(STM32F0_RCC_CFGR);
|
||||
regval &= ~RCC_CFGR_PLLMUL_MASK;
|
||||
regval |= STM32F0_CFGR_PLLMUL;
|
||||
regval &= ~RCC_CFGR_HPRE_MASK;
|
||||
regval |= RCC_CFGR_HPRE_SYSCLK;
|
||||
putreg32(regval, STM32F0_RCC_CFGR);
|
||||
|
||||
/* Set PCLK = HCLK */
|
||||
|
||||
regval &= ~RCC_CFGR_PPRE1_MASK;
|
||||
regval |= RCC_CFGR_PPRE1_HCLK;
|
||||
putreg32(regval, STM32F0_RCC_CFGR);
|
||||
|
||||
/* Configure the PLL to generate the system clock
|
||||
*
|
||||
* 1. Use source = HSI/2
|
||||
* 2. Use PREDIV = 1
|
||||
* 3. Use multiplier from board.h
|
||||
*/
|
||||
|
||||
regval &= ~(RCC_CFGR_PLLSRC_MASK | RCC_CFGR_PLLXTPRE_MASK | RCC_CFGR_PLLMUL_MASK);
|
||||
regval |= (RCC_CFGR_PLLSRC_HSId2 | RCC_CFGR_PLLXTPRE_DIV1 | STM32F0_CFGR_PLLMUL);
|
||||
putreg32(regval, STM32F0_RCC_CFGR);
|
||||
|
||||
/* Enable the PLL */
|
||||
|
@ -552,7 +552,7 @@ static struct stm32f0_serial_s g_usart3priv =
|
||||
.priv = &g_usart3priv,
|
||||
},
|
||||
|
||||
.irq = STM32F0_IRQ_USART3,
|
||||
.irq = STM32F0_IRQ_USART345678,
|
||||
.parity = CONFIG_USART3_PARITY,
|
||||
.bits = CONFIG_USART3_BITS,
|
||||
.stopbits2 = CONFIG_USART3_2STOP,
|
||||
@ -613,7 +613,7 @@ static struct stm32f0_serial_s g_usart4priv =
|
||||
.priv = &g_usart4priv,
|
||||
},
|
||||
|
||||
.irq = STM32F0_IRQ_USART4,
|
||||
.irq = STM32F0_IRQ_USART345678,
|
||||
.parity = CONFIG_USART4_PARITY,
|
||||
.bits = CONFIG_USART4_BITS,
|
||||
.stopbits2 = CONFIG_USART4_2STOP,
|
||||
@ -678,7 +678,7 @@ static struct stm32f0_serial_s g_usart5priv =
|
||||
.priv = &g_usart5priv,
|
||||
},
|
||||
|
||||
.irq = STM32F0_IRQ_USART5,
|
||||
.irq = STM32F0_IRQ_USART345678,
|
||||
.parity = CONFIG_USART5_PARITY,
|
||||
.bits = CONFIG_USART5_BITS,
|
||||
.stopbits2 = CONFIG_USART5_2STOP,
|
||||
@ -1029,32 +1029,32 @@ static void stm32f0serial_setapbclock(FAR struct uart_dev_s *dev, bool on)
|
||||
return;
|
||||
#ifdef CONFIG_STM32F0_USART1
|
||||
case STM32F0_USART1_BASE:
|
||||
rcc_en = RCC_APB2ENR_USART1EN;
|
||||
rcc_en = RCC_APB2ENR_USART1EN;
|
||||
regaddr = STM32F0_RCC_APB2ENR;
|
||||
break;
|
||||
#endif
|
||||
#ifdef CONFIG_STM32F0_USART2
|
||||
case STM32F0_USART2_BASE:
|
||||
rcc_en = RCC_APB1ENR_USART2EN;
|
||||
regaddr =STM32F0_RCC_APB1ENR;
|
||||
rcc_en = RCC_APB1ENR_USART2EN;
|
||||
regaddr = STM32F0_RCC_APB1ENR;
|
||||
break;
|
||||
#endif
|
||||
#ifdef CONFIG_STM32F0_USART3
|
||||
case STM32F0_USART3_BASE:
|
||||
rcc_en = RCC_APB1ENR_USART3EN;
|
||||
regaddr =STM32F0_RCC_APB1ENR;
|
||||
rcc_en = RCC_APB1ENR_USART3EN;
|
||||
regaddr = STM32F0_RCC_APB1ENR;
|
||||
break;
|
||||
#endif
|
||||
#ifdef CONFIG_STM32F0_USART4
|
||||
case STM32F0_USART4_BASE:
|
||||
rcc_en = RCC_APB1ENR_USART4EN;
|
||||
regaddr =STM32F0_RCC_APB1ENR;
|
||||
rcc_en = RCC_APB1ENR_USART4EN;
|
||||
regaddr = STM32F0_RCC_APB1ENR;
|
||||
break;
|
||||
#endif
|
||||
#ifdef CONFIG_STM32F0_USART5
|
||||
case STM32F0_USART5_BASE:
|
||||
rcc_en = RCC_APB1ENR_USART5EN;
|
||||
regaddr =STM32F0_RCC_APB1ENR;
|
||||
rcc_en = RCC_APB1ENR_USART5EN;
|
||||
regaddr = STM32F0_RCC_APB1ENR;
|
||||
break;
|
||||
#endif
|
||||
}
|
||||
|
@ -33,8 +33,8 @@
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
#ifndef __ARCH_ARM_SRC_STM32F7_STM32_RRC_H
|
||||
#define __ARCH_ARM_SRC_STM32F7_STM32_RRC_H
|
||||
#ifndef __ARCH_ARM_SRC_STM32F7_STM32_RCC_H
|
||||
#define __ARCH_ARM_SRC_STM32F7_STM32_RCC_H
|
||||
|
||||
/************************************************************************************
|
||||
* Included Files
|
||||
@ -211,11 +211,7 @@ void stm32_clockenable(void);
|
||||
* Name: stm32_rcc_enablelse
|
||||
*
|
||||
* Description:
|
||||
* Enable the External Low-Speed (LSE) Oscillator and, if the RTC is
|
||||
* configured, setup the LSE as the RTC clock source, and enable the RTC.
|
||||
*
|
||||
* For the STM32L15X family, this will also select the LSE as the clock source of
|
||||
* the LCD.
|
||||
* Enable the External Low-Speed (LSE) Oscillator.
|
||||
*
|
||||
* Input Parameters:
|
||||
* None
|
||||
@ -252,4 +248,4 @@ void stm32_rcc_disablelsi(void);
|
||||
}
|
||||
#endif
|
||||
#endif /* __ASSEMBLY__ */
|
||||
#endif /* __ARCH_ARM_SRC_STM32F7_STM32_RRC_H */
|
||||
#endif /* __ARCH_ARM_SRC_STM32F7_STM32_RCC_H */
|
||||
|
@ -116,6 +116,7 @@ config STM32L4_STM32L496XX
|
||||
select STM32L4_HAVE_I2C4
|
||||
select STM32L4_HAVE_CAN2
|
||||
select STM32L4_HAVE_DCMI
|
||||
select STM32L4_HAVE_DMA2D
|
||||
|
||||
choice
|
||||
prompt "Embedded FLASH size"
|
||||
@ -184,6 +185,10 @@ config STM32L4_HAVE_DCMI
|
||||
bool
|
||||
default n
|
||||
|
||||
config STM32L4_HAVE_DMA2D
|
||||
bool
|
||||
default n
|
||||
|
||||
config STM32L4_HAVE_HASH
|
||||
bool
|
||||
default n
|
||||
@ -307,6 +312,11 @@ config STM32L4_DCMI
|
||||
default n
|
||||
depends on STM32L4_HAVE_DCMI
|
||||
|
||||
config STM32L4_DMA2D
|
||||
bool "DMA2D"
|
||||
default n
|
||||
depends on STM32L4_HAVE_DMA2D
|
||||
|
||||
config STM32L4_HASH
|
||||
bool "HASH"
|
||||
default n
|
||||
|
@ -1,9 +1,7 @@
|
||||
This is a port of NuttX to the STM32L4 Family
|
||||
Used development board is the Nucleo L476RG, STM32L4VGDiscovery
|
||||
|
||||
The status is HIGHLY EXPERIMENTAL.
|
||||
|
||||
OSTEST application works, but drivers are not complete.
|
||||
Used development boards are the Nucleo L476RG, Nucleo L496ZG and
|
||||
STM32L4VGDiscovery
|
||||
|
||||
Most code is copied and adapted from the STM32 Port.
|
||||
|
||||
@ -24,16 +22,20 @@ RCC : All registers defined, peripherals enabled, basic clock working
|
||||
SYSCTL : All registers defined
|
||||
USART : Working in normal mode (no DMA, to be tested, code is written)
|
||||
DMA : works; at least tested with QSPI
|
||||
SRAM2 : OK; can be included in MM region or left separate for special app purposes
|
||||
SRAM2 : OK; can be included in MM region or left separate for special app
|
||||
: purposes
|
||||
FIREWALL : Code written, to be tested, requires support from ldscript
|
||||
SPI : Code written, to be tested, including DMA
|
||||
SPI : OK, tested (Including DMA)
|
||||
I2C : Code written, to be tested (I2C4 missing)
|
||||
RTC : works
|
||||
QSPI : works in polling, interrupt, DMA, and also memory-mapped modes
|
||||
CAN : TODO
|
||||
OTGFS : dev implemented, tested, outstanding issue with CDCACM (ACM_SET_LINE_CODING, but otherwise works);
|
||||
: host implemented, only build smoke-tested (i.e. builds, but no functional testing yet)
|
||||
Timers : Implemented, with PWM oneshot and freerun, tickless OS support. Limited testing (focused on tickless OS so far)
|
||||
CAN : OK, tested
|
||||
OTGFS : dev implemented, tested, outstanding issue with CDCACM
|
||||
: (ACM_SET_LINE_CODING, but otherwise works); host implemented,
|
||||
: only build smoke-tested (i.e. builds, but no functional testing
|
||||
: yet)
|
||||
Timers : Implemented, with PWM oneshot and freerun, tickless OS support.
|
||||
: Limited testing (focused on tickless OS so far), PWM and QE tested OK.
|
||||
PM : TODO, PWR registers defined
|
||||
FSMC : TODO
|
||||
AES : TODO
|
||||
@ -46,10 +48,12 @@ ADC : TODO
|
||||
DAC : TODO
|
||||
|
||||
New peripherals with implementation to be written from scratch
|
||||
These are Low Priority TODO items, unless someone requests or contributes it.
|
||||
These are Low Priority TODO items, unless someone requests or contributes
|
||||
it.
|
||||
|
||||
TSC : TODO (Touch Screen Controller)
|
||||
SWP : TODO (Single wire protocol master, to connect with NFC enabled SIM cards)
|
||||
SWP : TODO (Single wire protocol master, to connect with NFC enabled
|
||||
: SIM cards)
|
||||
LPUART : TODO (Low power UART working with LSE at low baud rates)
|
||||
LPTIMER : TODO (Low power TIMER)
|
||||
OPAMP : TODO (Analog operational amplifier)
|
||||
@ -60,3 +64,4 @@ SAIPLL : works (PLL For Digital Audio interfaces, and other things)
|
||||
SAI : TODO (Digital Audio interfaces, I2S, SPDIF, etc)
|
||||
HASH : TODO (SHA-1, SHA-224, SHA-256, HMAC)
|
||||
DCMI : TODO (Digital Camera interfaces)
|
||||
DMA2D : TODO (Chrom-Art Accelerator for image manipulation)
|
||||
|
@ -49,8 +49,8 @@
|
||||
|
||||
#define STM32L4_NEXTI1 31
|
||||
#define STM32L4_EXTI1_MASK 0xffffffff
|
||||
#define STM32L4_NEXTI2 8
|
||||
#define STM32L4_EXTI2_MASK 0x000000ff
|
||||
#define STM32L4_NEXTI2 9
|
||||
#define STM32L4_EXTI2_MASK 0x000001ff
|
||||
|
||||
#define STM32L4_EXTI1_BIT(n) (1 << (n))
|
||||
#define STM32L4_EXTI2_BIT(n) (1 << (n))
|
||||
@ -114,6 +114,7 @@
|
||||
#define EXTI2_PVM3 (1 << 5) /* EXTI line 37 is connected to the PVM3 wakeup */
|
||||
#define EXTI2_PVM4 (1 << 6) /* EXTI line 38 is connected to the PVM4 wakeup */
|
||||
#define EXTI2_LCD (1 << 7) /* EXTI line 39 is connected to the LCD wakeup */
|
||||
#define EXTI2_I2C4 (1 << 8) /* EXTI line 40 is connected to the I2C4 wakeup */
|
||||
|
||||
/* Interrupt mask register */
|
||||
|
||||
|
@ -63,6 +63,7 @@
|
||||
#define STM32L4_SYSCFG_CFGR2_OFFSET 0x001c /* SYSCFG configuration register 2 */
|
||||
#define STM32L4_SYSCFG_SWPR_OFFSET 0x0020 /* SYSCFG SRAM2 write protection register */
|
||||
#define STM32L4_SYSCFG_SKR_OFFSET 0x0024 /* SYSCFG SRAM2 key register */
|
||||
#define STM32L4_SYSCFG_SWPR2_OFFSET 0x0028 /* SYSCFG SRAM2 write protection register 2 */
|
||||
|
||||
/* Register Addresses *******************************************************************************/
|
||||
|
||||
@ -100,8 +101,9 @@
|
||||
#define SYSCFG_CFGR1_I2C_PB8_FMP (1 << 18) /* Bit 18: Fast-mode Plus (Fm+) driving capability activation on PB8 */
|
||||
#define SYSCFG_CFGR1_I2C_PB9_FMP (1 << 19) /* Bit 19: Fast-mode Plus (Fm+) driving capability activation on PB9 */
|
||||
#define SYSCFG_CFGR1_I2C1_FMP (1 << 20) /* Bit 20: I2C1 Fast-mode Plus (Fm+) driving capability activation */
|
||||
#define SYSCFG_CFGR1_I2C2_FMP (1 << 21) /* Bit 21: I2C1 Fast-mode Plus (Fm+) driving capability activation */
|
||||
#define SYSCFG_CFGR1_I2C3_FMP (1 << 22) /* Bit 22: I2C1 Fast-mode Plus (Fm+) driving capability activation */
|
||||
#define SYSCFG_CFGR1_I2C2_FMP (1 << 21) /* Bit 21: I2C2 Fast-mode Plus (Fm+) driving capability activation */
|
||||
#define SYSCFG_CFGR1_I2C3_FMP (1 << 22) /* Bit 22: I2C3 Fast-mode Plus (Fm+) driving capability activation */
|
||||
#define SYSCFG_CFGR1_I2C4_FMP (1 << 23) /* Bit 23: I2C4 Fast-mode Plus (Fm+) driving capability activation */
|
||||
#define SYSCFG_CFGR1_FPU_IE0 (1 << 26) /* Bit 26: FPU Invalid operation interrupt enable */
|
||||
#define SYSCFG_CFGR1_FPU_IE1 (1 << 27) /* Bit 27: FPU Divide-by-zero interrupt enable */
|
||||
#define SYSCFG_CFGR1_FPU_IE2 (1 << 28) /* Bit 28: FPU Underflow interrupt enable */
|
||||
@ -118,45 +120,47 @@
|
||||
#define SYSCFG_EXTICR_PORTE (4) /* 0100: PE[x] pin */
|
||||
#define SYSCFG_EXTICR_PORTF (5) /* 0101: PF[C] pin */
|
||||
#define SYSCFG_EXTICR_PORTG (6) /* 0110: PG[x] pin */
|
||||
#define SYSCFG_EXTICR_PORTH (7) /* 0111: PH[x] pin (only on STM32L496xx/4A6xx) */
|
||||
#define SYSCFG_EXTICR_PORTI (8) /* 1000: PI[x] pin (only on STM32L496xx/4A6xx) */
|
||||
|
||||
#define SYSCFG_EXTICR_PORT_MASK (7)
|
||||
#define SYSCFG_EXTICR_PORT_MASK (15)
|
||||
#define SYSCFG_EXTICR_EXTI_SHIFT(g) (((g) & 3) << 2)
|
||||
#define SYSCFG_EXTICR_EXTI_MASK(g) (SYSCFG_EXTICR_PORT_MASK << (SYSCFG_EXTICR_EXTI_SHIFT(g)))
|
||||
|
||||
#define SYSCFG_EXTICR1_EXTI0_SHIFT (0) /* Bits 0-2: EXTI 0 coinfiguration */
|
||||
#define SYSCFG_EXTICR1_EXTI0_SHIFT (0) /* Bits 0-2: EXTI 0 configuration */
|
||||
#define SYSCFG_EXTICR1_EXTI0_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR1_EXTI0_SHIFT)
|
||||
#define SYSCFG_EXTICR1_EXTI1_SHIFT (4) /* Bits 4-6: EXTI 1 coinfiguration */
|
||||
#define SYSCFG_EXTICR1_EXTI1_SHIFT (4) /* Bits 4-6: EXTI 1 configuration */
|
||||
#define SYSCFG_EXTICR1_EXTI1_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR1_EXTI1_SHIFT)
|
||||
#define SYSCFG_EXTICR1_EXTI2_SHIFT (8) /* Bits 8-10: EXTI 2 coinfiguration */
|
||||
#define SYSCFG_EXTICR1_EXTI2_SHIFT (8) /* Bits 8-10: EXTI 2 configuration */
|
||||
#define SYSCFG_EXTICR1_EXTI2_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR1_EXTI2_SHIFT)
|
||||
#define SYSCFG_EXTICR1_EXTI3_SHIFT (12) /* Bits 12-14: EXTI 3 coinfiguration */
|
||||
#define SYSCFG_EXTICR1_EXTI3_SHIFT (12) /* Bits 12-14: EXTI 3 configuration */
|
||||
#define SYSCFG_EXTICR1_EXTI3_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR1_EXTI3_SHIFT)
|
||||
|
||||
#define SYSCFG_EXTICR2_EXTI4_SHIFT (0) /* Bits 0-2: EXTI 4 coinfiguration */
|
||||
#define SYSCFG_EXTICR2_EXTI4_SHIFT (0) /* Bits 0-2: EXTI 4 configuration */
|
||||
#define SYSCFG_EXTICR2_EXTI4_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR2_EXTI4_SHIFT)
|
||||
#define SYSCFG_EXTICR2_EXTI5_SHIFT (4) /* Bits 4-6: EXTI 5 coinfiguration */
|
||||
#define SYSCFG_EXTICR2_EXTI5_SHIFT (4) /* Bits 4-6: EXTI 5 configuration */
|
||||
#define SYSCFG_EXTICR2_EXTI5_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR2_EXTI5_SHIFT)
|
||||
#define SYSCFG_EXTICR2_EXTI6_SHIFT (8) /* Bits 8-10: EXTI 6 coinfiguration */
|
||||
#define SYSCFG_EXTICR2_EXTI6_SHIFT (8) /* Bits 8-10: EXTI 6 configuration */
|
||||
#define SYSCFG_EXTICR2_EXTI6_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR2_EXTI6_SHIFT)
|
||||
#define SYSCFG_EXTICR2_EXTI7_SHIFT (12) /* Bits 12-14: EXTI 7 coinfiguration */
|
||||
#define SYSCFG_EXTICR2_EXTI7_SHIFT (12) /* Bits 12-14: EXTI 7 configuration */
|
||||
#define SYSCFG_EXTICR2_EXTI7_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR2_EXTI7_SHIFT)
|
||||
|
||||
#define SYSCFG_EXTICR3_EXTI8_SHIFT (0) /* Bits 0-2: EXTI 8 coinfiguration */
|
||||
#define SYSCFG_EXTICR3_EXTI8_SHIFT (0) /* Bits 0-2: EXTI 8 configuration */
|
||||
#define SYSCFG_EXTICR3_EXTI8_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR3_EXTI8_SHIFT)
|
||||
#define SYSCFG_EXTICR3_EXTI9_SHIFT (4) /* Bits 4-6: EXTI 9 coinfiguration */
|
||||
#define SYSCFG_EXTICR3_EXTI9_SHIFT (4) /* Bits 4-6: EXTI 9 configuration */
|
||||
#define SYSCFG_EXTICR3_EXTI9_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR3_EXTI9_SHIFT)
|
||||
#define SYSCFG_EXTICR3_EXTI10_SHIFT (8) /* Bits 8-10: EXTI 10 coinfiguration */
|
||||
#define SYSCFG_EXTICR3_EXTI10_SHIFT (8) /* Bits 8-10: EXTI 10 configuration */
|
||||
#define SYSCFG_EXTICR3_EXTI10_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR3_EXTI10_SHIFT)
|
||||
#define SYSCFG_EXTICR3_EXTI11_SHIFT (12) /* Bits 12-14: EXTI 11 coinfiguration */
|
||||
#define SYSCFG_EXTICR3_EXTI11_SHIFT (12) /* Bits 12-14: EXTI 11 configuration */
|
||||
#define SYSCFG_EXTICR3_EXTI11_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR3_EXTI11_SHIFT)
|
||||
|
||||
#define SYSCFG_EXTICR4_EXTI12_SHIFT (0) /* Bits 0-2: EXTI 12 coinfiguration */
|
||||
#define SYSCFG_EXTICR4_EXTI12_SHIFT (0) /* Bits 0-2: EXTI 12 configuration */
|
||||
#define SYSCFG_EXTICR4_EXTI12_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR4_EXTI12_SHIFT)
|
||||
#define SYSCFG_EXTICR4_EXTI13_SHIFT (4) /* Bits 4-6: EXTI 13 coinfiguration */
|
||||
#define SYSCFG_EXTICR4_EXTI13_SHIFT (4) /* Bits 4-6: EXTI 13 configuration */
|
||||
#define SYSCFG_EXTICR4_EXTI13_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR4_EXTI13_SHIFT)
|
||||
#define SYSCFG_EXTICR4_EXTI14_SHIFT (8) /* Bits 8-10: EXTI 14 coinfiguration */
|
||||
#define SYSCFG_EXTICR4_EXTI14_SHIFT (8) /* Bits 8-10: EXTI 14 configuration */
|
||||
#define SYSCFG_EXTICR4_EXTI14_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR4_EXTI14_SHIFT)
|
||||
#define SYSCFG_EXTICR4_EXTI15_SHIFT (12) /* Bits 12-14: EXTI 15 coinfiguration */
|
||||
#define SYSCFG_EXTICR4_EXTI15_SHIFT (12) /* Bits 12-14: EXTI 15 configuration */
|
||||
#define SYSCFG_EXTICR4_EXTI15_MASK (SYSCFG_EXTICR_PORT_MASK << SYSCFG_EXTICR4_EXTI15_SHIFT)
|
||||
|
||||
/* SYSCFG SRAM2 control and status register */
|
||||
@ -173,13 +177,16 @@
|
||||
#define SYSCFG_CFGR2_SPF (1 << 8) /* Bit 8: SRAM2 parity error flag */
|
||||
|
||||
/* SYSCFG SRAM2 write protection register */
|
||||
/* There is one bit per SRAM2 page */
|
||||
/* There is one bit per SRAM2 page (0 to 31) */
|
||||
|
||||
/* SYSCFG SRAM2 key register */
|
||||
|
||||
#define SYSCFG_SKR_SHIFT 0
|
||||
#define SYSCFG_SKR_MASK (0xFF << SYSCFG_SKR_SHIFT)
|
||||
|
||||
#endif /* CONFIG_STM32L4_STM32L476XX || CONFIG_STM32L4_STM32L486XX */
|
||||
/* SYSCFG SRAM2 write protection register 2 (only on STM32L496xx/4A6xx) */
|
||||
/* There is one bit per SRAM2 page (32 to 63) */
|
||||
|
||||
#endif /* CONFIG_STM32L4_STM32L476XX || CONFIG_STM32L4_STM32L486XX || CONFIG_STM32L4_STM32L496XX */
|
||||
#endif /* __ARCH_ARM_SRC_STM32L4_CHIP_STM32L4_SYSCFG_H */
|
||||
|
||||
|
@ -343,6 +343,11 @@
|
||||
|
||||
#define DMACHAN_DAC2 DMACHAN_SETTING(STM32L4_DMA2_CHAN5, 3)
|
||||
|
||||
/* DCMI */
|
||||
|
||||
#define DMACHAN_DCMI_1 DMACHAN_SETTING(STM32L4_DMA2_CHAN5, 4)
|
||||
#define DMACHAN_DCMI_2 DMACHAN_SETTING(STM32L4_DMA2_CHAN6, 0)
|
||||
|
||||
/* DFSDM */
|
||||
|
||||
#define DMACHAN_DFSDM0 DMACHAN_SETTING(STM32L4_DMA1_CHAN4, 0)
|
||||
@ -350,6 +355,10 @@
|
||||
#define DMACHAN_DFSDM2 DMACHAN_SETTING(STM32L4_DMA1_CHAN6, 0)
|
||||
#define DMACHAN_DFSDM3 DMACHAN_SETTING(STM32L4_DMA1_CHAN7, 0)
|
||||
|
||||
/* HASH */
|
||||
|
||||
#define DMACHAN_HASH_IN DMACHAN_SETTING(STM32L4_DMA2_CHAN7, 6)
|
||||
|
||||
/* I2C */
|
||||
|
||||
#define DMACHAN_I2C1_RX_1 DMACHAN_SETTING(STM32L4_DMA1_CHAN7, 3)
|
||||
@ -363,6 +372,9 @@
|
||||
#define DMACHAN_I2C3_RX DMACHAN_SETTING(STM32L4_DMA1_CHAN3, 2)
|
||||
#define DMACHAN_I2C3_TX DMACHAN_SETTING(STM32L4_DMA1_CHAN2, 3)
|
||||
|
||||
#define DMACHAN_I2C4_RX DMACHAN_SETTING(STM32L4_DMA2_CHAN1, 0)
|
||||
#define DMACHAN_I2C4_TX DMACHAN_SETTING(STM32L4_DMA2_CHAN2, 0)
|
||||
|
||||
/* QUADSPI */
|
||||
|
||||
#define DMACHAN_QUADSPI_1 DMACHAN_SETTING(STM32L4_DMA1_CHAN5, 5)
|
||||
|
@ -126,6 +126,11 @@
|
||||
#define GPIO_CAN1_TX_2 (GPIO_ALT|GPIO_AF9 |GPIO_PORTB|GPIO_PIN9)
|
||||
#define GPIO_CAN1_TX_3 (GPIO_ALT|GPIO_AF9 |GPIO_PORTD|GPIO_PIN1)
|
||||
|
||||
#define GPIO_CAN2_RX_1 (GPIO_ALT|GPIO_AF3 |GPIO_PORTB|GPIO_PIN5)
|
||||
#define GPIO_CAN2_TX_1 (GPIO_ALT|GPIO_AF8 |GPIO_PORTB|GPIO_PIN6)
|
||||
#define GPIO_CAN2_RX_2 (GPIO_ALT|GPIO_AF10 |GPIO_PORTB|GPIO_PIN12)
|
||||
#define GPIO_CAN2_TX_2 (GPIO_ALT|GPIO_AF10 |GPIO_PORTB|GPIO_PIN13)
|
||||
|
||||
/* Clocks outputs */
|
||||
|
||||
#define GPIO_MCO (GPIO_ALT|GPIO_AF0 |GPIO_PORTA|GPIO_PIN8)
|
||||
@ -151,6 +156,15 @@
|
||||
#define GPIO_DAC1_OUT (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN4)
|
||||
#define GPIO_DAC2_OUT (GPIO_ANALOG|GPIO_PORTA|GPIO_PIN5)
|
||||
|
||||
/* Digital Camera Interface (DCMI) */
|
||||
|
||||
#define GPIO_DCMI_PIXCK_1 (GPIO_ALT|GPIO_AF4|GPIO_PORTA|GPIO_PIN6)
|
||||
#define GPIO_DCMI_PIXCK_2 (GPIO_ALT|GPIO_AF10|GPIO_PORTD|GPIO_PIN9)
|
||||
#define GPIO_DCMI_HSYNC_1 (GPIO_ALT|GPIO_AF10|GPIO_PORTA|GPIO_PIN4)
|
||||
#define GPIO_DCMI_HSYNC_2 (GPIO_ALT|GPIO_AF10|GPIO_PORTD|GPIO_PIN8)
|
||||
#define GPIO_DCMI_VSYNC_1 (GPIO_ALT|GPIO_AF10|GPIO_PORTB|GPIO_PIN7)
|
||||
/* TODO: DCMI data pins missing */
|
||||
|
||||
/* Digital Filter for Sigma-Delta Modulators (DFSDM) */
|
||||
|
||||
#define GPIO_DFSDM_DATIN0_1 (GPIO_ALT|GPIO_AF6 |GPIO_PORTB|GPIO_PIN1)
|
||||
@ -253,6 +267,10 @@
|
||||
|
||||
/* I2C */
|
||||
|
||||
/* Note: STM32L496xx/4A6xx devices have few additional mappings for
|
||||
* I2C1-3 that are not defined here.
|
||||
*/
|
||||
|
||||
#define GPIO_I2C1_SDA_1 (GPIO_ALT|GPIO_AF4 |GPIO_PORTB|GPIO_PIN7)
|
||||
#define GPIO_I2C1_SDA_2 (GPIO_ALT|GPIO_AF4 |GPIO_PORTB|GPIO_PIN9)
|
||||
#define GPIO_I2C1_SDA_3 (GPIO_ALT|GPIO_AF4 |GPIO_PORTG|GPIO_PIN13)
|
||||
@ -278,6 +296,19 @@
|
||||
#define GPIO_I2C3_SMBA_1 (GPIO_ALT|GPIO_AF4 |GPIO_PORTB|GPIO_PIN2)
|
||||
#define GPIO_I2C3_SMBA_2 (GPIO_ALT|GPIO_AF4 |GPIO_PORTG|GPIO_PIN6)
|
||||
|
||||
#define GPIO_I2C4_SDA_1 (GPIO_ALT|GPIO_AF5 |GPIO_PORTB|GPIO_PIN7)
|
||||
#define GPIO_I2C4_SDA_2 (GPIO_ALT|GPIO_AF3 |GPIO_PORTB|GPIO_PIN11)
|
||||
#define GPIO_I2C4_SDA_3 (GPIO_ALT|GPIO_AF2 |GPIO_PORTC|GPIO_PIN1)
|
||||
#define GPIO_I2C4_SDA_4 (GPIO_ALT|GPIO_AF4 |GPIO_PORTD|GPIO_PIN13)
|
||||
#define GPIO_I2C4_SCL_1 (GPIO_ALT|GPIO_AF5 |GPIO_PORTB|GPIO_PIN6)
|
||||
#define GPIO_I2C4_SCL_2 (GPIO_ALT|GPIO_AF3 |GPIO_PORTB|GPIO_PIN10)
|
||||
#define GPIO_I2C4_SCL_3 (GPIO_ALT|GPIO_AF2 |GPIO_PORTC|GPIO_PIN0)
|
||||
#define GPIO_I2C4_SCL_4 (GPIO_ALT|GPIO_AF4 |GPIO_PORTD|GPIO_PIN12)
|
||||
#define GPIO_I2C4_SMBA_1 (GPIO_ALT|GPIO_AF5 |GPIO_PORTA|GPIO_PIN14)
|
||||
#define GPIO_I2C4_SMBA_2 (GPIO_ALT|GPIO_AF4 |GPIO_PORTD|GPIO_PIN11)
|
||||
#define GPIO_I2C4_SMBA_3 (GPIO_ALT|GPIO_AF4 |GPIO_PORTD|GPIO_PIN11)
|
||||
#define GPIO_I2C4_SMBA_4 (GPIO_ALT|GPIO_AF4 |GPIO_PORTF|GPIO_PIN13)
|
||||
|
||||
/* JTAG */
|
||||
|
||||
#define GPIO_JTCK_SWCLK (GPIO_ALT|GPIO_AF0|GPIO_PORTA|GPIO_PIN14)
|
||||
|
@ -35,8 +35,8 @@
|
||||
*
|
||||
****************************************************************************************************/
|
||||
|
||||
#ifndef __ARCH_ARM_SRC_STM32L4_CHIP_STM32F42XXX_RCC_H
|
||||
#define __ARCH_ARM_SRC_STM32L4_CHIP_STM32F42XXX_RCC_H
|
||||
#ifndef __ARCH_ARM_SRC_STM32L4_CHIP_STM32L4X6XX_RCC_H
|
||||
#define __ARCH_ARM_SRC_STM32L4_CHIP_STM32L4X6XX_RCC_H
|
||||
|
||||
/****************************************************************************************************
|
||||
* Included Files
|
||||
@ -80,9 +80,11 @@
|
||||
#define STM32L4_RCC_APB1SMENR1_OFFSET 0x0078 /* RCC APB1 low power mode peripheral clock enable register 1 */
|
||||
#define STM32L4_RCC_APB1SMENR2_OFFSET 0x007c /* RCC APB1 low power mode peripheral clock enable register 2 */
|
||||
#define STM32L4_RCC_APB2SMENR_OFFSET 0x0080 /* RCC APB2 low power mode peripheral clock enable register */
|
||||
#define STM32L4_RCC_CCIPR_OFFSET 0x0088 /* Peripherals independ clock configuration register */
|
||||
#define STM32L4_RCC_CCIPR_OFFSET 0x0088 /* Peripherals independent clock configuration register 1 */
|
||||
#define STM32L4_RCC_BDCR_OFFSET 0x0090 /* Backup domain control register */
|
||||
#define STM32L4_RCC_CSR_OFFSET 0x0094 /* Control/status register */
|
||||
#define STM32L4_RCC_CRRCR_OFFSET 0x0098 /* Clock recovery RC register */
|
||||
#define STM32L4_RCC_CCIPR2_OFFSET 0x009c /* Peripherals independent clock configuration register 2 */
|
||||
|
||||
/* Register Addresses *******************************************************************************/
|
||||
|
||||
@ -116,6 +118,8 @@
|
||||
#define STM32L4_RCC_CCIPR (STM32L4_RCC_BASE+STM32L4_RCC_CCIPR_OFFSET)
|
||||
#define STM32L4_RCC_BDCR (STM32L4_RCC_BASE+STM32L4_RCC_BDCR_OFFSET)
|
||||
#define STM32L4_RCC_CSR (STM32L4_RCC_BASE+STM32L4_RCC_CSR_OFFSET)
|
||||
#define STM32L4_RCC_CRRCR (STM32L4_RCC_BASE+STM32L4_RCC_CRRCR_OFFSET)
|
||||
#define STM32L4_RCC_CCIPR2 (STM32L4_RCC_BASE+STM32L4_RCC_CCIPR2_OFFSET)
|
||||
|
||||
/* Register Bitfield Definitions ********************************************************************/
|
||||
|
||||
@ -336,41 +340,44 @@
|
||||
|
||||
/* Clock interrupt enable register */
|
||||
|
||||
#define RCC_CIR_LSIRDYIE (1 << 0) /* Bit 0: LSI Ready Interrupt Enable */
|
||||
#define RCC_CIR_LSERDYIE (1 << 1) /* Bit 1: LSE Ready Interrupt Enable */
|
||||
#define RCC_CIR_MSIRDYIE (1 << 2) /* Bit 2: MSI Ready Interrupt Enable */
|
||||
#define RCC_CIR_HSIRDYIE (1 << 3) /* Bit 3: HSI Ready Interrupt Enable */
|
||||
#define RCC_CIR_HSERDYIE (1 << 4) /* Bit 4: HSE Ready Interrupt Enable */
|
||||
#define RCC_CIR_PLLRDYIE (1 << 5) /* Bit 5: PLL Ready Interrupt Enable */
|
||||
#define RCC_CIR_PLLSAI1RDYIE (1 << 6) /* Bit 6: PLLSAI1 Ready Interrupt enable */
|
||||
#define RCC_CIR_PLLSAI2RDYIE (1 << 7) /* Bit 7: PLLSAI2 Ready Interrupt enable */
|
||||
#define RCC_CIR_LSECSSIE (1 << 9) /* Bit 9: LSE Clock Security System Interrupt Enable */
|
||||
#define RCC_CIR_LSIRDYIE (1 << 0) /* Bit 0: LSI Ready Interrupt Enable */
|
||||
#define RCC_CIR_LSERDYIE (1 << 1) /* Bit 1: LSE Ready Interrupt Enable */
|
||||
#define RCC_CIR_MSIRDYIE (1 << 2) /* Bit 2: MSI Ready Interrupt Enable */
|
||||
#define RCC_CIR_HSIRDYIE (1 << 3) /* Bit 3: HSI Ready Interrupt Enable */
|
||||
#define RCC_CIR_HSERDYIE (1 << 4) /* Bit 4: HSE Ready Interrupt Enable */
|
||||
#define RCC_CIR_PLLRDYIE (1 << 5) /* Bit 5: PLL Ready Interrupt Enable */
|
||||
#define RCC_CIR_PLLSAI1RDYIE (1 << 6) /* Bit 6: PLLSAI1 Ready Interrupt enable */
|
||||
#define RCC_CIR_PLLSAI2RDYIE (1 << 7) /* Bit 7: PLLSAI2 Ready Interrupt enable */
|
||||
#define RCC_CIR_LSECSSIE (1 << 9) /* Bit 9: LSE Clock Security System Interrupt Enable */
|
||||
#define RCC_CIR_HSI48RDYIE (1 << 10) /* Bit 10: HSI48 Ready Interrupt Enable */
|
||||
|
||||
/* Clock interrupt flag register */
|
||||
|
||||
#define RCC_CIR_LSIRDYIF (1 << 0) /* Bit 0: LSI Ready Interrupt Flag */
|
||||
#define RCC_CIR_LSERDYIF (1 << 1) /* Bit 1: LSE Ready Interrupt Flag */
|
||||
#define RCC_CIR_MSIRDYIF (1 << 2) /* Bit 2: MSI Ready Interrupt Flag */
|
||||
#define RCC_CIR_HSIRDYIF (1 << 3) /* Bit 3: HSI Ready Interrupt Flag */
|
||||
#define RCC_CIR_HSERDYIF (1 << 4) /* Bit 4: HSE Ready Interrupt Flag */
|
||||
#define RCC_CIR_PLLRDYIF (1 << 5) /* Bit 5: PLL Ready Interrupt Flag */
|
||||
#define RCC_CIR_PLLSAI1RDYIF (1 << 6) /* Bit 6: PLLSAI1 Ready Interrupt Flag */
|
||||
#define RCC_CIR_PLLSAI2RDYIF (1 << 7) /* Bit 7: PLLSAI2 Ready Interrupt Flag */
|
||||
#define RCC_CIR_CSSF (1 << 8) /* Bit 8: Clock Security System Interrupt Flag */
|
||||
#define RCC_CIR_LSECSSIF (1 << 9) /* Bit 9: LSE Clock Security System Interrupt Flag */
|
||||
#define RCC_CIR_LSIRDYIF (1 << 0) /* Bit 0: LSI Ready Interrupt Flag */
|
||||
#define RCC_CIR_LSERDYIF (1 << 1) /* Bit 1: LSE Ready Interrupt Flag */
|
||||
#define RCC_CIR_MSIRDYIF (1 << 2) /* Bit 2: MSI Ready Interrupt Flag */
|
||||
#define RCC_CIR_HSIRDYIF (1 << 3) /* Bit 3: HSI Ready Interrupt Flag */
|
||||
#define RCC_CIR_HSERDYIF (1 << 4) /* Bit 4: HSE Ready Interrupt Flag */
|
||||
#define RCC_CIR_PLLRDYIF (1 << 5) /* Bit 5: PLL Ready Interrupt Flag */
|
||||
#define RCC_CIR_PLLSAI1RDYIF (1 << 6) /* Bit 6: PLLSAI1 Ready Interrupt Flag */
|
||||
#define RCC_CIR_PLLSAI2RDYIF (1 << 7) /* Bit 7: PLLSAI2 Ready Interrupt Flag */
|
||||
#define RCC_CIR_CSSF (1 << 8) /* Bit 8: Clock Security System Interrupt Flag */
|
||||
#define RCC_CIR_LSECSSIF (1 << 9) /* Bit 9: LSE Clock Security System Interrupt Flag */
|
||||
#define RCC_CIR_HSI48RDYIF (1 << 10) /* Bit 10: HSI48 Ready Interrupt Flag */
|
||||
|
||||
/* Clock interrupt clear register */
|
||||
|
||||
#define RCC_CIR_LSIRDYIC (1 << 0) /* Bit 0: LSI Ready Interrupt Clear */
|
||||
#define RCC_CIR_LSERDYIC (1 << 1) /* Bit 1: LSE Ready Interrupt Clear */
|
||||
#define RCC_CIR_MSIRDYIC (1 << 2) /* Bit 2: MSI Ready Interrupt Clear */
|
||||
#define RCC_CIR_HSIRDYIC (1 << 3) /* Bit 3: HSI Ready Interrupt Clear */
|
||||
#define RCC_CIR_HSERDYIC (1 << 4) /* Bit 4: HSE Ready Interrupt Clear */
|
||||
#define RCC_CIR_PLLRDYIC (1 << 5) /* Bit 5: PLL Ready Interrupt Clear */
|
||||
#define RCC_CIR_PLLSAI1RDYIC (1 << 6) /* Bit 6: PLLSAI1 Ready Interrupt Clear */
|
||||
#define RCC_CIR_PLLSAI2RDYIC (1 << 7) /* Bit 7: PLLSAI2 Ready Interrupt Clear */
|
||||
#define RCC_CIR_CSSC (1 << 8) /* Bit 8: Clock Security System Interrupt Clear */
|
||||
#define RCC_CIR_LSECSSIC (1 << 9) /* Bit 9: LSE Clock Security System Interrupt Clear */
|
||||
#define RCC_CIR_LSIRDYIC (1 << 0) /* Bit 0: LSI Ready Interrupt Clear */
|
||||
#define RCC_CIR_LSERDYIC (1 << 1) /* Bit 1: LSE Ready Interrupt Clear */
|
||||
#define RCC_CIR_MSIRDYIC (1 << 2) /* Bit 2: MSI Ready Interrupt Clear */
|
||||
#define RCC_CIR_HSIRDYIC (1 << 3) /* Bit 3: HSI Ready Interrupt Clear */
|
||||
#define RCC_CIR_HSERDYIC (1 << 4) /* Bit 4: HSE Ready Interrupt Clear */
|
||||
#define RCC_CIR_PLLRDYIC (1 << 5) /* Bit 5: PLL Ready Interrupt Clear */
|
||||
#define RCC_CIR_PLLSAI1RDYIC (1 << 6) /* Bit 6: PLLSAI1 Ready Interrupt Clear */
|
||||
#define RCC_CIR_PLLSAI2RDYIC (1 << 7) /* Bit 7: PLLSAI2 Ready Interrupt Clear */
|
||||
#define RCC_CIR_CSSC (1 << 8) /* Bit 8: Clock Security System Interrupt Clear */
|
||||
#define RCC_CIR_LSECSSIC (1 << 9) /* Bit 9: LSE Clock Security System Interrupt Clear */
|
||||
#define RCC_CIR_HSI48RDYIC (1 << 10) /* Bit 10: HSI48 Oscillator Ready Interrupt Clear */
|
||||
|
||||
/* AHB1 peripheral reset register */
|
||||
|
||||
@ -379,10 +386,11 @@
|
||||
#define RCC_AHB1RSTR_FLASHRST (1 << 8) /* Bit 8: Flash memory interface reset */
|
||||
#define RCC_AHB1RSTR_CRCRST (1 << 12) /* Bit 12: CRC reset */
|
||||
#define RCC_AHB1RSTR_TSCRST (1 << 16) /* Bit 16: Touch Sensing Controller reset */
|
||||
#define RCC_AHB1RSTR_DMA2DRST (1 << 17) /* Bit 17: DMA2D reset */
|
||||
|
||||
/* AHB2 peripheral reset register */
|
||||
|
||||
#define RCC_AHB1ENR_GPIOEN(port) (1 << port)
|
||||
#define RCC_AHB1ENR_GPIOEN(port) (1 << (port))
|
||||
#define RCC_AHB2RSTR_GPIOARST (1 << 0) /* Bit 0: IO port A reset */
|
||||
#define RCC_AHB2RSTR_GPIOBRST (1 << 1) /* Bit 1: IO port B reset */
|
||||
#define RCC_AHB2RSTR_GPIOCRST (1 << 2) /* Bit 2: IO port C reset */
|
||||
@ -391,10 +399,13 @@
|
||||
#define RCC_AHB2RSTR_GPIOFRST (1 << 5) /* Bit 5: IO port F reset */
|
||||
#define RCC_AHB2RSTR_GPIOGRST (1 << 6) /* Bit 6: IO port G reset */
|
||||
#define RCC_AHB2RSTR_GPIOHRST (1 << 7) /* Bit 7: IO port H reset */
|
||||
#define RCC_AHB2RSTR_GPIOIRST (1 << 8) /* Bit 8: IO port I reset */
|
||||
#define RCC_AHB2RSTR_OTGFSRST (1 << 12) /* Bit 12: USB OTG FS module reset */
|
||||
#define RCC_AHB2RSTR_ADCRST (1 << 13) /* Bit 13: ADC interface reset (common to all ADCs) */
|
||||
#define RCC_AHB2RSTR_DCMIRST (1 << 14) /* Bit 14: DCMI interface reset */
|
||||
#define RCC_AHB2RSTR_AESRST (1 << 16) /* Bit 16: AES Cryptographic module reset */
|
||||
#define RCC_AHB2RSTR_RNGRST (1 << 18) /* Bit 6: Random number generator module reset */
|
||||
#define RCC_AHB2RSTR_HASHRST (1 << 17) /* Bit 17: HASH module reset */
|
||||
#define RCC_AHB2RSTR_RNGRST (1 << 18) /* Bit 18: Random number generator module reset */
|
||||
|
||||
/* AHB3 peripheral reset register */
|
||||
|
||||
@ -419,7 +430,9 @@
|
||||
#define RCC_APB1RSTR1_I2C1RST (1 << 21) /* Bit 21: I2C1 reset */
|
||||
#define RCC_APB1RSTR1_I2C2RST (1 << 22) /* Bit 22: I2C2 reset */
|
||||
#define RCC_APB1RSTR1_I2C3RST (1 << 23) /* Bit 23: I2C3 reset */
|
||||
#define RCC_APB1RSTR1_CRSRST (1 << 24) /* Bit 24: CRS reset */
|
||||
#define RCC_APB1RSTR1_CAN1RST (1 << 25) /* Bit 25: CAN1 reset */
|
||||
#define RCC_APB1RSTR1_CAN2RST (1 << 26) /* Bit 26: CAN2 reset */
|
||||
#define RCC_APB1RSTR1_PWRRST (1 << 28) /* Bit 28: Power interface reset */
|
||||
#define RCC_APB1RSTR1_DAC1RST (1 << 29) /* Bit 29: DAC1 reset */
|
||||
#define RCC_APB1RSTR1_OPAMPRST (1 << 30) /* Bit 30: OPAMP reset */
|
||||
@ -428,6 +441,7 @@
|
||||
/* APB1 Peripheral reset register 2 */
|
||||
|
||||
#define RCC_APB1RSTR2_LPUART1RST (1 << 0) /* Bit 0: Low-power UART 1 reset */
|
||||
#define RCC_APB1RSTR2_I2C4RST (1 << 1) /* Bit 1: I2C4 reset */
|
||||
#define RCC_APB1RSTR2_SWPMI1RST (1 << 2) /* Bit 2: Single Wire Protocol reset */
|
||||
#define RCC_APB1RSTR2_LPTIM2RST (1 << 5) /* Bit 5: Low-power Timer 2 reset */
|
||||
|
||||
@ -453,6 +467,7 @@
|
||||
#define RCC_AHB1ENR_FLASHEN (1 << 8) /* Bit 8: Flash memory interface enable */
|
||||
#define RCC_AHB1ENR_CRCEN (1 << 12) /* Bit 12: CRC enable */
|
||||
#define RCC_AHB1ENR_TSCEN (1 << 16) /* Bit 16: Touch Sensing Controller enable */
|
||||
#define RCC_AHB1ENR_DMA2DEN (1 << 17) /* Bit 17: DMA2D enable */
|
||||
|
||||
/* AHB2 Peripheral Clock enable register */
|
||||
|
||||
@ -464,9 +479,12 @@
|
||||
#define RCC_AHB2ENR_GPIOFEN (1 << 5) /* Bit 5: IO port F enable */
|
||||
#define RCC_AHB2ENR_GPIOGEN (1 << 6) /* Bit 6: IO port G enable */
|
||||
#define RCC_AHB2ENR_GPIOHEN (1 << 7) /* Bit 7: IO port H enable */
|
||||
#define RCC_AHB2ENR_GPIOIEN (1 << 8) /* Bit 8: IO port I enable */
|
||||
#define RCC_AHB2ENR_OTGFSEN (1 << 12) /* Bit 12: USB OTG FS module enable */
|
||||
#define RCC_AHB2ENR_ADCEN (1 << 13) /* Bit 13: ADC interface enable (common to all ADCs) */
|
||||
#define RCC_AHB2ENR_DCMIEN (1 << 14) /* Bit 14: DCMI interface enable */
|
||||
#define RCC_AHB2ENR_AESEN (1 << 16) /* Bit 16: AES Cryptographic module enable */
|
||||
#define RCC_AHB2ENR_HASHEN (1 << 17) /* Bit 17: HASH module enable */
|
||||
#define RCC_AHB2ENR_RNGEN (1 << 18) /* Bit 18: Random number generator module enable */
|
||||
|
||||
/* AHB3 Peripheral Clock enable register */
|
||||
@ -474,7 +492,7 @@
|
||||
#define RCC_AHB3ENR_FSMCEN (1 << 0) /* Bit 0: Flexible static memory controller module enable */
|
||||
#define RCC_AHB3ENR_QSPIEN (1 << 8) /* Bit 8: Quad SPI module enable */
|
||||
|
||||
/* APB1 Peripheral Clock enable register 1*/
|
||||
/* APB1 Peripheral Clock enable register 1 */
|
||||
|
||||
#define RCC_APB1ENR1_TIM2EN (1 << 0) /* Bit 0: TIM2 enable */
|
||||
#define RCC_APB1ENR1_TIM3EN (1 << 1) /* Bit 1: TIM3 enable */
|
||||
@ -483,6 +501,7 @@
|
||||
#define RCC_APB1ENR1_TIM6EN (1 << 4) /* Bit 4: TIM6 enable */
|
||||
#define RCC_APB1ENR1_TIM7EN (1 << 5) /* Bit 5: TIM7 enable */
|
||||
#define RCC_APB1ENR1_LCDEN (1 << 9) /* Bit 9: LCD controller enable */
|
||||
#define RCC_APB1ENR1_RTCAPBEN (1 << 10) /* Bit 10: RTC APB clock enable */
|
||||
#define RCC_APB1ENR1_WWDGEN (1 << 11) /* Bit 11: Windowed Watchdog enable */
|
||||
#define RCC_APB1ENR1_SPI2EN (1 << 14) /* Bit 14: SPI2 enable */
|
||||
#define RCC_APB1ENR1_SPI3EN (1 << 15) /* Bit 15: SPI3 enable */
|
||||
@ -493,15 +512,18 @@
|
||||
#define RCC_APB1ENR1_I2C1EN (1 << 21) /* Bit 21: I2C1 enable */
|
||||
#define RCC_APB1ENR1_I2C2EN (1 << 22) /* Bit 22: I2C2 enable */
|
||||
#define RCC_APB1ENR1_I2C3EN (1 << 23) /* Bit 23: I2C3 enable */
|
||||
#define RCC_APB1ENR1_CRSEN (1 << 24) /* Bit 24: CRSEN enable */
|
||||
#define RCC_APB1ENR1_CAN1EN (1 << 25) /* Bit 25: CAN1 enable */
|
||||
#define RCC_APB1ENR1_CAN2EN (1 << 26) /* Bit 26: CAN2 enable */
|
||||
#define RCC_APB1ENR1_PWREN (1 << 28) /* Bit 28: Power interface enable */
|
||||
#define RCC_APB1ENR1_DAC1EN (1 << 29) /* Bit 29: DAC1 enable */
|
||||
#define RCC_APB1ENR1_OPAMPEN (1 << 30) /* Bit 30: OPAMP enable */
|
||||
#define RCC_APB1ENR1_LPTIM1EN (1 << 31) /* Bit 31: Low-power Timer 1 enable */
|
||||
|
||||
/* APB1 Peripheral Clock enable register 2*/
|
||||
/* APB1 Peripheral Clock enable register 2 */
|
||||
|
||||
#define RCC_APB1ENR2_LPUART1EN (1 << 0) /* Bit 0: Low-power UART 1 enable */
|
||||
#define RCC_APB1ENR2_I2C4EN (1 << 1) /* Bit 1: I2C4 enable */
|
||||
#define RCC_APB1ENR2_SWPMI1EN (1 << 2) /* Bit 2: Single Wire Protocol enable */
|
||||
#define RCC_APB1ENR2_LPTIM2EN (1 << 5) /* Bit 5: Low-power Timer 2 enable */
|
||||
|
||||
@ -529,6 +551,7 @@
|
||||
#define RCC_AHB1SMENR_SRAM1SMEN (1 << 9) /* Bit 9: SRAM1 enable during Sleep mode */
|
||||
#define RCC_AHB1SMENR_CRCLPSMEN (1 << 12) /* Bit 12: CRC enable during Sleep mode */
|
||||
#define RCC_AHB1SMENR_TSCLPSMEN (1 << 16) /* Bit 16: Touch Sensing Controller enable during Sleep mode */
|
||||
#define RCC_AHB1SMENR_DMA2DSMEN (1 << 17) /* Bit 17: DMA2D enable during Sleep mode */
|
||||
|
||||
/* RCC AHB2 low power mode peripheral clock enable register */
|
||||
|
||||
@ -540,18 +563,21 @@
|
||||
#define RCC_AHB2SMENR_GPIOFSMEN (1 << 5) /* Bit 5: IO port F enable during Sleep mode */
|
||||
#define RCC_AHB2SMENR_GPIOGSMEN (1 << 6) /* Bit 6: IO port G enable during Sleep mode */
|
||||
#define RCC_AHB2SMENR_GPIOHSMEN (1 << 7) /* Bit 7: IO port H enable during Sleep mode */
|
||||
#define RCC_AHB2SMENR_GPIOISMEN (1 << 8) /* Bit 8: IO port I enable during Sleep mode */
|
||||
#define RCC_AHB2SMENR_SRAM2SMEN (1 << 9) /* Bit 9: SRAM2 enable during Sleep mode */
|
||||
#define RCC_AHB2SMENR_OTGFSSMEN (1 << 12) /* Bit 12: USB OTG FS module enable during Sleep mode */
|
||||
#define RCC_AHB2SMENR_ADCSMEN (1 << 13) /* Bit 13: ADC interface enable during Sleep mode (common to all ADCs) */
|
||||
#define RCC_AHB2SMENR_DCMISMEN (1 << 14) /* Bit 14: DCMI interface enable during Sleep mode */
|
||||
#define RCC_AHB2SMENR_AESSMEN (1 << 16) /* Bit 16: AES Cryptographic module enable during Sleep mode */
|
||||
#define RCC_AHB2SMENR_RNGSMEN (1 << 18) /* Bit 6: Random number generator module enable during Sleep mode */
|
||||
#define RCC_AHB2SMENR_HASHSMEN (1 << 17) /* Bit 17: HASH module enable during Sleep mode */
|
||||
#define RCC_AHB2SMENR_RNGSMEN (1 << 18) /* Bit 18: Random number generator module enable during Sleep mode */
|
||||
|
||||
/* RCC AHB3 low power mode peripheral clock enable register */
|
||||
|
||||
#define RCC_AHB3SMENR_FSMCSMEN (1 << 0) /* Bit 0: Flexible static memory controller module enable during Sleep mode */
|
||||
#define RCC_AHB3SMENR_QSPISMEN (1 << 8) /* Bit 8: Quad SPI module enable during Sleep mode */
|
||||
|
||||
/* RCC APB1 low power modeperipheral clock enable register 1 */
|
||||
/* RCC APB1 low power mode peripheral clock enable register 1 */
|
||||
|
||||
#define RCC_APB1SMENR1_TIM2SMEN (1 << 0) /* Bit 0: TIM2 enable during Sleep mode */
|
||||
#define RCC_APB1SMENR1_TIM3SMEN (1 << 1) /* Bit 1: TIM3 enable during Sleep mode */
|
||||
@ -560,6 +586,7 @@
|
||||
#define RCC_APB1SMENR1_TIM6SMEN (1 << 4) /* Bit 4: TIM6 enable during Sleep mode */
|
||||
#define RCC_APB1SMENR1_TIM7SMEN (1 << 5) /* Bit 5: TIM7 enable during Sleep mode */
|
||||
#define RCC_APB1SMENR1_LCDSMEN (1 << 9) /* Bit 9: LCD controller enable during Sleep mode */
|
||||
#define RCC_APB1SMENR1_RTCAPBSMEN (1 << 10) /* Bit 10: RTC APB clock enable during Sleep mode */
|
||||
#define RCC_APB1SMENR1_WWDGSMEN (1 << 11) /* Bit 11: Windowed Watchdog enable during Sleep mode */
|
||||
#define RCC_APB1SMENR1_SPI2SMEN (1 << 14) /* Bit 14: SPI2 enable during Sleep mode */
|
||||
#define RCC_APB1SMENR1_SPI3SMEN (1 << 15) /* Bit 15: SPI3 enable during Sleep mode */
|
||||
@ -570,7 +597,9 @@
|
||||
#define RCC_APB1SMENR1_I2C1SMEN (1 << 21) /* Bit 21: I2C1 enable during Sleep mode */
|
||||
#define RCC_APB1SMENR1_I2C2SMEN (1 << 22) /* Bit 22: I2C2 enable during Sleep mode */
|
||||
#define RCC_APB1SMENR1_I2C3SMEN (1 << 23) /* Bit 23: I2C3 enable during Sleep mode */
|
||||
#define RCC_APB1SMENR1_CRSSMEN (1 << 24) /* Bit 24: CRS enable during Sleep mode */
|
||||
#define RCC_APB1SMENR1_CAN1SMEN (1 << 25) /* Bit 25: CAN1 enable during Sleep mode */
|
||||
#define RCC_APB1SMENR1_CAN2SMEN (1 << 26) /* Bit 26: CAN2 enable during Sleep mode */
|
||||
#define RCC_APB1SMENR1_PWRSMEN (1 << 28) /* Bit 28: Power interface enable during Sleep mode */
|
||||
#define RCC_APB1SMENR1_DAC1SMEN (1 << 29) /* Bit 29: DAC1 enable during Sleep mode */
|
||||
#define RCC_APB1SMENR1_OPAMPSMEN (1 << 30) /* Bit 30: OPAMP enable during Sleep mode */
|
||||
@ -579,6 +608,7 @@
|
||||
/* RCC APB1 low power modeperipheral clock enable register 2 */
|
||||
|
||||
#define RCC_APB1SMENR2_LPUART1SMEN (1 << 0) /* Bit 0: Low-power UART 1 enable during Sleep mode */
|
||||
#define RCC_APB1SMENR2_I2C4SMEN (1 << 1) /* Bit 1: I2C4 enable during Sleep mode */
|
||||
#define RCC_APB1SMENR2_SWPMI1SMEN (1 << 2) /* Bit 2: Single Wire Protocol enable during Sleep mode */
|
||||
#define RCC_APB1SMENR2_LPTIM2SMEN (1 << 5) /* Bit 5: Low-power Timer 2 enable during Sleep mode */
|
||||
|
||||
@ -761,5 +791,21 @@
|
||||
#define RCC_CSR_WWDGRSTF (1 << 30) /* Bit 30: Window watchdog reset flag */
|
||||
#define RCC_CSR_LPWRRSTF (1 << 31) /* Bit 31: Low-Power reset flag */
|
||||
|
||||
#endif /* CONFIG_STM32L4_STM32L476XX || CONFIG_STM32L4_STM32L486XX */
|
||||
#endif /* __ARCH_ARM_SRC_STM32L4_CHIP_STM32F42XXX_RCC_H */
|
||||
/* Clock recovery RC register (only on STM32L496xx/4A6xx) */
|
||||
|
||||
#define RCC_CRRCR_HSI48CAL_SHIFT 7
|
||||
# define RCC_CRRCR_HSI48CAL_MASK (0x01ff << RCC_CRRCR_HSI48CAL_SHIFT) /* HSI48 clock calibration */
|
||||
|
||||
#define RCC_CRRCR_HSI48ON (1 << 0) /* Bit 0: HSI48 clock enable */
|
||||
#define RCC_CRRCR_HSI48RDY (1 << 1) /* Bit 1: HSI48 clock ready flag */
|
||||
|
||||
/* Peripheral Independent Clock Configuration 2 register (only on STM32L496xx/4A6xx) */
|
||||
|
||||
#define RCC_CCIPR2_I2C4SEL_SHIFT (0)
|
||||
#define RCC_CCIPR2_I2C4SEL_MASK (3 << RCC_CCIPR2_I2C4SEL_SHIFT)
|
||||
# define RCC_CCIPR2_I2C4SEL_PCLK (0 << RCC_CCIPR2_I2C4SEL_SHIFT)
|
||||
# define RCC_CCIPR2_I2C4SEL_SYSCLK (1 << RCC_CCIPR2_I2C4SEL_SHIFT)
|
||||
# define RCC_CCIPR2_I2C4SEL_HSI (2 << RCC_CCIPR2_I2C4SEL_SHIFT)
|
||||
|
||||
#endif /* CONFIG_STM32L4_STM32L476XX || CONFIG_STM32L4_STM32L486XX || CONFIG_STM32L4_STM32L496XX */
|
||||
#endif /* __ARCH_ARM_SRC_STM32L4_CHIP_STM32L4X6XX_RCC_H */
|
||||
|
@ -33,8 +33,8 @@
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
#ifndef __ARCH_ARM_SRC_STM32L4_STM32L4_RRC_H
|
||||
#define __ARCH_ARM_SRC_STM32L4_STM32L4_RRC_H
|
||||
#ifndef __ARCH_ARM_SRC_STM32L4_STM32L4_RCC_H
|
||||
#define __ARCH_ARM_SRC_STM32L4_STM32L4_RCC_H
|
||||
|
||||
/************************************************************************************
|
||||
* Included Files
|
||||
@ -187,11 +187,7 @@ void stm32l4_clockenable(void);
|
||||
* Name: stm32l4_rcc_enablelse
|
||||
*
|
||||
* Description:
|
||||
* Enable the External Low-Speed (LSE) Oscillator and, if the RTC is
|
||||
* configured, setup the LSE as the RTC clock source, and enable the RTC.
|
||||
*
|
||||
* For the STM32L15X family, this will also select the LSE as the clock source of
|
||||
* the LCD.
|
||||
* Enable the External Low-Speed (LSE) Oscillator.
|
||||
*
|
||||
* Input Parameters:
|
||||
* None
|
||||
|
@ -159,6 +159,12 @@ static inline void rcc_enableahb1(void)
|
||||
regval |= RCC_AHB1ENR_TSCEN;
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_STM32L4_DMA2D
|
||||
/* DMA2D clock enable */
|
||||
|
||||
regval |= RCC_AHB1ENR_DMA2DEN;
|
||||
#endif
|
||||
|
||||
putreg32(regval, STM32L4_RCC_AHB1ENR); /* Enable peripherals */
|
||||
}
|
||||
|
||||
@ -220,12 +226,24 @@ static inline void rcc_enableahb2(void)
|
||||
regval |= RCC_AHB2ENR_ADCEN;
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_STM32L4_DCMI
|
||||
/* Digital Camera interfaces clock enable */
|
||||
|
||||
regval |= RCC_AHB2ENR_DCMIEN;
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_STM32L4_AES
|
||||
/* Cryptographic modules clock enable */
|
||||
|
||||
regval |= RCC_AHB2ENR_AESEN;
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_STM32L4_HASH
|
||||
/* HASH module clock enable */
|
||||
|
||||
regval |= RCC_AHB2ENR_HASHEN;
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_STM32L4_RNG
|
||||
/* Random number generator clock enable */
|
||||
|
||||
@ -389,6 +407,12 @@ static inline void rcc_enableapb1(void)
|
||||
regval |= RCC_APB1ENR1_CAN1EN;
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_STM32L4_CAN2
|
||||
/* CAN 2 clock enable */
|
||||
|
||||
regval |= RCC_APB1ENR1_CAN2EN;
|
||||
#endif
|
||||
|
||||
/* Power interface clock enable. The PWR block is always enabled so that
|
||||
* we can set the internal voltage regulator as required.
|
||||
*/
|
||||
@ -425,6 +449,12 @@ static inline void rcc_enableapb1(void)
|
||||
regval |= RCC_APB1ENR2_LPUART1EN;
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_STM32L4_I2C4
|
||||
/* I2C4 clock enable */
|
||||
|
||||
regval |= RCC_APB1ENR2_I2C4EN;
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_STM32L4_SWPMI
|
||||
/* Single-wire protocol master clock enable */
|
||||
|
||||
@ -889,7 +919,7 @@ static void stm32l4_stdclockconfig(void)
|
||||
#endif
|
||||
|
||||
/****************************************************************************
|
||||
* Name: rcc_enableperiphals
|
||||
* Name: rcc_enableperipherals
|
||||
****************************************************************************/
|
||||
|
||||
static inline void rcc_enableperipherals(void)
|
||||
|
@ -126,7 +126,7 @@ static int elf_symname(FAR struct elf_loadinfo_s *loadinfo,
|
||||
/* Read that number of bytes into the array */
|
||||
|
||||
buffer = &loadinfo->iobuffer[bytesread];
|
||||
ret = elf_read(loadinfo, buffer, readlen, offset);
|
||||
ret = elf_read(loadinfo, buffer, readlen, offset + bytesread);
|
||||
if (ret < 0)
|
||||
{
|
||||
berr("elf_read failed: %d\n", ret);
|
||||
|
@ -8,12 +8,42 @@ Nucleo-F072RB README
|
||||
Contents
|
||||
========
|
||||
|
||||
- Status
|
||||
- Nucleo-64 Boards
|
||||
- LEDs
|
||||
- Buttons
|
||||
- Serial Console
|
||||
- Configurations
|
||||
|
||||
Status
|
||||
======
|
||||
2017-04-27: There are many problems. On start up, I have to reset
|
||||
several times before I get NSH prompt (or parts of it). Apparently the
|
||||
STM32 is either hanging (perhaps in clockconfig()) or perhaps it has
|
||||
taken a hard fault before it is able to generate debug output?
|
||||
|
||||
There are many hardfaults during initial serial output. This change
|
||||
seems to eliminate those hardfaults:
|
||||
|
||||
@@ -2163,7 +2163,7 @@ static void stm32f0serial_txint(FAR struct uart_dev_s *dev, bool enable)
|
||||
* interrupts disabled (note this may recurse).
|
||||
*/
|
||||
|
||||
- uart_xmitchars(dev);
|
||||
+// uart_xmitchars(dev);
|
||||
#endif
|
||||
}
|
||||
else
|
||||
|
||||
Which implies that the hardfaults are due to runaway recursion in the
|
||||
serial driver? This suggest some error in either determining when there
|
||||
is TX data available or in disabling TX interrupts.
|
||||
|
||||
But this not a solution. Even without the hard faults, it may hang
|
||||
attempting to output the NSH greeting and prompt or hang unable to
|
||||
receive input. These symptoms suggest some issue with TX and RX
|
||||
interrupt handling.
|
||||
|
||||
Nucleo-64 Boards
|
||||
================
|
||||
|
||||
|
@ -47,7 +47,6 @@
|
||||
|
||||
#include <nuttx/irq.h>
|
||||
#include <nuttx/spi/spi.h>
|
||||
#include <nuttx/wireless/wireless.h>
|
||||
#include <nuttx/wireless/cc3000.h>
|
||||
#include <nuttx/wireless/cc3000/include/cc3000_upif.h>
|
||||
|
||||
|
@ -47,7 +47,6 @@
|
||||
|
||||
#include <nuttx/irq.h>
|
||||
#include <nuttx/spi/spi.h>
|
||||
#include <nuttx/wireless/wireless.h>
|
||||
#include <nuttx/wireless/cc3000.h>
|
||||
#include <nuttx/wireless/cc3000/include/cc3000_upif.h>
|
||||
|
||||
|
@ -47,7 +47,6 @@
|
||||
|
||||
#include <nuttx/irq.h>
|
||||
#include <nuttx/spi/spi.h>
|
||||
#include <nuttx/wireless/wireless.h>
|
||||
#include <nuttx/wireless/cc3000.h>
|
||||
#include <nuttx/wireless/cc3000/include/cc3000_upif.h>
|
||||
|
||||
|
@ -73,7 +73,7 @@
|
||||
#include <nuttx/fs/fs.h>
|
||||
#include <nuttx/spi/spi.h>
|
||||
|
||||
#include <nuttx/wireless/wireless.h>
|
||||
#include <nuttx/wireless/ioctl.h>
|
||||
#include <nuttx/wireless/cc3000.h>
|
||||
#include <nuttx/wireless/cc3000/include/cc3000_upif.h>
|
||||
#include <nuttx/wireless/cc3000/cc3000_common.h>
|
||||
|
@ -53,9 +53,10 @@
|
||||
#include <stdint.h>
|
||||
#include <mqueue.h>
|
||||
#include <pthread.h>
|
||||
|
||||
#include <nuttx/spi/spi.h>
|
||||
#include <nuttx/irq.h>
|
||||
#include <nuttx/wireless/wireless.h>
|
||||
#include <nuttx/wireless/ioctl.h>
|
||||
#include <nuttx/wireless/cc3000.h>
|
||||
#include <nuttx/wireless/cc3000/cc3000_common.h>
|
||||
|
||||
|
@ -43,7 +43,6 @@
|
||||
#include <nuttx/config.h>
|
||||
#include <nuttx/spi/spi.h>
|
||||
#include <nuttx/irq.h>
|
||||
#include <nuttx/wireless/wireless.h>
|
||||
|
||||
#include <stdint.h>
|
||||
#include <stdbool.h>
|
||||
|
@ -68,27 +68,28 @@
|
||||
#define _QEIOCBASE (0x0f00) /* Quadrature encoder ioctl commands */
|
||||
#define _AUDIOIOCBASE (0x1000) /* Audio ioctl commands */
|
||||
#define _SLCDIOCBASE (0x1100) /* Segment LCD ioctl commands */
|
||||
#define _WLIOCBASE (0x1200) /* Wireless modules ioctl commands */
|
||||
#define _CFGDIOCBASE (0x1300) /* Config Data device (app config) ioctl commands */
|
||||
#define _TCIOCBASE (0x1400) /* Timer ioctl commands */
|
||||
#define _DJOYBASE (0x1500) /* Discrete joystick ioctl commands */
|
||||
#define _AJOYBASE (0x1600) /* Analog joystick ioctl commands */
|
||||
#define _PIPEBASE (0x1700) /* FIFO/pipe ioctl commands */
|
||||
#define _RTCBASE (0x1800) /* RTC ioctl commands */
|
||||
#define _RELAYBASE (0x1900) /* Relay devices ioctl commands */
|
||||
#define _CANBASE (0x1a00) /* CAN ioctl commands */
|
||||
#define _BTNBASE (0x1b00) /* Button ioctl commands */
|
||||
#define _ULEDBASE (0x1c00) /* User LED ioctl commands */
|
||||
#define _ZCBASE (0x1d00) /* Zero Cross ioctl commands */
|
||||
#define _LOOPBASE (0x1e00) /* Loop device commands */
|
||||
#define _MODEMBASE (0x1f00) /* Modem ioctl commands */
|
||||
#define _I2CBASE (0x2000) /* I2C driver commands */
|
||||
#define _SPIBASE (0x2100) /* SPI driver commands */
|
||||
#define _GPIOBASE (0x2200) /* GPIO driver commands */
|
||||
#define _CLIOCBASE (0x2300) /* Contactless modules ioctl commands */
|
||||
#define _USBCBASE (0x2400) /* USB-C controller ioctl commands */
|
||||
#define _MAC802154BASE (0x2500) /* 802.15.4 MAC ioctl commands */
|
||||
#define _PHY802154BASE (0x2600) /* 802.15.4 Radio ioctl commands */
|
||||
#define _WLIOCBASE (0x1200) /* Wireless modules ioctl network commands */
|
||||
#define _WLCIOCBASE (0x1300) /* Wireless modules ioctl character driver commands */
|
||||
#define _CFGDIOCBASE (0x1400) /* Config Data device (app config) ioctl commands */
|
||||
#define _TCIOCBASE (0x1500) /* Timer ioctl commands */
|
||||
#define _DJOYBASE (0x1600) /* Discrete joystick ioctl commands */
|
||||
#define _AJOYBASE (0x1700) /* Analog joystick ioctl commands */
|
||||
#define _PIPEBASE (0x1800) /* FIFO/pipe ioctl commands */
|
||||
#define _RTCBASE (0x1900) /* RTC ioctl commands */
|
||||
#define _RELAYBASE (0x1a00) /* Relay devices ioctl commands */
|
||||
#define _CANBASE (0x1b00) /* CAN ioctl commands */
|
||||
#define _BTNBASE (0x1c00) /* Button ioctl commands */
|
||||
#define _ULEDBASE (0x1d00) /* User LED ioctl commands */
|
||||
#define _ZCBASE (0x1e00) /* Zero Cross ioctl commands */
|
||||
#define _LOOPBASE (0x1f00) /* Loop device commands */
|
||||
#define _MODEMBASE (0x2000) /* Modem ioctl commands */
|
||||
#define _I2CBASE (0x2100) /* I2C driver commands */
|
||||
#define _SPIBASE (0x2200) /* SPI driver commands */
|
||||
#define _GPIOBASE (0x2300) /* GPIO driver commands */
|
||||
#define _CLIOCBASE (0x2400) /* Contactless modules ioctl commands */
|
||||
#define _USBCBASE (0x2500) /* USB-C controller ioctl commands */
|
||||
#define _MAC802154BASE (0x2600) /* 802.15.4 MAC ioctl commands */
|
||||
#define _PHY802154BASE (0x2700) /* 802.15.4 Radio ioctl commands */
|
||||
|
||||
/* boardctl() commands share the same number space */
|
||||
|
||||
@ -296,12 +297,18 @@
|
||||
#define _SLCDIOCVALID(c) (_IOC_TYPE(c)==_SLCDIOCBASE)
|
||||
#define _SLCDIOC(nr) _IOC(_SLCDIOCBASE,nr)
|
||||
|
||||
/* Wireless driver ioctl definitions ****************************************/
|
||||
/* Wireless driver networki ioctl definitions *******************************/
|
||||
/* (see nuttx/include/wireless/wireless.h */
|
||||
|
||||
#define _WLIOCVALID(c) (_IOC_TYPE(c)==_WLIOCBASE)
|
||||
#define _WLIOC(nr) _IOC(_WLIOCBASE,nr)
|
||||
|
||||
/* Wireless driver character driver ioctl definitions ***********************/
|
||||
/* (see nuttx/include/wireless/ioctl.h */
|
||||
|
||||
#define _WLCIOCVALID(c) (_IOC_TYPE(c)==_WLCIOCBASE)
|
||||
#define _WLCIOC(nr) _IOC(_WLCIOCBASE,nr)
|
||||
|
||||
/* Application Config Data driver ioctl definitions *************************/
|
||||
/* (see nuttx/include/configdata.h */
|
||||
|
||||
|
@ -50,7 +50,7 @@
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <sys/types.h>
|
||||
#include <nuttx/wireless/wireless.h>
|
||||
#include <nuttx/wireless/ioctl.h>
|
||||
|
||||
/****************************************************************************
|
||||
* Pre-processor Definitions
|
||||
|
@ -54,7 +54,6 @@
|
||||
#include <nuttx/config.h>
|
||||
#include <nuttx/spi/spi.h>
|
||||
#include <nuttx/irq.h>
|
||||
#include <nuttx/wireless/wireless.h>
|
||||
|
||||
#if defined(CONFIG_DRIVERS_WIRELESS) && defined(CONFIG_WL_CC3000)
|
||||
|
||||
|
108
include/nuttx/wireless/ioctl.h
Normal file
108
include/nuttx/wireless/ioctl.h
Normal file
@ -0,0 +1,108 @@
|
||||
/************************************************************************************
|
||||
* include/nuttx/wireless/ioctl.h
|
||||
* Wireless character driver IOCTL commands
|
||||
*
|
||||
* Copyright (C) 2011-2013, 2017 Gregory Nutt. All rights reserved.
|
||||
* Author: Laurent Latil <gnutt@nuttx.org>
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
/* This file includes common definitions to be used in all wireless character drivers
|
||||
* (when applicable).
|
||||
*/
|
||||
|
||||
#ifndef __INCLUDE_NUTTX_WIRELESS_IOCTL_H
|
||||
#define __INCLUDE_NUTTX_WIRELESS_IOCTL_H
|
||||
|
||||
/************************************************************************************
|
||||
* Included Files
|
||||
************************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <nuttx/fs/ioctl.h>
|
||||
|
||||
#ifdef CONFIG_DRIVERS_WIRELESS
|
||||
|
||||
/************************************************************************************
|
||||
* Pre-processor Definitions
|
||||
************************************************************************************/
|
||||
|
||||
/* Character Driver IOCTL commands *************************************************/
|
||||
/* Non-compatible, NuttX only IOCTL definitions for use with low-level wireless
|
||||
* drivers that are accessed via a character device. Use of these IOCTL commands
|
||||
* requires a file descriptor created by the open() interface.
|
||||
*/
|
||||
|
||||
#define WLIOC_SETRADIOFREQ _WLCIOC(0x0001) /* arg: Pointer to uint32_t, frequency
|
||||
* value (in Mhz) */
|
||||
#define WLIOC_GETRADIOFREQ _WLCIOC(0x0002) /* arg: Pointer to uint32_t, frequency
|
||||
* value (in Mhz) */
|
||||
#define WLIOC_SETADDR _WLCIOC(0x0003) /* arg: Pointer to address value, format
|
||||
* of the address is driver specific */
|
||||
#define WLIOC_GETADDR _WLCIOC(0x0004) /* arg: Pointer to address value, format
|
||||
* of the address is driver specific */
|
||||
#define WLIOC_SETTXPOWER _WLCIOC(0x0005) /* arg: Pointer to int32_t, output power
|
||||
* (in dBm) */
|
||||
#define WLIOC_GETTXPOWER _WLCIOC(0x0006) /* arg: Pointer to int32_t, output power
|
||||
* (in dBm) */
|
||||
|
||||
/* Device-specific IOCTL commands **************************************************/
|
||||
|
||||
#define WL_FIRST 0x0001 /* First common command */
|
||||
#define WL_NCMDS 0x0006 /* Number of common commands */
|
||||
|
||||
/* User defined ioctl commands are also supported. These will be forwarded
|
||||
* by the upper-half QE driver to the lower-half QE driver via the ioctl()
|
||||
* method fo the QE lower-half interface. However, the lower-half driver
|
||||
* must reserve a block of commands as follows in order prevent IOCTL
|
||||
* command numbers from overlapping.
|
||||
*/
|
||||
|
||||
/* See include/nuttx/wireless/cc3000.h */
|
||||
|
||||
#define CC3000_FIRST (WL_FIRST + WL_NCMDS)
|
||||
#define CC3000_NCMDS 7
|
||||
|
||||
/* See include/nuttx/wireless/nrf24l01.h */
|
||||
|
||||
#define NRF24L01_FIRST (CC3000_FIRST + CC3000_NCMDS)
|
||||
#define NRF24L01_NCMDS 14
|
||||
|
||||
/* See include/nuttx/wireless/ieee802154/ieee802154_ioctl.h */
|
||||
|
||||
#define IEEE802154_FIRST (NRF24L01_FIRST + NRF24L01_NCMDS)
|
||||
#define IEEE802154_NCMDS 2
|
||||
|
||||
/************************************************************************************
|
||||
* Public Types
|
||||
************************************************************************************/
|
||||
|
||||
#endif /* CONFIG_DRIVERS_WIRELESS */
|
||||
#endif /* __INCLUDE_NUTTX_WIRELESS_IOCTL_H */
|
@ -43,7 +43,7 @@
|
||||
#include <nuttx/config.h>
|
||||
#include <nuttx/spi/spi.h>
|
||||
#include <nuttx/irq.h>
|
||||
#include <nuttx/wireless/wireless.h>
|
||||
#include <nuttx/wireless/ioctl.h>
|
||||
|
||||
#include <stdint.h>
|
||||
#include <stdbool.h>
|
||||
|
@ -1,5 +1,6 @@
|
||||
/************************************************************************************
|
||||
* include/nuttx/wireless/wireless.h
|
||||
* Wireless network IOCTL commands
|
||||
*
|
||||
* Copyright (C) 2011-2013, 2017 Gregory Nutt. All rights reserved.
|
||||
* Author: Laurent Latil <gnutt@nuttx.org>
|
||||
@ -33,7 +34,7 @@
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
/* This file includes common definitions to be used in all wireless drivers
|
||||
/* This file includes common definitions to be used in all wireless network drivers
|
||||
* (when applicable).
|
||||
*/
|
||||
|
||||
@ -153,49 +154,11 @@
|
||||
|
||||
#define SIOCSIWPMKSA _WLIOC(0x0032) /* PMKSA cache operation */
|
||||
|
||||
#define WL_FIRSTCHAR 0x0033
|
||||
#define WL_NNETCMDS 0x0032
|
||||
/* Device-specific network IOCTL commands ******************************************/
|
||||
|
||||
/* Character Driver IOCTL commands *************************************************/
|
||||
/* Non-compatible, NuttX only IOCTL definitions for use with low-level wireless
|
||||
* drivers that are accessed via a character device. Use of these IOCTL commands
|
||||
* requires a file descriptor created by the open() interface.
|
||||
*/
|
||||
|
||||
#define WLIOC_SETRADIOFREQ _WLIOC(0x0033) /* arg: Pointer to uint32_t, frequency
|
||||
* value (in Mhz) */
|
||||
#define WLIOC_GETRADIOFREQ _WLIOC(0x0034) /* arg: Pointer to uint32_t, frequency
|
||||
* value (in Mhz) */
|
||||
#define WLIOC_SETADDR _WLIOC(0x0035) /* arg: Pointer to address value, format
|
||||
* of the address is driver specific */
|
||||
#define WLIOC_GETADDR _WLIOC(0x0036) /* arg: Pointer to address value, format
|
||||
* of the address is driver specific */
|
||||
#define WLIOC_SETTXPOWER _WLIOC(0x0037) /* arg: Pointer to int32_t, output power
|
||||
* (in dBm) */
|
||||
#define WLIOC_GETTXPOWER _WLIOC(0x0038) /* arg: Pointer to int32_t, output power
|
||||
* (in dBm) */
|
||||
|
||||
/* Device-specific IOCTL commands **************************************************/
|
||||
|
||||
#define WL_FIRST 0x0001 /* First common command */
|
||||
#define WL_NCMDS 0x0038 /* Number of common commands */
|
||||
|
||||
/* User defined ioctl commands are also supported. These will be forwarded
|
||||
* by the upper-half QE driver to the lower-half QE driver via the ioctl()
|
||||
* method fo the QE lower-half interface. However, the lower-half driver
|
||||
* must reserve a block of commands as follows in order prevent IOCTL
|
||||
* command numbers from overlapping.
|
||||
*/
|
||||
|
||||
/* See include/nuttx/wireless/cc3000.h */
|
||||
|
||||
#define CC3000_FIRST (WL_FIRST + WL_NCMDS)
|
||||
#define CC3000_NCMDS 7
|
||||
|
||||
/* See include/nuttx/wireless/nrf24l01.h */
|
||||
|
||||
#define NRF24L01_FIRST (CC3000_FIRST + CC3000_NCMDS)
|
||||
#define NRF24L01_NCMDS 14
|
||||
#define WL_NETFIRST 0x0001 /* First network command */
|
||||
#define WL_NNETCMDS 0x0032 /* Number of network commands */
|
||||
#define WL_USERFIRST (WL_NETFIRST + WL_NNETCMDS)
|
||||
|
||||
/* Other Common Wireless Definitions ***********************************************/
|
||||
|
||||
|
Loading…
x
Reference in New Issue
Block a user