Merge changes from topic "st_uart_updates" into integration

* changes:
  feat(stm32mp1): add early console in SP_min
  feat(st): properly manage early console
  feat(st-uart): manage STM32MP_RECONFIGURE_CONSOLE
  docs(st): introduce STM32MP_RECONFIGURE_CONSOLE
  feat(st): add trace for early console
  fix(stm32mp1): enable crash console in FIQ handler
  feat(st-uart): add initialization with the device tree
  refactor(stm32mp1): move DT_UART_COMPAT in include file
  feat(stm32mp1): configure the serial boot load address
  fix(stm32mp1): update the FIP load address for serial boot
  refactor(st): configure baudrate for UART programmer
  refactor(st-uart): compute the over sampling dynamically
diff --git a/docs/plat/stm32mp1.rst b/docs/plat/stm32mp1.rst
index 7ae98b1..fff86a8 100644
--- a/docs/plat/stm32mp1.rst
+++ b/docs/plat/stm32mp1.rst
@@ -144,8 +144,12 @@
 
 - | ``DTB_FILE_NAME``: to precise board device-tree blob to be used.
   | Default: stm32mp157c-ev1.dtb
+- | ``DWL_BUFFER_BASE``: the 'serial boot' load address of FIP,
+  | default location (end of the first 128MB) is used when absent
 - | ``STM32MP_EARLY_CONSOLE``: to enable early traces before clock driver is setup.
   | Default: 0 (disabled)
+- | ``STM32MP_RECONFIGURE_CONSOLE``: to re-configure crash console (especially after BL2).
+  | Default: 0 (disabled)
 - | ``STM32MP_UART_BAUDRATE``: to select UART baud rate.
   | Default: 115200
 - | ``STM32_TF_VERSION``: to manage BL2 monotonic counter.
diff --git a/drivers/st/clk/stm32mp_clkfunc.c b/drivers/st/clk/stm32mp_clkfunc.c
index 80c2f41..01d1420 100644
--- a/drivers/st/clk/stm32mp_clkfunc.c
+++ b/drivers/st/clk/stm32mp_clkfunc.c
@@ -17,7 +17,6 @@
 
 #include <platform_def.h>
 
-#define DT_UART_COMPAT		"st,stm32h7-uart"
 /*
  * Get the frequency of an oscillator from its name in device tree.
  * @param name: oscillator name
diff --git a/drivers/st/uart/aarch32/stm32_console.S b/drivers/st/uart/aarch32/stm32_console.S
index e467f09..e3e0e67 100644
--- a/drivers/st/uart/aarch32/stm32_console.S
+++ b/drivers/st/uart/aarch32/stm32_console.S
@@ -46,10 +46,16 @@
 	cmp	r0, #0
 	beq	core_init_fail
 #if !defined(IMAGE_BL2)
+#if STM32MP_RECONFIGURE_CONSOLE
+	/* UART clock rate is set to 0 in BL32, skip init in that case */
+	cmp	r1, #0
+	beq	1f
+#else /* STM32MP_RECONFIGURE_CONSOLE */
 	/* Skip UART initialization if it is already enabled */
 	ldr	r3, [r0, #USART_CR1]
 	ands	r3, r3, #USART_CR1_UE
 	bne	1f
+#endif /* STM32MP_RECONFIGURE_CONSOLE */
 #endif /* IMAGE_BL2 */
 	/* Check baud rate and uart clock for sanity */
 	cmp	r1, #0
diff --git a/drivers/st/uart/stm32_uart.c b/drivers/st/uart/stm32_uart.c
index e2e5405..63970c7 100644
--- a/drivers/st/uart/stm32_uart.c
+++ b/drivers/st/uart/stm32_uart.c
@@ -1,5 +1,5 @@
 /*
- * Copyright (c) 2021, STMicroelectronics - All Rights Reserved
+ * Copyright (c) 2021-2022, STMicroelectronics - All Rights Reserved
  *
  * SPDX-License-Identifier: BSD-3-Clause
  */
@@ -9,7 +9,9 @@
 #include <string.h>
 
 #include <common/bl_common.h>
+#include <drivers/clk.h>
 #include <drivers/delay_timer.h>
+#include <drivers/st/stm32_gpio.h>
 #include <drivers/st/stm32_uart.h>
 #include <drivers/st/stm32_uart_regs.h>
 #include <drivers/st/stm32mp_clkfunc.h>
@@ -106,7 +108,33 @@
 {
 	uint32_t tmpreg;
 	unsigned long clockfreq;
+	unsigned long int_div;
 	uint32_t brrtemp;
+	uint32_t over_sampling;
+
+	/*---------------------- USART BRR configuration --------------------*/
+	clockfreq = uart_get_clock_freq(huart);
+	if (clockfreq == 0UL) {
+		return -ENODEV;
+	}
+
+	int_div = clockfreq / init->baud_rate;
+	if (int_div < 16U) {
+		uint32_t usartdiv = uart_div_sampling8(clockfreq,
+						       init->baud_rate,
+						       init->prescaler);
+
+		brrtemp = (usartdiv & USART_BRR_DIV_MANTISSA) |
+			  ((usartdiv & USART_BRR_DIV_FRACTION) >> 1);
+		over_sampling = USART_CR1_OVER8;
+	} else {
+		brrtemp = uart_div_sampling16(clockfreq,
+					      init->baud_rate,
+					      init->prescaler) &
+			  (USART_BRR_DIV_FRACTION | USART_BRR_DIV_MANTISSA);
+		over_sampling = 0x0U;
+	}
+	mmio_write_32(huart->base + USART_BRR, brrtemp);
 
 	/*
 	 * ---------------------- USART CR1 Configuration --------------------
@@ -115,12 +143,12 @@
 	 * - set the M bits according to init->word_length value,
 	 * - set PCE and PS bits according to init->parity value,
 	 * - set TE and RE bits according to init->mode value,
-	 * - set OVER8 bit according to init->over_sampling value.
+	 * - set OVER8 bit according baudrate and clock.
 	 */
 	tmpreg = init->word_length |
 		 init->parity |
 		 init->mode |
-		 init->over_sampling |
+		 over_sampling |
 		 init->fifo_mode;
 	mmio_clrsetbits_32(huart->base + USART_CR1, STM32_UART_CR1_FIELDS, tmpreg);
 
@@ -161,27 +189,6 @@
 	mmio_clrsetbits_32(huart->base + USART_PRESC, USART_PRESC_PRESCALER,
 			   init->prescaler);
 
-	/*---------------------- USART BRR configuration --------------------*/
-	clockfreq = uart_get_clock_freq(huart);
-	if (clockfreq == 0UL) {
-		return -ENODEV;
-	}
-
-	if (init->over_sampling == STM32_UART_OVERSAMPLING_8) {
-		uint32_t usartdiv = uart_div_sampling8(clockfreq,
-						       init->baud_rate,
-						       init->prescaler);
-
-		brrtemp = (usartdiv & USART_BRR_DIV_MANTISSA) |
-			  ((usartdiv & USART_BRR_DIV_FRACTION) >> 1);
-	} else {
-		brrtemp = uart_div_sampling16(clockfreq,
-					      init->baud_rate,
-					      init->prescaler) &
-			  (USART_BRR_DIV_FRACTION | USART_BRR_DIV_MANTISSA);
-	}
-	mmio_write_32(huart->base + USART_BRR, brrtemp);
-
 	return 0;
 }
 
@@ -295,12 +302,14 @@
  * @param  init: UART initialization parameter.
  * @retval UART status.
  */
-
 int stm32_uart_init(struct stm32_uart_handle_s *huart,
 		    uintptr_t base_addr,
 		    const struct stm32_uart_init_s *init)
 {
 	int ret;
+	int uart_node;
+	int clk;
+	void *fdt = NULL;
 
 	if (huart == NULL || init == NULL || base_addr == 0U) {
 		return -EINVAL;
@@ -308,6 +317,32 @@
 
 	huart->base = base_addr;
 
+	/* Search UART instance in DT */
+	if (fdt_get_address(&fdt) == 0) {
+		return -FDT_ERR_NOTFOUND;
+	}
+
+	if (fdt == NULL) {
+		return -FDT_ERR_NOTFOUND;
+	}
+
+	uart_node = dt_match_instance_by_compatible(DT_UART_COMPAT, base_addr);
+	if (uart_node == -FDT_ERR_NOTFOUND) {
+		return -FDT_ERR_NOTFOUND;
+	}
+
+	/* Pinctrl initialization */
+	if (dt_set_pinctrl_config(uart_node) != 0) {
+		return -FDT_ERR_BADVALUE;
+	}
+
+	/* Clock initialization */
+	clk = fdt_get_clock_id(uart_node);
+	if (clk < 0) {
+		return -FDT_ERR_NOTFOUND;
+	}
+	clk_enable(clk);
+
 	/* Disable the peripheral */
 	stm32_uart_stop(huart->base);
 
diff --git a/include/drivers/st/stm32_uart.h b/include/drivers/st/stm32_uart.h
index 212968f..866e158 100644
--- a/include/drivers/st/stm32_uart.h
+++ b/include/drivers/st/stm32_uart.h
@@ -1,5 +1,5 @@
 /*
- * Copyright (c) 2021, STMicroelectronics - All Rights Reserved
+ * Copyright (c) 2021-2022, STMicroelectronics - All Rights Reserved
  *
  * SPDX-License-Identifier: BSD-3-Clause
  */
@@ -34,10 +34,6 @@
 #define STM32_UART_HWCONTROL_CTS		USART_CR3_CTSE
 #define STM32_UART_HWCONTROL_RTS_CTS		(USART_CR3_RTSE | USART_CR3_CTSE)
 
-/* UART over sampling */
-#define STM32_UART_OVERSAMPLING_16		0x00000000U
-#define STM32_UART_OVERSAMPLING_8		USART_CR1_OVER8
-
 /* UART prescaler */
 #define STM32_UART_PRESCALER_DIV1		0x00000000U
 #define STM32_UART_PRESCALER_DIV2		0x00000001U
@@ -112,13 +108,6 @@
 					 * value of @ref STM32_UARTHWCONTROL_*.
 					 */
 
-	uint32_t over_sampling;		/*
-					 * Specifies whether the over sampling
-					 * 8 is enabled or disabled.
-					 * This parameter can be a value of
-					 * @ref STM32_UART_OVERSAMPLING_*.
-					 */
-
 	uint32_t one_bit_sampling;	/*
 					 * Specifies whether a single sample
 					 * or three samples' majority vote is
diff --git a/plat/st/common/stm32cubeprogrammer_uart.c b/plat/st/common/stm32cubeprogrammer_uart.c
index 46ac9cf..d004dcf 100644
--- a/plat/st/common/stm32cubeprogrammer_uart.c
+++ b/plat/st/common/stm32cubeprogrammer_uart.c
@@ -1,5 +1,5 @@
 /*
- * Copyright (c) 2021, STMicroelectronics - All Rights Reserved
+ * Copyright (c) 2021-2022, STMicroelectronics - All Rights Reserved
  *
  * SPDX-License-Identifier: BSD-3-Clause
  */
@@ -486,13 +486,12 @@
 
 /* Init UART: 115200, 8bit 1stop parity even and enable FIFO mode */
 const struct stm32_uart_init_s init = {
-	.baud_rate = U(115200),
+	.baud_rate = STM32MP_UART_BAUDRATE,
 	.word_length = STM32_UART_WORDLENGTH_9B,
 	.stop_bits = STM32_UART_STOPBITS_1,
 	.parity = STM32_UART_PARITY_EVEN,
 	.hw_flow_control = STM32_UART_HWCONTROL_NONE,
 	.mode = STM32_UART_MODE_TX_RX,
-	.over_sampling = STM32_UART_OVERSAMPLING_16,
 	.fifo_mode = STM32_UART_FIFOMODE_EN,
 };
 
diff --git a/plat/st/common/stm32mp_common.c b/plat/st/common/stm32mp_common.c
index d922d3c..eee983f 100644
--- a/plat/st/common/stm32mp_common.c
+++ b/plat/st/common/stm32mp_common.c
@@ -274,8 +274,11 @@
 #if STM32MP_EARLY_CONSOLE
 void stm32mp_setup_early_console(void)
 {
+#if defined(IMAGE_BL2) || STM32MP_RECONFIGURE_CONSOLE
 	plat_crash_console_init();
+#endif
 	set_console(STM32MP_DEBUG_USART_BASE, STM32MP_DEBUG_USART_CLK_FRQ);
+	NOTICE("Early console setup\n");
 }
 #endif /* STM32MP_EARLY_CONSOLE */
 
diff --git a/plat/st/stm32mp1/include/platform_def.h b/plat/st/stm32mp1/include/platform_def.h
index 8ecb4c3..fe4ef3d 100644
--- a/plat/st/stm32mp1/include/platform_def.h
+++ b/plat/st/stm32mp1/include/platform_def.h
@@ -103,8 +103,7 @@
 #define PLAT_STM32MP_NS_IMAGE_OFFSET	BL33_BASE
 
 /* Needed by STM32CubeProgrammer support */
-#define DWL_BUFFER_BASE			(STM32MP_DDR_BASE + U(0x08000000))
-#define DWL_BUFFER_SIZE			U(0x08000000)
+#define DWL_BUFFER_SIZE			U(0x01000000)
 
 /*
  * SSBL offset in case it's stored in eMMC boot partition.
diff --git a/plat/st/stm32mp1/platform.mk b/plat/st/stm32mp1/platform.mk
index 7203de8..def2898 100644
--- a/plat/st/stm32mp1/platform.mk
+++ b/plat/st/stm32mp1/platform.mk
@@ -10,6 +10,7 @@
 USE_COHERENT_MEM	:=	0
 
 STM32MP_EARLY_CONSOLE	?=	0
+STM32MP_RECONFIGURE_CONSOLE ?=	0
 STM32MP_UART_BAUDRATE	?=	115200
 
 # Allow TF-A to concatenate BL2 & BL32 binaries in a single file,
@@ -121,6 +122,9 @@
 STM32MP_USB_PROGRAMMER	?=	0
 STM32MP_UART_PROGRAMMER	?=	0
 
+# Download load address for serial boot devices
+DWL_BUFFER_BASE 	?=	0xC7000000
+
 # Device tree
 ifeq ($(STM32MP13),1)
 BL2_DTSI		:=	stm32mp13-bl2.dtsi
@@ -205,6 +209,7 @@
 		STM32MP_EMMC \
 		STM32MP_EMMC_BOOT \
 		STM32MP_RAW_NAND \
+		STM32MP_RECONFIGURE_CONSOLE \
 		STM32MP_SDMMC \
 		STM32MP_SPI_NAND \
 		STM32MP_SPI_NOR \
@@ -225,6 +230,7 @@
 
 $(eval $(call add_defines,\
 	$(sort \
+		DWL_BUFFER_BASE \
 		PLAT_PARTITION_MAX_ENTRIES \
 		PLAT_XLAT_TABLES_DYNAMIC \
 		STM32_TF_A_COPIES \
@@ -235,6 +241,7 @@
 		STM32MP_EMMC \
 		STM32MP_EMMC_BOOT \
 		STM32MP_RAW_NAND \
+		STM32MP_RECONFIGURE_CONSOLE \
 		STM32MP_SDMMC \
 		STM32MP_SPI_NAND \
 		STM32MP_SPI_NOR \
diff --git a/plat/st/stm32mp1/sp_min/sp_min_setup.c b/plat/st/stm32mp1/sp_min/sp_min_setup.c
index 8106795..325666f 100644
--- a/plat/st/stm32mp1/sp_min/sp_min_setup.c
+++ b/plat/st/stm32mp1/sp_min/sp_min_setup.c
@@ -1,5 +1,5 @@
 /*
- * Copyright (c) 2015-2021, ARM Limited and Contributors. All rights reserved.
+ * Copyright (c) 2015-2022, ARM Limited and Contributors. All rights reserved.
  *
  * SPDX-License-Identifier: BSD-3-Clause
  */
@@ -40,6 +40,8 @@
  ******************************************************************************/
 void sp_min_plat_fiq_handler(uint32_t id)
 {
+	(void)plat_crash_console_init();
+
 	switch (id & INT_ID_MASK) {
 	case STM32MP1_IRQ_TZC400:
 		tzc400_init(STM32MP1_TZC_BASE);
@@ -51,7 +53,7 @@
 		panic();
 		break;
 	default:
-		ERROR("SECURE IT handler not define for it : %u", id);
+		ERROR("SECURE IT handler not define for it : %u\n", id);
 		break;
 	}
 }
@@ -119,6 +121,8 @@
 	uintptr_t dt_addr = arg1;
 #endif
 
+	stm32mp_setup_early_console();
+
 	/* Imprecise aborts can be masked in NonSecure */
 	write_scr(read_scr() | SCR_AW_BIT);
 
diff --git a/plat/st/stm32mp1/stm32mp1_def.h b/plat/st/stm32mp1/stm32mp1_def.h
index 116bd5d..a74d58c 100644
--- a/plat/st/stm32mp1/stm32mp1_def.h
+++ b/plat/st/stm32mp1/stm32mp1_def.h
@@ -666,5 +666,6 @@
 #define DT_RCC_SEC_CLK_COMPAT		"st,stm32mp1-rcc-secure"
 #endif
 #define DT_SDMMC2_COMPAT		"st,stm32-sdmmc2"
+#define DT_UART_COMPAT			"st,stm32h7-uart"
 
 #endif /* STM32MP1_DEF_H */