Merged in raiden00/nuttx_h7 (pull request #836)
Initial DMA support for STM32H7 arch/arm/src/stm32h7: SPI DMA mode arch/arm/src/stm32h7/chip/stm32h7x3xx_memorymap.h: add base addresses for D1, D2 and D3 domain; use 2 bytes to specify memory region arch/arm/src/stm32h7/stm32h7x3xx_rcc.c: add D1 domain core prescaler configuration Approved-by: Gregory Nutt <gnutt@nuttx.org>
This commit is contained in:
parent
66cb78c306
commit
32086c6d8d
@ -147,6 +147,20 @@ config STM32H7_DMA2
|
||||
select STM32H7_DMA
|
||||
select ARCH_DMA
|
||||
|
||||
config STM32H7_MDMA
|
||||
bool "MDMA"
|
||||
default n
|
||||
depends on EXPERIMENTAL
|
||||
select STM32H7_DMA
|
||||
select ARCH_DMA
|
||||
|
||||
config STM32H7_BDMA
|
||||
bool "BDMA"
|
||||
default n
|
||||
depends on EXPERIMENTAL
|
||||
select STM32H7_DMA
|
||||
select ARCH_DMA
|
||||
|
||||
menu "STM32H7 I2C Selection"
|
||||
|
||||
config STM32H7_I2C1
|
||||
@ -332,6 +346,16 @@ config STM32H7_SPI_DMA
|
||||
|
||||
endmenu # "SPI Configuration"
|
||||
|
||||
config STM32H7_DMACAPABLE
|
||||
bool "Workaround non-DMA capable memory"
|
||||
depends on ARCH_DMA
|
||||
default n
|
||||
---help---
|
||||
This option enables the DMA interface stm32_dmacapable that can be
|
||||
used to check if it is possible to do DMA from the selected address.
|
||||
Drivers then may use this information to determine if they should
|
||||
attempt the DMA or fall back to a different transfer method.
|
||||
|
||||
menu "U[S]ART Configuration"
|
||||
depends on STM32H7_USART
|
||||
|
||||
|
@ -59,11 +59,10 @@
|
||||
#define STM32_FMC_BANK6 0xd0000000 /* 0xd0000000-0xdfffffff: 256Mb FMC SDRAM Bank 2 */
|
||||
#define STM32_CORTEX_BASE 0xe0000000 /* 0xe0000000-0xffffffff: 512Mb Cortex-M7 block */
|
||||
|
||||
#define STM32_REGION_MASK 0xf0000000
|
||||
#define STM32_REGION_MASK 0xff000000
|
||||
#define STM32_IS_SRAM(a) ((((uint32_t)(a)) & STM32_REGION_MASK) == STM32_SRAM_BASE)
|
||||
#define STM32_IS_EXTSRAM(a) ((((uint32_t)(a)) & STM32_REGION_MASK) == STM32_FMC_BANK1)
|
||||
|
||||
|
||||
/* Code Base Addresses **************************************************************/
|
||||
|
||||
#define STM32_ITCM_BASE 0x00000000 /* 0x00000000-0x0000ffff: ITCM */
|
||||
@ -85,14 +84,18 @@
|
||||
|
||||
/* Peripheral Base Addresses ********************************************************/
|
||||
|
||||
#define STM32_APB1_BASE 0x40000000 /* 0x40000000-0x40007fff: APB1 */
|
||||
#define STM32_APB2_BASE 0x40010000 /* 0x40010000-0x40016bff: APB2 */
|
||||
#define STM32_AHB1_BASE 0x40020000 /* 0x40020000-0x4007ffff: APB1 */
|
||||
#define STM32_AHB2_BASE 0x48020000 /* 0x50000000-0x48022bff: AHB2 */
|
||||
#define STM32_APB3_BASE 0x50000000 /* 0x60000000-0x50003fff: APB3 */
|
||||
#define STM32_AHB3_BASE 0x51000000 /* 0x51000000-0x52008fff: AHB3 */
|
||||
#define STM32_APB4_BASE 0x58000000 /* 0x60000000-0x58006bff: APB4 */
|
||||
#define STM32_AHB4_BASE 0x58020000 /* 0x58020000-0x580267ff: AHB4 */
|
||||
#define STM32_PREGION_MASK 0xff000000
|
||||
#define STM32_D2_BASE 0x40000000 /* 0x40000000-0x48022800: D2 domain */
|
||||
# define STM32_APB1_BASE 0x40000000 /* 0x40000000-0x40007fff: APB1 */
|
||||
# define STM32_APB2_BASE 0x40010000 /* 0x40010000-0x40016bff: APB2 */
|
||||
# define STM32_AHB1_BASE 0x40020000 /* 0x40020000-0x4007ffff: APB1 */
|
||||
# define STM32_AHB2_BASE 0x48020000 /* 0x50000000-0x48022bff: AHB2 */
|
||||
#define STM32_D1_BASE 0x50000000 /* 0x50000000-0x50003fff: D1 domain */
|
||||
# define STM32_APB3_BASE 0x50000000 /* 0x60000000-0x50003fff: APB3 */
|
||||
# define STM32_AHB3_BASE 0x51000000 /* 0x51000000-0x52008fff: AHB3 */
|
||||
#define STM32_D3_BASE 0x58000000 /* 0x58000000-0x580267ff: D3 domain */
|
||||
# define STM32_APB4_BASE 0x58000000 /* 0x60000000-0x58006bff: APB4 */
|
||||
# define STM32_AHB4_BASE 0x58020000 /* 0x58020000-0x580267ff: AHB4 */
|
||||
|
||||
/* APB1 Base Addresses **************************************************************/
|
||||
|
||||
|
2333
arch/arm/src/stm32h7/stm32_dma.c
Normal file
2333
arch/arm/src/stm32h7/stm32_dma.c
Normal file
File diff suppressed because it is too large
Load Diff
231
arch/arm/src/stm32h7/stm32_dma.h
Normal file
231
arch/arm/src/stm32h7/stm32_dma.h
Normal file
@ -0,0 +1,231 @@
|
||||
/************************************************************************************
|
||||
* arch/arm/src/stm32h7/stm32_dma.h
|
||||
*
|
||||
* Copyright (C) 2018 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_STM32H7_STM32_DMA_H
|
||||
#define __ARCH_ARM_SRC_STM32H7_STM32_DMA_H
|
||||
|
||||
/************************************************************************************
|
||||
* Included Files
|
||||
************************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <sys/types.h>
|
||||
|
||||
#include "chip/stm32_dma.h"
|
||||
#include "chip/stm32_dmamux.h"
|
||||
|
||||
/* These definitions provide the bit encoding of the 'status' parameter passed to the
|
||||
* DMA callback function (see dma_callback_t).
|
||||
*/
|
||||
|
||||
#define DMA_STATUS_FEIF 0 /* Stream FIFO error (ignored) */
|
||||
#define DMA_STATUS_DMEIF DMA_STREAM_DMEIF_BIT /* Stream direct mode error */
|
||||
#define DMA_STATUS_TEIF DMA_STREAM_TEIF_BIT /* Stream Transfer Error */
|
||||
#define DMA_STATUS_HTIF DMA_STREAM_HTIF_BIT /* Stream Half Transfer */
|
||||
#define DMA_STATUS_TCIF DMA_STREAM_TCIF_BIT /* Stream Transfer Complete */
|
||||
|
||||
#define DMA_STATUS_ERROR (DMA_STATUS_FEIF|DMA_STATUS_DMEIF|DMA_STATUS_TEIF)
|
||||
#define DMA_STATUS_SUCCESS (DMA_STATUS_TCIF|DMA_STATUS_HTIF)
|
||||
|
||||
/************************************************************************************
|
||||
* Public Types
|
||||
************************************************************************************/
|
||||
|
||||
/* DMA channel configuration - common for DMA1 DMA2 MDMA and BDMA */
|
||||
|
||||
struct stm32_dma_config_s
|
||||
{
|
||||
uint32_t paddr; /* Peripheral address */
|
||||
uint32_t maddr; /* Memory address */
|
||||
uint32_t cfg1; /* DMA transfer configuration 1.
|
||||
* Its function depends on DMA controller:
|
||||
* - DMA1 and DMA2 - SCR register configuration
|
||||
* - BDMA - CCR register configuration
|
||||
* - MDMA - CCR register configuration
|
||||
*/
|
||||
uint32_t cfg2; /* DMA transfer configuration 2.
|
||||
* Its function depends on DMA controller:
|
||||
* - MDMA - CTCR register configuration
|
||||
*/
|
||||
uint32_t ndata; /* Number of data to transfer */
|
||||
};
|
||||
|
||||
typedef struct stm32_dma_config_s stm32_dmacfg_t;
|
||||
|
||||
/* DMA_HANDLE Provides an opaque are reference that can be used to represent a DMA
|
||||
* a DMA stream.
|
||||
*/
|
||||
|
||||
typedef FAR void *DMA_HANDLE;
|
||||
|
||||
/* Description:
|
||||
* This is the type of the callback that is used to inform the user of the
|
||||
* completion of the DMA. NOTE: The DMA module does *NOT* perform any cache
|
||||
* operations. It is the responsibility of the DMA client to invalidate DMA
|
||||
* buffers after completion of the DMA RX operations.
|
||||
*
|
||||
* Input Parameters:
|
||||
* handle - Refers tot he DMA channel or stream
|
||||
* status - A bit encoded value that provides the completion status. See the
|
||||
* DMASTATUS_* definitions above.
|
||||
* arg - A user-provided value that was provided when stm32_dmastart() was
|
||||
* called.
|
||||
*/
|
||||
|
||||
typedef void (*dma_callback_t)(DMA_HANDLE handle, uint8_t status, void *arg);
|
||||
|
||||
/************************************************************************************
|
||||
* Public Data
|
||||
************************************************************************************/
|
||||
|
||||
#ifndef __ASSEMBLY__
|
||||
|
||||
#undef EXTERN
|
||||
#if defined(__cplusplus)
|
||||
#define EXTERN extern "C"
|
||||
extern "C"
|
||||
{
|
||||
#else
|
||||
#define EXTERN extern
|
||||
#endif
|
||||
|
||||
/************************************************************************************
|
||||
* Public Functions
|
||||
************************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: stm32_dmachannel
|
||||
*
|
||||
* Description:
|
||||
* Allocate a DMA channel. This function gives the caller mutually
|
||||
* exclusive access to the DMA channel specified by the 'dmamap' argument.
|
||||
* It is common for standard DMA (DMA1, DMA2), master DMA (MDMA) and
|
||||
* basic DMA (BDMA) controllers.
|
||||
*
|
||||
* Input Parameters:
|
||||
* dmamap - Identifies the stream/channel resource. For the STM32 H7, this
|
||||
* is a bit-encoded value as provided by the DMAMAP_* definitions
|
||||
* in chip/stm32h7xxxxxxx_dmamux.h
|
||||
*
|
||||
* Returned Value:
|
||||
* One success, this function returns a non-NULL, void* DMA channel
|
||||
* handle. NULL is returned on any failure. This function can fail only
|
||||
* if no DMA channel is available.
|
||||
*
|
||||
* Assumptions:
|
||||
* - The caller does not hold he DMA channel.
|
||||
* - The caller can wait for the DMA channel to be freed if it is no
|
||||
* available.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
DMA_HANDLE stm32_dmachannel(unsigned int dmamap);
|
||||
|
||||
/****************************************************************************
|
||||
* Name: stm32_dmafree
|
||||
*
|
||||
* Description:
|
||||
* Release a DMA channel and unmap DMAMUX if required.
|
||||
*
|
||||
* NOTE: The 'handle' used in this argument must NEVER be used again
|
||||
* until stm32_dmachannel() is called again to re-gain access to the channel.
|
||||
*
|
||||
* Returned Value:
|
||||
* None
|
||||
*
|
||||
* Assumptions:
|
||||
* - The caller holds the DMA channel.
|
||||
* - There is no DMA in progress
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
void stm32_dmafree(DMA_HANDLE handle);
|
||||
|
||||
/****************************************************************************
|
||||
* Name: stm32_dmasetup
|
||||
*
|
||||
* Description:
|
||||
* Configure DMA before using
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
void stm32_dmasetup(DMA_HANDLE handle, stm32_dmacfg_t *cfg);
|
||||
|
||||
/****************************************************************************
|
||||
* Name: stm32_dmastart
|
||||
****************************************************************************/
|
||||
|
||||
void stm32_dmastart(DMA_HANDLE handle, dma_callback_t callback, void *arg,
|
||||
bool half);
|
||||
|
||||
/****************************************************************************
|
||||
* Name: stm32_dmastop
|
||||
****************************************************************************/
|
||||
|
||||
void stm32_dmastop(DMA_HANDLE handle);
|
||||
|
||||
/****************************************************************************
|
||||
* Name: stm32_dmaresidual
|
||||
****************************************************************************/
|
||||
|
||||
size_t stm32_dmaresidual(DMA_HANDLE handle);
|
||||
|
||||
/****************************************************************************
|
||||
* Name: stm32_dmacapable
|
||||
****************************************************************************/
|
||||
|
||||
#ifdef CONFIG_STM32H7_DMACAPABLE
|
||||
bool stm32_dmacapable(DMA_HANDLE handle, stm32_dmacfg_t *cfg);
|
||||
#else
|
||||
# define stm32_dmacapable(handle, cfg) (true)
|
||||
#endif
|
||||
|
||||
/****************************************************************************
|
||||
* Name: stm32_dmadump
|
||||
****************************************************************************/
|
||||
|
||||
#ifdef CONFIG_DEBUG_DMA_INFO
|
||||
void stm32_dmadump(DMA_HANDLE handle, const char *msg);
|
||||
#else
|
||||
# define stm32_dmadump(handle,msg)
|
||||
#endif
|
||||
|
||||
#undef EXTERN
|
||||
#if defined(__cplusplus)
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif /* __ASSEMBLY__ */
|
||||
#endif /* __ARCH_ARM_SRC_STM32H7_STM32_DMA_H */
|
@ -88,6 +88,7 @@
|
||||
#include "stm32_rcc.h"
|
||||
#include "stm32_gpio.h"
|
||||
#include "stm32_spi.h"
|
||||
#include "stm32_dma.h"
|
||||
|
||||
#if defined(CONFIG_STM32H7_SPI1) || defined(CONFIG_STM32H7_SPI2) || \
|
||||
defined(CONFIG_STM32H7_SPI3) || defined(CONFIG_STM32H7_SPI4) || \
|
||||
@ -104,10 +105,6 @@
|
||||
# error "Interrupt driven SPI not yet supported"
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_STM32H7_SPI_DMA
|
||||
# error "SPI DMA not supported yet"
|
||||
#endif
|
||||
|
||||
/* Can't have both interrupt driven SPI and SPI DMA */
|
||||
|
||||
#if defined(CONFIG_STM32H7_SPI_INTERRUPTS) && defined(CONFIG_STM32H7_SPI_DMA)
|
||||
@ -200,8 +197,8 @@ struct stm32_spidev_s
|
||||
bool defertrig; /* Flag indicating that trigger should be deferred */
|
||||
bool trigarmed; /* Flag indicating that the trigger is armed */
|
||||
#endif
|
||||
uint8_t rxch; /* The RX DMA channel number */
|
||||
uint8_t txch; /* The TX DMA channel number */
|
||||
uint32_t rxch; /* The RX DMA channel number */
|
||||
uint32_t txch; /* The TX DMA channel number */
|
||||
DMA_HANDLE rxdma; /* DMA channel handle for RX transfers */
|
||||
DMA_HANDLE txdma; /* DMA channel handle for TX transfers */
|
||||
sem_t rxsem; /* Wait for RX DMA to complete */
|
||||
@ -961,6 +958,8 @@ static void spi_dmatxcallback(DMA_HANDLE handle, uint8_t isr, void *arg)
|
||||
static void spi_dmarxsetup(FAR struct stm32_spidev_s *priv, FAR void *rxbuffer,
|
||||
FAR void *rxdummy, size_t nwords)
|
||||
{
|
||||
stm32_dmacfg_t dmacfg;
|
||||
|
||||
/* 8- or 16-bit mode? */
|
||||
|
||||
if (spi_9to16bitmode(priv))
|
||||
@ -994,8 +993,13 @@ static void spi_dmarxsetup(FAR struct stm32_spidev_s *priv, FAR void *rxbuffer,
|
||||
|
||||
/* Configure the RX DMA */
|
||||
|
||||
stm32_dmasetup(priv->rxdma, priv->spibase + STM32_SPI_RXDR_OFFSET,
|
||||
(uint32_t)rxbuffer, nwords, priv->rxccr);
|
||||
dmacfg.paddr = priv->spibase + STM32_SPI_RXDR_OFFSET;
|
||||
dmacfg.maddr = (uint32_t)rxbuffer;
|
||||
dmacfg.ndata = nwords;
|
||||
dmacfg.cfg1 = priv->rxccr;
|
||||
dmacfg.cfg2 = 0;
|
||||
|
||||
stm32_dmasetup(priv->rxdma, &dmacfg);
|
||||
}
|
||||
#endif
|
||||
|
||||
@ -1011,6 +1015,8 @@ static void spi_dmarxsetup(FAR struct stm32_spidev_s *priv, FAR void *rxbuffer,
|
||||
static void spi_dmatxsetup(FAR struct stm32_spidev_s *priv, FAR const void *txbuffer,
|
||||
FAR const void *txdummy, size_t nwords)
|
||||
{
|
||||
stm32_dmacfg_t dmacfg;
|
||||
|
||||
/* 8- or 16-bit mode? */
|
||||
|
||||
if (spi_9to16bitmode(priv))
|
||||
@ -1042,10 +1048,15 @@ static void spi_dmatxsetup(FAR struct stm32_spidev_s *priv, FAR const void *txbu
|
||||
}
|
||||
}
|
||||
|
||||
dmacfg.paddr = priv->spibase + STM32_SPI_TXDR_OFFSET;
|
||||
dmacfg.maddr = (uint32_t)txbuffer;
|
||||
dmacfg.ndata = nwords;
|
||||
dmacfg.cfg1 = priv->txccr;
|
||||
dmacfg.cfg2 = 0;
|
||||
|
||||
/* Setup the TX DMA */
|
||||
|
||||
stm32_dmasetup(priv->txdma, priv->spibase + STM32_SPI_TXDR_OFFSET,
|
||||
(uint32_t)txbuffer, nwords, priv->txccr);
|
||||
stm32_dmasetup(priv->txdma, &dmacfg);
|
||||
}
|
||||
#endif
|
||||
|
||||
@ -1358,6 +1369,7 @@ static void spi_setmode(FAR struct spi_dev_s *dev, enum spi_mode_e mode)
|
||||
|
||||
spi_enable(priv, false);
|
||||
spi_modifyreg(priv, STM32_SPI_CFG1_OFFSET, 0, SPI_CFG1_RXDMAEN | SPI_CFG1_TXDMAEN);
|
||||
spi_enable(priv, true);
|
||||
#endif
|
||||
|
||||
/* Save the mode so that subsequent re-configurations will be faster */
|
||||
@ -1704,8 +1716,23 @@ static void spi_exchange(FAR struct spi_dev_s *dev, FAR const void *txbuffer,
|
||||
DEBUGASSERT(priv != NULL);
|
||||
|
||||
#ifdef CONFIG_STM32H7_DMACAPABLE
|
||||
if ((txbuffer && !stm32_dmacapable((uint32_t)txbuffer, nwords, priv->txccr)) ||
|
||||
(rxbuffer && !stm32_dmacapable((uint32_t)rxbuffer, nwords, priv->rxccr)))
|
||||
stm32_dmacfg_t dmacfg1;
|
||||
stm32_dmacfg_t dmacfg2;
|
||||
|
||||
/* TX transfer configuration */
|
||||
|
||||
dmacfg1.maddr = (uint32_t)txbuffer;
|
||||
dmacfg1.ndata = nwords;
|
||||
dmacfg1.cfg1 = priv->txccr;
|
||||
|
||||
/* RX transfer configuration */
|
||||
|
||||
dmacfg2.maddr = (uint32_t)rxbuffer;
|
||||
dmacfg2.ndata = nwords;
|
||||
dmacfg2.cfg1 = priv->rxccr;
|
||||
|
||||
if ((txbuffer && !stm32_dmacapable(priv->txdma, &dmacfg1)) ||
|
||||
(rxbuffer && !stm32_dmacapable(priv->rxdma, &dmacfg2)))
|
||||
{
|
||||
/* Unsupported memory region, fall back to non-DMA method. */
|
||||
|
||||
@ -1739,6 +1766,10 @@ static void spi_exchange(FAR struct spi_dev_s *dev, FAR const void *txbuffer,
|
||||
arch_flush_dcache((uintptr_t)txbuffer, (uintptr_t)txbuffer + buflen);
|
||||
}
|
||||
|
||||
/* REVISIT: Master transfer start */
|
||||
|
||||
spi_modifyreg(priv, STM32_SPI_CR1_OFFSET, 0, SPI_CR1_CSTART);
|
||||
|
||||
#ifdef CONFIG_SPI_TRIGGER
|
||||
/* Is deferred triggering in effect? */
|
||||
|
||||
|
@ -516,12 +516,11 @@ static void stm32_stdclockconfig(void)
|
||||
|
||||
if (timeout > 0)
|
||||
{
|
||||
|
||||
/* Set the HCLK source/divider */
|
||||
/* Set the D1 domain Core prescaler and the HCLK source/divider */
|
||||
|
||||
regval = getreg32(STM32_RCC_D1CFGR);
|
||||
regval &= ~RCC_D1CFGR_HPRE_MASK;
|
||||
regval |= STM32_RCC_D1CFGR_HPRE;
|
||||
regval &= ~(RCC_D1CFGR_HPRE_MASK | RCC_D1CFGR_D1CPRE_MASK);
|
||||
regval |= (STM32_RCC_D1CFGR_HPRE | STM32_RCC_D1CFGR_D1CPRE);
|
||||
putreg32(regval, STM32_RCC_D1CFGR);
|
||||
|
||||
/* Set PCLK1 */
|
||||
|
@ -55,7 +55,7 @@
|
||||
/* Clocking *************************************************************************/
|
||||
/* The Nucleo-144 board provides the following clock sources:
|
||||
*
|
||||
* MCO: 8 MHz from MCO output of ST-LINK is used as input clock
|
||||
* MCO: 8 MHz from MCO output of ST-LINK is used as input clock (default)
|
||||
* X2: 32.768 KHz crystal for LSE
|
||||
* X3: HSE crystal oscillator (not provided)
|
||||
*
|
||||
@ -67,7 +67,7 @@
|
||||
* LSE: 32.768 kHz
|
||||
*/
|
||||
|
||||
#define STM32_BOARD_XTAL 8000000ul
|
||||
#define STM32_BOARD_XTAL 8000000ul /* ST-LINK MCO */
|
||||
|
||||
#define STM32_HSI_FREQUENCY 16000000ul
|
||||
#define STM32_LSI_FREQUENCY 32000
|
||||
@ -164,6 +164,7 @@
|
||||
* CPUCLK = SYSCLK / 1 = 400 MHz
|
||||
*/
|
||||
|
||||
#define STM32_RCC_D1CFGR_D1CPRE (RCC_D1CFGR_D1CPRE_SYSCLK)
|
||||
#define STM32_SYSCLK_FREQUENCY (STM32_PLL1P_FREQUENCY)
|
||||
#define STM32_CPUCLK_FREQUENCY (STM32_SYSCLK_FREQUENCY / 1)
|
||||
|
||||
@ -328,6 +329,11 @@
|
||||
#define GPIO_SPI3_SCK GPIO_SPI3_SCK_1 /* PB3 */
|
||||
#define GPIO_SPI3_NSS GPIO_SPI3_NSS_2 /* PA4 */
|
||||
|
||||
/* DMA ******************************************************************************/
|
||||
|
||||
#define DMAMAP_SPI3_RX DMAMAP_DMA12_SPI3RX_0 /* DMA1 */
|
||||
#define DMAMAP_SPI3_TX DMAMAP_DMA12_SPI3TX_0 /* DMA1 */
|
||||
|
||||
/************************************************************************************
|
||||
* Public Data
|
||||
************************************************************************************/
|
||||
|
Loading…
Reference in New Issue
Block a user