summary | shortlog | log | commit | commitdiff | tree
raw | patch | inline | side by side (parent: 8c0b36f)
raw | patch | inline | side by side (parent: 8c0b36f)
author | M V Pratap Reddy <x0257344@ti.com> | |
Thu, 13 Aug 2020 12:13:17 +0000 (17:43 +0530) | ||
committer | Sivaraj R <sivaraj@ti.com> | |
Wed, 19 Aug 2020 10:54:16 +0000 (05:54 -0500) |
- Enabled build support for am64x evm diagnostic tests
12 files changed:
diff --git a/packages/ti/board/diag/board_diag_component.mk b/packages/ti/board/diag/board_diag_component.mk
index 7cd144cb558967dfd815326fb53e6d2cad65d718..b9dadfbeaf30d4216858ec04369432e7cc7f7bad 100755 (executable)
board_diag_j721e_CORELIST = mpu1_0 mcu1_0
board_diag_j7200_CORELIST = mpu1_0 mcu1_0
board_diag_tpr12_CORELIST = mcu1_0
+board_diag_am64x_CORELIST = mpu1_0 mcu1_0
############################
# Board diagnostic package
export board_diag_temperature_MAKEFILE
board_diag_temperature_PKG_LIST = board_diag_temperature
board_diag_temperature_INCLUDE = $(board_diag_temperature_PATH)
-board_diag_temperature_BOARDLIST = j721e_evm am65xx_evm am65xx_idk j7200_evm tpr12_evm
+board_diag_temperature_BOARDLIST = j721e_evm am65xx_evm am65xx_idk j7200_evm tpr12_evm am64x_evm
board_diag_temperature_$(SOC)_CORELIST = $(board_diag_$(SOC)_CORELIST)
export board_diag_temperature_$(SOC)_CORELIST
export board_diag_temperature_SBL_APPIMAGEGEN = $(board_diag_APPIMAGEGEN_CTRL)
diff --git a/packages/ti/board/diag/common/am64x/diag_common_cfg.c b/packages/ti/board/diag/common/am64x/diag_common_cfg.c
--- /dev/null
@@ -0,0 +1,238 @@
+/******************************************************************************\r
+ * Copyright (c) 2020 Texas Instruments Incorporated - http://www.ti.com\r
+ *\r
+ * Redistribution and use in source and binary forms, with or without\r
+ * modification, are permitted provided that the following conditions\r
+ * are met:\r
+ *\r
+ * Redistributions of source code must retain the above copyright\r
+ * notice, this list of conditions and the following disclaimer.\r
+ *\r
+ * Redistributions in binary form must reproduce the above copyright\r
+ * notice, this list of conditions and the following disclaimer in the\r
+ * documentation and/or other materials provided with the\r
+ * distribution.\r
+ *\r
+ * Neither the name of Texas Instruments Incorporated nor the names of\r
+ * its contributors may be used to endorse or promote products derived\r
+ * from this software without specific prior written permission.\r
+ *\r
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS\r
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT\r
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR\r
+ * A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT\r
+ * OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,\r
+ * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT\r
+ * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,\r
+ * DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY\r
+ * THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT\r
+ * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE\r
+ * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.\r
+ *\r
+ *****************************************************************************/\r
+\r
+/**\r
+ * \file diag_common_cfg.c\r
+ *\r
+ * \brief Common functions used by diagnostic tests modules.\r
+ *\r
+ * This file contains the utils functions which are common for different\r
+ * interfaces of given platform and used by diagnostic test modules.\r
+ *\r
+ *\r
+ */\r
+\r
+/* ========================================================================== */\r
+/* Include Files */\r
+/* ========================================================================== */\r
+\r
+#include <ti/csl/tistdtypes.h>\r
+#include <ti/board/board.h>\r
+#include <diag_common_cfg.h>\r
+#include <ti/osal/osal.h>\r
+\r
+#include <ti/drv/i2c/I2C.h>\r
+#include <ti/drv/i2c/soc/I2C_soc.h>\r
+#include <ti/drv/uart/UART_stdio.h>\r
+\r
+\r
+/**\r
+ * \brief Diagnostic init function\r
+ *\r
+ * This function includes the common initialization sequence for \r
+ * diagnostic tests.\r
+ *\r
+ * \return\r
+ * 1 - In case of success\r
+ * 0 - In case of failure\r
+ *\r
+ */\r
+Board_STATUS DIAG_init(void)\r
+{\r
+ Board_initCfg boardCfg;\r
+ Board_STATUS status;\r
+ \r
+#ifdef PDK_RAW_BOOT\r
+ boardCfg = BOARD_INIT_DEFAULT;\r
+#else\r
+ boardCfg = BOARD_INIT_UART_STDIO | BOARD_INIT_PINMUX_CONFIG;\r
+#endif\r
+\r
+ status = Board_init(boardCfg);\r
+ \r
+ return(status);\r
+}\r
+\r
+/**\r
+ * \brief Compares two data buffers\r
+ *\r
+ * This function verifies the data in two buffers passed as parameters and\r
+ * returns the result. 'failIndex' contains the index of the first mismatch\r
+ * when buffer comparision fails.\r
+ *\r
+ * \param buf1 [IN] Data buffer 1\r
+ * \param buf2 [IN] Data buffer 2\r
+ * \param length [IN] Length of the buffers\r
+ * \param failIndex [OUT] Index of first data mismatch\r
+ *\r
+ * \return\r
+ * 1 - In case of success\r
+ * 0 - In case of failure\r
+ *\r
+ */\r
+bool BoardDiag_memCompare(uint8_t *buf1, uint8_t *buf2, uint32_t length, \r
+ uint32_t *failIndex)\r
+{\r
+ uint32_t idx = 0;\r
+ bool match = 1;\r
+ \r
+ for(idx = 0; ((idx < length) && (match == 1)); idx++)\r
+ {\r
+ if(buf1[idx] != buf2[idx])\r
+ {\r
+ match = 0;\r
+ *failIndex = idx;\r
+ } \r
+ }\r
+\r
+ return (match);\r
+}\r
+\r
+/**\r
+ * \brief Generate test pattern function\r
+ *\r
+ * This function fills the data buffer passed as input parameter with\r
+ * different test patterns as indicated by 'flag' parameter.\r
+ * Below are the different test patterns supported\r
+ *\r
+ * BOARD_DIAG_TEST_PATTERN_FF - Fills the buffer with 0xFF\r
+ * BOARD_DIAG_TEST_PATTERN_AA - Fills the buffer with 0xAA\r
+ * BOARD_DIAG_TEST_PATTERN_55 - Fills the buffer with 0x55\r
+ * BOARD_DIAG_TEST_PATTERN_NULL - Fills buffer with 0\r
+ * BOARD_DIAG_TEST_PATTERN_RANDOM - Fills the buffer with randon pattern\r
+ * BOARD_DIAG_TEST_PATTERN_INC - Fills the buffer with increment pattern\r
+ * starting from 0\r
+ * BOARD_DIAG_TEST_PATTERN_AA_55 - Fills the buffer with 0xAA in even locations\r
+ * 0x55 in odd locations\r
+ *\r
+ * If 'flag' does match with any of the above values, buffer will be filled\r
+ * with 0 by default.\r
+ *\r
+ * \param buf [IN] Buffer to fill with the test pattern\r
+ * \param length [IN] Length of the buffer\r
+ * \param flag [IN] Flag to set the test pattern\r
+ *\r
+ */\r
+void BoardDiag_genPattern(uint8_t *buf, uint32_t length, uint8_t flag)\r
+{\r
+ uint8_t data = 0;\r
+ uint8_t incFlag = 0;\r
+ uint8_t randFlag = 0;\r
+ uint8_t checkerBoard = 0;\r
+ uint32_t idx;\r
+\r
+ switch(flag)\r
+ {\r
+ case BOARD_DIAG_TEST_PATTERN_FF:\r
+ case BOARD_DIAG_TEST_PATTERN_AA:\r
+ case BOARD_DIAG_TEST_PATTERN_55:\r
+ case BOARD_DIAG_TEST_PATTERN_NULL:\r
+ data = flag;\r
+ break;\r
+ case BOARD_DIAG_TEST_PATTERN_INC:\r
+ data = 0;\r
+ incFlag = 1;\r
+ break;\r
+ case BOARD_DIAG_TEST_PATTERN_RANDOM:\r
+ data = rand();\r
+ randFlag = 1;\r
+ case BOARD_DIAG_TEST_PATTERN_AA_55:\r
+ data = 0xAA;\r
+ checkerBoard = 1;\r
+ break;\r
+ default:\r
+ data = flag;\r
+ break;\r
+ }\r
+\r
+ for(idx = 0; idx < length; idx++)\r
+ {\r
+ buf[idx] = data;\r
+ \r
+ if(incFlag)\r
+ data++;\r
+ \r
+ if(randFlag)\r
+ data = rand();\r
+\r
+ if(checkerBoard)\r
+ data = ~data;\r
+ }\r
+}\r
+\r
+/**\r
+ * \brief This API reads a byte from the Receiver Buffer Register\r
+ * (RBR). It checks once if any character is ready to be read.\r
+ *\r
+ * Note: When UART driver is used through STDIO interface,it is not possible\r
+ * to read the data without waiting forever. This API will be useful in such \r
+ * cases.\r
+ *\r
+ * \param instance Memory address of the UART instance being used.\r
+ *\r
+ * \return value of RHR register\r
+ */\r
+\r
+int8_t BoardDiag_getUserInput(uint8_t instance)\r
+{\r
+ return 0;\r
+}\r
+\r
+/**\r
+ * \brief This API Enables the main I2C instances\r
+ *\r
+ * \param instance [IN] I2C instance number.\r
+ * \param baseAddr [IN] Register base address of the I2C instance.\r
+ */\r
+void enableMAINI2C(uint8_t instance, uint32_t baseAddr)\r
+{\r
+ BoardDiag_enableI2C(instance, baseAddr);\r
+}\r
+\r
+/**\r
+ * \brief This API Enables the I2C instances\r
+ *\r
+ * \param instance [IN] I2C instance.\r
+ * \param baseAddr [IN] Register base address of the I2C instance.\r
+ */\r
+void BoardDiag_enableI2C(uint8_t instance, uint32_t baseAddr)\r
+{\r
+ I2C_HwAttrs i2cCfg;\r
+\r
+ I2C_socGetInitCfg(instance, &i2cCfg);\r
+\r
+ i2cCfg.baseAddr = baseAddr;\r
+ i2cCfg.enableIntr = 0;\r
+\r
+ I2C_socSetInitCfg(instance, &i2cCfg);\r
+}\r
diff --git a/packages/ti/board/diag/common/am64x/diag_common_cfg.h b/packages/ti/board/diag/common/am64x/diag_common_cfg.h
--- /dev/null
@@ -0,0 +1,65 @@
+/******************************************************************************\r
+ * Copyright (c) 2020 Texas Instruments Incorporated - http://www.ti.com\r
+ *\r
+ * Redistribution and use in source and binary forms, with or without\r
+ * modification, are permitted provided that the following conditions\r
+ * are met:\r
+ *\r
+ * Redistributions of source code must retain the above copyright\r
+ * notice, this list of conditions and the following disclaimer.\r
+ *\r
+ * Redistributions in binary form must reproduce the above copyright\r
+ * notice, this list of conditions and the following disclaimer in the\r
+ * documentation and/or other materials provided with the\r
+ * distribution.\r
+ *\r
+ * Neither the name of Texas Instruments Incorporated nor the names of\r
+ * its contributors may be used to endorse or promote products derived\r
+ * from this software without specific prior written permission.\r
+ *\r
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS\r
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT\r
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR\r
+ * A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT\r
+ * OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,\r
+ * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT\r
+ * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,\r
+ * DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY\r
+ * THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT\r
+ * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE\r
+ * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.\r
+ *\r
+ *****************************************************************************/\r
+\r
+/**\r
+ * \file diag_common_cfg.h\r
+ *\r
+ * \brief Common protoypes and data structures used by diagnostic tests.\r
+ *\r
+ */\r
+#include <stdbool.h>\r
+#include <stdlib.h>\r
+\r
+#include "board.h"\r
+#include "board_cfg.h"\r
+#include <ti/board/src/am64x_evm/include/board_utils.h>\r
+\r
+#define DIAG_STRESS_TEST_ITERATIONS (100)\r
+\r
+/* Macros used by test pattern generate function */ \r
+#define BOARD_DIAG_TEST_PATTERN_FF (0xFF)\r
+#define BOARD_DIAG_TEST_PATTERN_AA (0xAA)\r
+#define BOARD_DIAG_TEST_PATTERN_55 (0x55)\r
+#define BOARD_DIAG_TEST_PATTERN_NULL (0)\r
+#define BOARD_DIAG_TEST_PATTERN_RANDOM (1)\r
+#define BOARD_DIAG_TEST_PATTERN_INC (2)\r
+#define BOARD_DIAG_TEST_PATTERN_AA_55 (3)\r
+\r
+\r
+Board_STATUS DIAG_init(void);\r
+bool BoardDiag_memCompare(uint8_t *buf1, uint8_t *buf2, uint32_t length, \r
+ uint32_t *failIndex);\r
+void BoardDiag_genPattern(uint8_t *buf, uint32_t length, uint8_t flag);\r
+int8_t BoardDiag_getUserInput(uint8_t instance);\r
+void enableMAINI2C(uint8_t instance, uint32_t baseAddr);\r
+void BoardDiag_enableI2C(uint8_t instance, uint32_t baseAddr);\r
diff --git a/packages/ti/board/diag/common/am64x/diag_entry.asm b/packages/ti/board/diag/common/am64x/diag_entry.asm
--- /dev/null
@@ -0,0 +1,314 @@
+/*\r
+ * Copyright (c) 2017-2018, Texas Instruments Incorporated\r
+ * All rights reserved.\r
+ *\r
+ * Redistribution and use in source and binary forms, with or without\r
+ * modification, are permitted provided that the following conditions\r
+ * are met:\r
+ *\r
+ * * Redistributions of source code must retain the above copyright\r
+ * notice, this list of conditions and the following disclaimer.\r
+ *\r
+ * * Redistributions in binary form must reproduce the above copyright\r
+ * notice, this list of conditions and the following disclaimer in the\r
+ * documentation and/or other materials provided with the distribution.\r
+ *\r
+ * * Neither the name of Texas Instruments Incorporated nor the names of\r
+ * its contributors may be used to endorse or promote products derived\r
+ * from this software without specific prior written permission.\r
+ *\r
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"\r
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO,\r
+ * THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR\r
+ * PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR\r
+ * CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL,\r
+ * EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO,\r
+ * PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS;\r
+ * OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY,\r
+ * WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR\r
+ * OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE,\r
+ * EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.\r
+ */\r
+#include <ti/csl/arch/a53/src/startup/aarch64/boot_defs.h>\r
+\r
+//************************** Global symbols ************************************\r
+ .global Entry\r
+ .global _stack\r
+ .global _bss_start\r
+ .global _bss_end\r
+ .global start_boot\r
+ .global main\r
+ .global ti_csl_arm_gicv3_vectors\r
+\r
+.macro GICD_WRITE_LOOP x, y, offset\r
+ str w1, [x0, #\offset]\r
+ .if \y-\x\r
+ GICD_WRITE_LOOP "(\x+1)", \y, "(\offset+4)"\r
+ .endif\r
+.endm\r
+\r
+.macro INIT_GICD_IGROUPR\r
+ ldr x0, =CSL_GIC_BASE_ADDR\r
+ mvn w1, wzr\r
+ GICD_WRITE_LOOP 0, 31, 0x0080\r
+.endm\r
+\r
+.macro INIT_GICD_IGRPMODR\r
+ ldr x0, =CSL_GIC_BASE_ADDR\r
+ mov w1, wzr\r
+ GICD_WRITE_LOOP 0, 31, 0x0D00\r
+.endm\r
+\r
+\r
+ .section .text.csl_a53_startup, "ax"\r
+ .func Entry\r
+Entry:\r
+ mov x21, sp /* Store the SP in x21 */\r
+ mov x22, x30 /* Store the LR in x22 */\r
+ mrs x0, currentel\r
+ cmp x0, #0xC\r
+ bne 2f\r
+ ldr x0, =ti_csl_arm_v8a_Core_disableCaches\r
+ blr x0\r
+\r
+ /*\r
+ * ----------------------\r
+ * Switch from EL3 to EL2\r
+ * ----------------------\r
+ */\r
+ mov x0, #0x0531\r
+ msr scr_el3, x0\r
+ msr cptr_el3, xzr /* Disable all trap bits */\r
+ mov x0, #0x33ff\r
+ msr cptr_el2, x0 /* Disable all trap bits */\r
+ ldr x0, =CSL_GIC_BASE_ADDR\r
+ mov w1, #0x37\r
+ str w1, [x0] /* Enable GIC */\r
+ mov x0, #0xf\r
+ msr s3_6_c12_c12_5, x0 /* Enable GIC system register interface\r
+ and disable IRQ/FIQ bypass */\r
+ isb\r
+ mov x0, #0x1\r
+ msr s3_6_c12_c12_7, x0 /* Enable Non-secure group 1 interrupts */\r
+ isb\r
+ INIT_GICD_IGROUPR\r
+ INIT_GICD_IGRPMODR\r
+ ldr x0, =CSL_GICR_BASE_ADDR\r
+ ldr x1, =ti_csl_arm_v8a_Core_getGicxAddr\r
+ blr x1\r
+ ldr w1, [x0, #0x14]\r
+ mov w2, #0x2\r
+ bic w1, w1, w2\r
+ str w1, [x0, #0x14] /* wakeup GICR */\r
+1: ldr w1, [x0, #0x14]\r
+ and w1, w1, #0x4\r
+ cbnz w1, 1b\r
+ ldr x0, =CSL_GICS_BASE_ADDR\r
+ ldr x1, =ti_csl_arm_v8a_Core_getGicxAddr\r
+ blr x1\r
+ mvn x1, xzr\r
+ str w1, [x0, #0x80] /* Configure all SGIs & PPIs as Group 1 ints */\r
+ str wzr, [x0, #0xD00] /* Clear GICR_IGRPMODR0 */\r
+ mov x0, #0xff\r
+ msr icc_pmr_el1, x0 /* Set priority mask */\r
+ mov x0, #0x0830\r
+ movk x0, #0x30c5, lsl #16\r
+ msr sctlr_el2, x0 /* Initialize sctlr_el2 to reset values */\r
+ mrs x0, actlr_el3\r
+ orr x0, x0, #0x2\r
+ msr actlr_el3, x0 /* Enable CPUECTLR_EL1 access from EL2 */\r
+ /* TODO setup vbar */\r
+ ldr x0, =CSL_GTC_CNTCR_ADDR\r
+ ldr w1, [x0]\r
+ orr w1, w1, #0x1\r
+ str w1, [x0] /* Enable system counter */\r
+ isb\r
+ bl switch_to_el2\r
+\r
+2:\r
+ mrs x0, currentel /* Read again as currentEL may have changed */\r
+ cmp x0, #0x8\r
+ bne 3f\r
+\r
+ /*\r
+ * ----------------------\r
+ * Switch from EL2 to EL1\r
+ * ----------------------\r
+ */\r
+ mrs x0, cnthctl_el2\r
+ orr x0, x0, #0x3 /* Enable EL1/EL0 access to timers */\r
+ msr cnthctl_el2, x0\r
+ msr cntvoff_el2, xzr\r
+ mov x0, #0x33ff\r
+ msr cptr_el2, x0 /* Disable all trap bits */\r
+ msr hstr_el2, xzr /* Disable all coprocessor trap bits */\r
+ mov x0, #0x0002 /* 64bit EL1, Disable hypervisor call (HVC)\r
+ instruction, Set/Way Invalidation Override */\r
+ movk x0, #0xA000, lsl #16\r
+ msr hcr_el2, x0\r
+ mov x0, #0x0838\r
+ movk x0, #0x30d0, lsl #16\r
+ msr sctlr_el1, x0\r
+ mrs x0, actlr_el2\r
+ orr x0, x0, #2\r
+ msr actlr_el2, x0\r
+ isb\r
+ mov x0, #0xF\r
+ msr icc_sre_el2, x0 /* Enable GIC system register interface\r
+ and disable IRQ/FIQ bypass */\r
+ bl switch_to_el1\r
+3:\r
+ ldr x0, =gnu_targets_arm_rtsv8A_startupAsm\r
+ br x0\r
+\r
+switch_to_el1:\r
+ mov x0, #0x3c5\r
+ msr spsr_el2, x0\r
+ msr elr_el2, x30\r
+ eret\r
+\r
+switch_to_el2:\r
+ mov x0, #0x3c9\r
+ msr spsr_el3, x0\r
+ msr elr_el3, x30\r
+ eret\r
+\r
+ .endfunc\r
+\r
+/*\r
+ * ======== Core_getGicxBaseAddr ========\r
+ *\r
+ * Ptr Core_getGicxAddr(Ptr gicxBaseAddr)\r
+ */\r
+ .section .text.csl_startup, "ax"\r
+ .func ti_csl_arm_v8a_Core_getGicxAddr\r
+\r
+ti_csl_arm_v8a_Core_getGicxAddr:\r
+ ldr x1, =CSL_GICX_OFFSET\r
+ mrs x2, mpidr_el1\r
+ ubfx x3, x2, #8, #8 /* x3 = Cluster Id */\r
+ and x2, x2, #0xFF /* x2 = Core Id */\r
+ sub x3, x3, #0\r
+ mrs x4, s3_1_c11_c0_2 /* Read L2CTLR_EL1 */\r
+ ubfx x4, x4, #24, #2 /* x4 = Number of cores per cluster */\r
+ lsl x3, x3, x4 /* x3 = clusterIdx * numCoresPerCluster */\r
+ add x2, x2, x3\r
+ madd x0, x1, x2, x0\r
+ ret\r
+ .endfunc\r
+\r
+\r
+ .section .text.csl_a53_startup, "ax"\r
+ .func gnu_targets_arm_rtsv8A_startupAsm\r
+gnu_targets_arm_rtsv8A_startupAsm:\r
+ /*\r
+ * ---------------------\r
+ * Boot code starts here\r
+ * ---------------------\r
+ */\r
+\r
+ mov x0, #0x3C0\r
+ msr daif, x0 /* Mask all interrupts */\r
+\r
+#if defined(__ARM_FP)\r
+ mov x0, #(3 << 20)\r
+ msr cpacr_el1, x0 /* Enable FP/SIMD at EL1 */\r
+#endif\r
+\r
+ isb /* Synchronize processor context */\r
+\r
+ /*\r
+ * ------------------------\r
+ * Initialize stack pointer\r
+ * ------------------------\r
+ */\r
+ msr spsel, #1 /* Use SP_ELx for ELx */\r
+ ldr x0, =__TI_STACK_BASE\r
+ ldr x1, =__TI_STACK_SIZE\r
+ add x0, x0, x1\r
+ and x0, x0, #(~0xf) /* 16-byte align SP */\r
+ mov sp, x0 /* Initialize SP */\r
+\r
+ /* Setup the vector table for all levels */\r
+ ldr x0, =ti_csl_arm_gicv3_vectors\r
+ msr vbar_el1, x0 /* Set vector table base address */\r
+\r
+ stp x21, x22, [sp, #-16]! /* save SP and LR to stack */\r
+\r
+ /* do more initialization in C, go to main() */\r
+ bl main\r
+ mov x20, x0\r
+ ldp x0, x1, [sp], #16 /* Load SP and LR to stack */\r
+ mov sp, x0\r
+ mov x30, x1\r
+ ret\r
+ .endfunc\r
+\r
+/*\r
+ * ======== Core_disableCaches ========\r
+ */\r
+ .section .text.ti_csl_arm_v8a_Core_disableCaches\r
+ .func ti_csl_arm_v8a_Core_disableCaches\r
+\r
+ti_csl_arm_v8a_Core_disableCaches:\r
+ mrs x0, clidr_el1\r
+ and w3, w0, #0x07000000 /* Get 2 x Level of Coherence */\r
+ lsr w3, w3, #23\r
+ cbz w3, 5f\r
+ mov w10, #0 /* w10 = 2 x cache level */\r
+ mov w8, #1 /* w8 = Constant 0b1 */\r
+1:\r
+ add w2, w10, w10, lsr #1 /* Caclulate 3x cache level */\r
+ lsr w1, w0, w2 /* Extract cache type for this level */\r
+ and w1, w1, #0x7\r
+ cmp w1, #2\r
+ blt 4f /* No data or unified cache */\r
+ msr csselr_el1, x10 /* Select this cache level */\r
+ isb /* Synchronize change of csselr */\r
+ mrs x1, ccsidr_el1 /* Read ccsidr */\r
+ and w2, w1, #7 /* w2 = log2(linelen)-4 */\r
+ add w2, w2, #4 /* w2 = log2(linelen) */\r
+ ubfx w4, w1, #3, #10 /* w4 = max way number, right aligned */\r
+ clz w5, w4 /* w5 = 32-log2(ways), bit position of\r
+ way in dc operand */\r
+ lsl w9, w4, w5 /* w9 = max way number, aligned to\r
+ position in DC operand */\r
+ lsl w16, w8, w5 /* w16 = amount to decrement way number\r
+ per iteration */\r
+2:\r
+ ubfx w7, w1, #13, #15 /* w7 = max set number, right aligned */\r
+ lsl w7, w7, w2 /* w7 = max set number, aligned to\r
+ position in DC operand */\r
+ lsl w17, w8, w2 /* w17 = amount to decrement set number\r
+ per iteration */\r
+3:\r
+ orr w11, w10, w9 /* w11 = combine way num & cache ...*/\r
+ orr w11, w11, w7 /* ... num and set num for DC operand */\r
+ dc cisw, x11 /* Do data cache clean and invalidate\r
+ by set and way */\r
+ subs w7, w7, w17 /* Decrement set number */\r
+ bge 3b\r
+ subs x9, x9, x16 /* Decrement way number */\r
+ bge 2b\r
+4:\r
+ add w10, w10, #2 /* Increment 2 x cache level */\r
+ cmp w3, w10\r
+ dsb sy /* Ensure completion of previous cache\r
+ maintenance operation */\r
+ bgt 1b\r
+5:\r
+ mrs x0, sctlr_el3 /* read SCTLR_EL3 */\r
+ bic x0, x0, #0x0004 /* clear C bit */\r
+ msr sctlr_el3, x0 /* DCache disabled */\r
+\r
+ mrs x0, sctlr_el3 /* read SCTLR_EL3 */\r
+ bic x0, x0, #0x1000 /* clear I bit */\r
+ msr sctlr_el3, x0 /* ICache disabled */\r
+ ic iallu /* invalidate all ICache */\r
+ dsb sy\r
+ isb\r
+\r
+ ret\r
+ .endfunc\r
+\r
+ .end\r
diff --git a/packages/ti/board/diag/common/am64x/diag_entry_r5.asm b/packages/ti/board/diag/common/am64x/diag_entry_r5.asm
--- /dev/null
@@ -0,0 +1,664 @@
+;******************************************************************************\r
+;* BOOT v16.9.4 *\r
+;* *\r
+;* Copyright (c) 1996-2019 Texas Instruments Incorporated *\r
+;* http://www.ti.com/ *\r
+;* *\r
+;* Redistribution and use in source and binary forms, with or without *\r
+;* modification, are permitted provided that the following conditions *\r
+;* are met: *\r
+;* *\r
+;* Redistributions of source code must retain the above copyright *\r
+;* notice, this list of conditions and the following disclaimer. *\r
+;* *\r
+;* Redistributions in binary form must reproduce the above copyright *\r
+;* notice, this list of conditions and the following disclaimer in *\r
+;* the documentation and/or other materials provided with the *\r
+;* distribution. *\r
+;* *\r
+;* Neither the name of Texas Instruments Incorporated nor the names *\r
+;* of its contributors may be used to endorse or promote products *\r
+;* derived from this software without specific prior written *\r
+;* permission. *\r
+;* *\r
+;* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS *\r
+;* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT *\r
+;* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR *\r
+;* A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT *\r
+;* OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, *\r
+;* SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT *\r
+;* LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, *\r
+;* DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY *\r
+;* THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT *\r
+;* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE *\r
+;* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. *\r
+;* *\r
+;******************************************************************************\r
+\r
+;****************************************************************************\r
+;* BOOT.ASM\r
+;*\r
+;* THIS IS THE INITAL BOOT ROUTINE FOR TMS470 C++ PROGRAMS.\r
+;* IT MUST BE LINKED AND LOADED WITH ALL C++ PROGRAMS.\r
+;*\r
+;* THIS MODULE PERFORMS THE FOLLOWING ACTIONS:\r
+;* 1) ALLOCATES THE STACK AND INITIALIZES THE STACK POINTER\r
+;* 2) CALLS AUTO-INITIALIZATION ROUTINE\r
+;* 3) CALLS THE FUNCTION MAIN TO START THE C++ PROGRAM\r
+;* 4) CALLS THE STANDARD EXIT ROUTINE\r
+;*\r
+;* THIS MODULE DEFINES THE FOLLOWING GLOBAL SYMBOLS:\r
+;* 1) __stack STACK MEMORY AREA\r
+;* 2) _c_int00 BOOT ROUTINE\r
+;*\r
+;****************************************************************************\r
+ .if __TI_ARM_V7M__ | __TI_ARM_V6M0__\r
+ .thumbfunc _c_int00\r
+ .thumbfunc _resetvectors\r
+ .thumbfunc HF\r
+ .else\r
+ .armfunc _c_int00\r
+ .armfunc _resetvectors\r
+ .armfunc HF\r
+ .endif\r
+\r
+;****************************************************************************\r
+; Accomodate different lowerd names in different ABIs\r
+;****************************************************************************\r
+ .if __TI_EABI_ASSEMBLER\r
+ .asg _system_pre_init, PRE_INIT_RTN\r
+ .asg __TI_auto_init, AUTO_INIT_RTN\r
+ .asg _args_main, ARGS_MAIN_RTN\r
+ .asg exit, EXIT_RTN\r
+ .asg main_func_sp, MAIN_FUNC_SP\r
+ .else ; COFF TI ARM9 ABI\r
+ .asg __system_pre_init, PRE_INIT_RTN\r
+ .asg __TI_auto_init, AUTO_INIT_RTN ; NOTE does not use COFF prefix\r
+ .asg __args_main, ARGS_MAIN_RTN\r
+ .asg _exit, EXIT_RTN\r
+ .asg _main_func_sp, MAIN_FUNC_SP\r
+ .endif\r
+\r
+ .if .TMS470_16BIS\r
+\r
+;****************************************************************************\r
+;* 16 BIT STATE BOOT ROUTINE *\r
+;****************************************************************************\r
+\r
+ .if __TI_ARM_V7M__ | __TI_ARM_V6M0__\r
+ .thumb\r
+ .else\r
+ .arm\r
+ .endif\r
+\r
+ .global __stack\r
+\r
+;****************************************************************************\r
+;* STACK ADDRESSES *\r
+;****************************************************************************\r
+ .sect ".bootCode"\r
+ .global __IRQ_STACK_END\r
+ .global __FIQ_STACK_END\r
+ .global __ABORT_STACK_END\r
+ .global __UND_STACK_END\r
+ .global __SVC_STACK_END\r
+IRQ_STACK_ADDR .long __IRQ_STACK_END\r
+FIQ_STACK_ADDR .long __FIQ_STACK_END\r
+ABORT_STACK_ADDR .long __ABORT_STACK_END\r
+UND_STACK_ADDR .long __UND_STACK_END\r
+SVC_STACK_ADDR .long __SVC_STACK_END\r
+\r
+;***************************************************************\r
+;* DEFINE THE USER MODE STACK (DEFAULT SIZE IS 512)\r
+;***************************************************************\r
+__stack:.usect ".stack", 0, 4\r
+\r
+ .global _c_int00\r
+ .sect ".bootCode"\r
+;***************************************************************\r
+;* FUNCTION DEF: _c_int00\r
+;***************************************************************\r
+_c_int00: .asmfunc stack_usage(0)\r
+\r
+ .if !__TI_ARM_V7M__ & !__TI_ARM_V6M0__\r
+ .if __TI_NEON_SUPPORT__ | __TI_VFP_SUPPORT__\r
+ ;*------------------------------------------------------\r
+ ;* SETUP PRIVILEGED AND USER MODE ACCESS TO COPROCESSORS\r
+ ;* 10 AND 11, REQUIRED TO ENABLE NEON/VFP\r
+ ;* COPROCESSOR ACCESS CONTROL REG\r
+ ;* BITS [23:22] - CP11, [21:20] - CP10\r
+ ;* SET TO 0b11 TO ENABLE USER AND PRIV MODE ACCESS\r
+ ;*------------------------------------------------------\r
+ MRC p15,#0x0,r0,c1,c0,#2\r
+ MOV r3,#0xf00000\r
+ ORR r0,r0,r3\r
+ MCR p15,#0x0,r0,c1,c0,#2\r
+\r
+ ;*------------------------------------------------------\r
+ ; SET THE EN BIT, FPEXC[30] TO ENABLE NEON AND VFP\r
+ ;*------------------------------------------------------\r
+ MOV r0,#0x40000000\r
+ FMXR FPEXC,r0\r
+ .endif ; __TI_NEON_SUPPORT__ | __TI_VFP_SUPPORT__\r
+ \r
+ ;*------------------------------------------------------\r
+ ;* SET TO IRQ MODE\r
+ ;*------------------------------------------------------\r
+ MRS r0, cpsr\r
+ BIC r0, r0, #0x1F ; CLEAR MODES\r
+ ORR r0, r0, #0x12 ; SET IRQ MODE\r
+ MSR cpsr_cf, r0\r
+\r
+ ;*------------------------------------------------------\r
+ ;* INITIALIZE THE IRQ MODE STACK\r
+ ;*------------------------------------------------------\r
+ .if __TI_AVOID_EMBEDDED_CONSTANTS\r
+ MOVW sp, IRQ_STACK_ADDR\r
+ MOVT sp, IRQ_STACK_ADDR\r
+ .else\r
+ LDR sp, IRQ_STACK_ADDR\r
+ .endif\r
+\r
+ ;*------------------------------------------------------\r
+ ;* SET TO FIQ MODE\r
+ ;*------------------------------------------------------\r
+ MRS r0, cpsr\r
+ BIC r0, r0, #0x1F ; CLEAR MODES\r
+ ORR r0, r0, #0x11 ; SET FRQ MODE\r
+ MSR cpsr_cf, r0\r
+\r
+ ;*------------------------------------------------------\r
+ ;* INITIALIZE THE FIQ MODE STACK\r
+ ;*------------------------------------------------------\r
+ .if __TI_AVOID_EMBEDDED_CONSTANTS\r
+ MOVW sp, FIQ_STACK_ADDR\r
+ MOVT sp, FIQ_STACK_ADDR\r
+ .else\r
+ LDR sp, FIQ_STACK_ADDR\r
+ .endif\r
+\r
+ ;*------------------------------------------------------\r
+ ;* SET TO ABORT` MODE\r
+ ;*------------------------------------------------------\r
+ MRS r0, cpsr\r
+ BIC r0, r0, #0x1F ; CLEAR MODES\r
+ ORR r0, r0, #0x17 ; SET ABORT MODE\r
+ MSR cpsr_cf, r0\r
+\r
+ ;*------------------------------------------------------\r
+ ;* INITIALIZE THE ABORT MODE STACK\r
+ ;*------------------------------------------------------\r
+ .if __TI_AVOID_EMBEDDED_CONSTANTS\r
+ MOVW sp, ABORT_STACK_ADDR\r
+ MOVT sp, ABORT_STACK_ADDR\r
+ .else\r
+ LDR sp, ABORT_STACK_ADDR\r
+ .endif\r
+\r
+ ;*------------------------------------------------------\r
+ ;* SET TO UNDEFINED MODE\r
+ ;*------------------------------------------------------\r
+ MRS r0, cpsr\r
+ BIC r0, r0, #0x1F ; CLEAR MODES\r
+ ORR r0, r0, #0x1B ; SET UNDEFINED MODE\r
+ MSR cpsr_cf, r0\r
+\r
+ ;*------------------------------------------------------\r
+ ;* INITIALIZE THE UNDEFINED MODE STACK\r
+ ;*------------------------------------------------------\r
+ .if __TI_AVOID_EMBEDDED_CONSTANTS\r
+ MOVW sp, UND_STACK_ADDR\r
+ MOVT sp, UND_STACK_ADDR\r
+ .else\r
+ LDR sp, UND_STACK_ADDR\r
+ .endif\r
+\r
+ ;*------------------------------------------------------\r
+ ;* SET TO SUPERVISOR MODE\r
+ ;*------------------------------------------------------\r
+ MRS r0, cpsr\r
+ BIC r0, r0, #0x1F ; CLEAR MODES\r
+ ORR r0, r0, #0x13 ; SET SUPERVISOR MODE\r
+ MSR cpsr_cf, r0\r
+\r
+ ;*------------------------------------------------------\r
+ ;* INITIALIZE THE SUPERVISOR MODE STACK\r
+ ;*------------------------------------------------------\r
+ .if __TI_AVOID_EMBEDDED_CONSTANTS\r
+ MOVW sp, SVC_STACK_ADDR\r
+ MOVT sp, SVC_STACK_ADDR\r
+ .else\r
+ LDR sp, SVC_STACK_ADDR\r
+ .endif\r
+\r
+ ;*------------------------------------------------------\r
+ ;* SET TO SYSTEM MODE\r
+ ;*------------------------------------------------------\r
+ MRS r0, cpsr\r
+ BIC r0, r0, #0x1F ; CLEAR MODES\r
+ ORR r0, r0, #0x1F ; SET SYSTEM MODE\r
+ MSR cpsr_cf, r0\r
+\r
+ ;*------------------------------------------------------\r
+ ;* INITIALIZE THE USER MODE STACK\r
+ ;*------------------------------------------------------\r
+ .if __TI_AVOID_EMBEDDED_CONSTANTS\r
+ MOVW sp, __stack\r
+ MOVT sp, __stack\r
+ MOVW r0, __STACK_SIZE\r
+ MOVT r0, __STACK_SIZE\r
+ .else\r
+ LDR sp, c_stack\r
+ LDR r0, c_STACK_SIZE\r
+ .endif\r
+ ADD sp, sp, r0\r
+\r
+ ;*-----------------------------------------------------\r
+ ;* ALIGN THE STACK TO 64-BITS IF EABI.\r
+ ;*-----------------------------------------------------\r
+ .if __TI_EABI_ASSEMBLER\r
+ BIC sp, sp, #0x07 ; Clear upper 3 bits for 64-bit alignment.\r
+ .endif\r
+\r
+ ;*-----------------------------------------------------\r
+ ;* SAVE CURRENT STACK POINTER FOR SDP ANALYSIS\r
+ ;*-----------------------------------------------------\r
+ .if __TI_AVOID_EMBEDDED_CONSTANTS\r
+ MOVW r0, MAIN_FUNC_SP\r
+ MOVT r0, MAIN_FUNC_SP\r
+ .else\r
+ LDR r0, c_mf_sp\r
+ .endif\r
+ STR sp, [r0]\r
+\r
+ BL __mpu_init\r
+ ;------------------------------------------------------\r
+ ;* SET TO SYS MODE\r
+ ;*------------------------------------------------------\r
+ MRS r0, cpsr\r
+ BIC r0, r0, #0x1F ; CLEAR MODES\r
+ ORR r0, r0, #0x1F ; SET SYS MODE\r
+ MSR cpsr_cf, r0\r
+\r
+ ;*------------------------------------------------------\r
+ ;* CHANGE TO 16 BIT STATE\r
+ ;*------------------------------------------------------\r
+ ADD r0, pc, #1\r
+ BX r0\r
+\r
+ .thumb\r
+ .else ; !__TI_ARM_V7M & !__TI_ARM_V6M0\r
+ .if __TI_TMS470_V7M4__ & __TI_VFP_SUPPORT__\r
+ .thumb\r
+ ;*------------------------------------------------------\r
+ ;* SETUP FULL ACCESS TO COPROCESSORS 10 AND 11,\r
+ ;* REQUIRED FOR FP. COPROCESSOR ACCESS CONTROL REG\r
+ ;* BITS [23:22] - CP11, [21:20] - CP10\r
+ ;* SET TO 0b11 TO ENABLE FULL ACCESS\r
+ ;*------------------------------------------------------\r
+cpacr .set 0xE000ED88 ; CAPCR address\r
+ MOVW r1, #cpacr & 0xFFFF\r
+ MOVT r1, #cpacr >> 16\r
+ LDR r0, [ r1 ]\r
+ MOV r3, #0xf0\r
+ ORR r0,r0,r3, LSL #16\r
+ STR r0, [ r1 ]\r
+ .thumb\r
+ .endif ; __TI_TMS470_V7M4__ & __TI_VFP_SUPPORT__\r
+ .endif ; !__TI_ARM_V7M & !__TI_ARM_V6M0__\r
+\r
+ ;*------------------------------------------------------\r
+ ;* Perform all the required initializations when\r
+ ;* _system_pre_init() returns non-zero:\r
+ ;* - Process BINIT Table\r
+ ;* - Perform C auto initialization\r
+ ;* - Call global constructors\r
+ ;*------------------------------------------------------\r
+ BL PRE_INIT_RTN\r
+ CMP R0, #0\r
+ BEQ bypass_auto_init\r
+ BL AUTO_INIT_RTN\r
+bypass_auto_init:\r
+\r
+ ;*------------------------------------------------------\r
+ ;* CALL APPLICATION\r
+ ;*------------------------------------------------------\r
+ BL ARGS_MAIN_RTN\r
+\r
+ ;*------------------------------------------------------\r
+ ;* IF APPLICATION DIDN'T CALL EXIT, CALL EXIT(1)\r
+ ;*------------------------------------------------------\r
+ MOVS r0, #1\r
+ BL EXIT_RTN\r
+\r
+ ;*------------------------------------------------------\r
+ ;* DONE, LOOP FOREVER\r
+ ;*------------------------------------------------------\r
+L1: B L1\r
+ .endasmfunc\r
+\r
+;***************************************************************\r
+;* FUNCTION DEF: HF\r
+;***************************************************************\r
+ .global HF\r
+\r
+HF: .asmfunc stack_usage(0)\r
+L2: B L2\r
+ .endasmfunc\r
+\r
+ .else ; !.TMS470_16BIS\r
+\r
+;****************************************************************************\r
+;* 32 BIT STATE BOOT ROUTINE *\r
+;****************************************************************************\r
+ .global __stack\r
+\r
+;****************************************************************************\r
+;* STACK ADDRESSES *\r
+;****************************************************************************\r
+ .sect ".bootCode"\r
+ .global __IRQ_STACK_END\r
+ .global __FIQ_STACK_END\r
+ .global __ABORT_STACK_END\r
+ .global __UND_STACK_END\r
+ .global __SVC_STACK_END\r
+IRQ_STACK_ADDR .long __IRQ_STACK_END\r
+FIQ_STACK_ADDR .long __FIQ_STACK_END\r
+ABORT_STACK_ADDR .long __ABORT_STACK_END\r
+UND_STACK_ADDR .long __UND_STACK_END\r
+SVC_STACK_ADDR .long __SVC_STACK_END\r
+;***************************************************************\r
+;* DEFINE THE USER MODE STACK (DEFAULT SIZE IS 512)\r
+;***************************************************************\r
+__stack:.usect ".stack", 0, 4\r
+\r
+ .global _c_int00\r
+;***************************************************************\r
+;* FUNCTION DEF: _c_int00\r
+;***************************************************************\r
+_c_int00: .asmfunc stack_usage(0)\r
+\r
+ .if __TI_NEON_SUPPORT__ | __TI_VFP_SUPPORT__\r
+ ;*------------------------------------------------------\r
+ ;* SETUP PRIVILEGED AND USER MODE ACCESS TO COPROCESSORS\r
+ ;* 10 AND 11, REQUIRED TO ENABLE NEON/VFP\r
+ ;* COPROCESSOR ACCESS CONTROL REG\r
+ ;* BITS [23:22] - CP11, [21:20] - CP10\r
+ ;* SET TO 0b11 TO ENABLE USER AND PRIV MODE ACCESS\r
+ ;*------------------------------------------------------\r
+ MRC p15,#0x0,r0,c1,c0,#2\r
+ MOV r3,#0xf00000\r
+ ORR r0,r0,r3\r
+ MCR p15,#0x0,r0,c1,c0,#2\r
+\r
+ ;*------------------------------------------------------\r
+ ; SET THE EN BIT, FPEXC[30] TO ENABLE NEON AND VFP\r
+ ;*------------------------------------------------------\r
+ MOV r0,#0x40000000\r
+ FMXR FPEXC,r0\r
+ .endif\r
+ ;*------------------------------------------------------\r
+ ;* SET TO IRQ MODE\r
+ ;*------------------------------------------------------\r
+ MRS r0, cpsr\r
+ BIC r0, r0, #0x1F ; CLEAR MODES\r
+ ORR r0, r0, #0x12 ; SET IRQ MODE\r
+ MSR cpsr_cf, r0\r
+\r
+ ;*------------------------------------------------------\r
+ ;* INITIALIZE THE IRQ MODE STACK\r
+ ;*------------------------------------------------------\r
+ .if __TI_AVOID_EMBEDDED_CONSTANTS\r
+ MOVW sp, IRQ_STACK_ADDR\r
+ MOVT sp, IRQ_STACK_ADDR\r
+ .else\r
+ LDR sp, IRQ_STACK_ADDR\r
+ .endif\r
+\r
+ ;*------------------------------------------------------\r
+ ;* SET TO FIQ MODE\r
+ ;*------------------------------------------------------\r
+ MRS r0, cpsr\r
+ BIC r0, r0, #0x1F ; CLEAR MODES\r
+ ORR r0, r0, #0x11 ; SET FRQ MODE\r
+ MSR cpsr_cf, r0\r
+\r
+ ;*------------------------------------------------------\r
+ ;* INITIALIZE THE FIQ MODE STACK\r
+ ;*------------------------------------------------------\r
+ .if __TI_AVOID_EMBEDDED_CONSTANTS\r
+ MOVW sp, FIQ_STACK_ADDR\r
+ MOVT sp, FIQ_STACK_ADDR\r
+ .else\r
+ LDR sp, FIQ_STACK_ADDR\r
+ .endif\r
+\r
+ ;*------------------------------------------------------\r
+ ;* SET TO ABORT` MODE\r
+ ;*------------------------------------------------------\r
+ MRS r0, cpsr\r
+ BIC r0, r0, #0x1F ; CLEAR MODES\r
+ ORR r0, r0, #0x17 ; SET ABORT MODE\r
+ MSR cpsr_cf, r0\r
+\r
+ ;*------------------------------------------------------\r
+ ;* INITIALIZE THE ABORT MODE STACK\r
+ ;*------------------------------------------------------\r
+ .if __TI_AVOID_EMBEDDED_CONSTANTS\r
+ MOVW sp, ABORT_STACK_ADDR\r
+ MOVT sp, ABORT_STACK_ADDR\r
+ .else\r
+ LDR sp, ABORT_STACK_ADDR\r
+ .endif\r
+\r
+ ;*------------------------------------------------------\r
+ ;* SET TO UNDEFINED MODE\r
+ ;*------------------------------------------------------\r
+ MRS r0, cpsr\r
+ BIC r0, r0, #0x1F ; CLEAR MODES\r
+ ORR r0, r0, #0x1B ; SET UNDEFINED MODE\r
+ MSR cpsr_cf, r0\r
+\r
+ ;*------------------------------------------------------\r
+ ;* INITIALIZE THE UNDEFINED MODE STACK\r
+ ;*------------------------------------------------------\r
+ .if __TI_AVOID_EMBEDDED_CONSTANTS\r
+ MOVW sp, UND_STACK_ADDR\r
+ MOVT sp, UND_STACK_ADDR\r
+ .else\r
+ LDR sp, UND_STACK_ADDR\r
+ .endif\r
+\r
+ ;*------------------------------------------------------\r
+ ;* SET TO SUPERVISOR MODE\r
+ ;*------------------------------------------------------\r
+ MRS r0, cpsr\r
+ BIC r0, r0, #0x1F ; CLEAR MODES\r
+ ORR r0, r0, #0x13 ; SET SUPERVISOR MODE\r
+ MSR cpsr_cf, r0\r
+\r
+ ;*------------------------------------------------------\r
+ ;* INITIALIZE THE SUPERVISOR MODE STACK\r
+ ;*------------------------------------------------------\r
+ .if __TI_AVOID_EMBEDDED_CONSTANTS\r
+ MOVW sp, SVC_STACK_ADDR\r
+ MOVT sp, SVC_STACK_ADDR\r
+ .else\r
+ LDR sp, SVC_STACK_ADDR\r
+ .endif\r
+\r
+ ;*------------------------------------------------------\r
+ ;* SET TO SYSTEM MODE\r
+ ;*------------------------------------------------------\r
+ MRS r0, cpsr\r
+ BIC r0, r0, #0x1F ; CLEAR MODES\r
+ ORR r0, r0, #0x1F ; SET SYSTEM MODE\r
+ MSR cpsr_cf, r0\r
+\r
+ ;*------------------------------------------------------\r
+ ;* INITIALIZE THE USER MODE STACK\r
+ ;*------------------------------------------------------\r
+ .if __TI_AVOID_EMBEDDED_CONSTANTS\r
+ MOVW sp, __stack\r
+ MOVT sp, __stack\r
+ MOVW r0, __STACK_SIZE\r
+ MOVT r0, __STACK_SIZE\r
+ .else\r
+ LDR sp, c_stack\r
+ LDR r0, c_STACK_SIZE\r
+ .endif\r
+ ADD sp, sp, r0\r
+\r
+ ;*-----------------------------------------------------\r
+ ;* ALIGN THE STACK TO 64-BITS IF EABI.\r
+ ;*-----------------------------------------------------\r
+ .if __TI_EABI_ASSEMBLER\r
+ BIC sp, sp, #0x07 ; Clear upper 3 bits for 64-bit alignment.\r
+ .endif\r
+\r
+ ;*-----------------------------------------------------\r
+ ;* SAVE CURRENT STACK POINTER FOR SDP ANALYSIS\r
+ ;*-----------------------------------------------------\r
+ .if __TI_AVOID_EMBEDDED_CONSTANTS\r
+ MOVW r0, MAIN_FUNC_SP\r
+ MOVT r0, MAIN_FUNC_SP\r
+ .else\r
+ LDR r0, c_mf_sp\r
+ .endif\r
+ STR sp, [r0]\r
+\r
+ ;*------------------------------------------------------\r
+ ;* Call the __mpu_init hook function.\r
+ ;*------------------------------------------------------\r
+ BL __mpu_init\r
+\r
+ ;*------------------------------------------------------\r
+ ;* SET TO SYSTEM MODE\r
+ ;*------------------------------------------------------\r
+ MRS r0, cpsr\r
+ BIC r0, r0, #0x1F ; CLEAR MODES\r
+ ORR r0, r0, #0x1F ; SET SYSTEM MODE\r
+ MSR cpsr_cf, r0\r
+\r
+ ;*------------------------------------------------------\r
+ ;* Perform all the required initializations when\r
+ ;* _system_pre_init() returns non-zero:\r
+ ;* - Process BINIT Table\r
+ ;* - Perform C auto initialization\r
+ ;* - Call global constructors\r
+ ;*------------------------------------------------------\r
+ BL PRE_INIT_RTN\r
+ CMP R0, #0\r
+ BEQ bypass_auto_init\r
+ BL AUTO_INIT_RTN\r
+bypass_auto_init:\r
+\r
+ ;*------------------------------------------------------\r
+ ;* CALL APPLICATION\r
+ ;*------------------------------------------------------\r
+ BL ARGS_MAIN_RTN\r
+\r
+ ;*------------------------------------------------------\r
+ ;* IF APPLICATION DIDN'T CALL EXIT, CALL EXIT(1)\r
+ ;*------------------------------------------------------\r
+ MOV R0, #1\r
+ BL EXIT_RTN\r
+\r
+ ;*------------------------------------------------------\r
+ ;* DONE, LOOP FOREVER\r
+ ;*------------------------------------------------------\r
+L1: B L1\r
+ .endasmfunc\r
+\r
+;***************************************************************\r
+;* FUNCTION DEF: HF\r
+;***************************************************************\r
+ .global HF\r
+HF: .asmfunc stack_usage(0)\r
+L2: B L2\r
+ .endasmfunc\r
+\r
+ .endif ; !.TMS470_16BIS\r
+\r
+;***************************************************************\r
+;* CONSTANTS USED BY THIS MODULE\r
+;***************************************************************\r
+ .if !__TI_AVOID_EMBEDDED_CONSTANTS\r
+c_stack .long __stack\r
+c_STACK_SIZE .long __STACK_SIZE\r
+c_mf_sp .long MAIN_FUNC_SP\r
+ .endif\r
+\r
+ .if __TI_EABI_ASSEMBLER\r
+ .data\r
+ .align 4\r
+_stkchk_called:\r
+ .field 0,32\r
+ .else\r
+ .sect ".cinit"\r
+ .align 4\r
+ .field 4,32\r
+ .field _stkchk_called+0,32\r
+ .field 0,32\r
+\r
+ .bss _stkchk_called,4,4\r
+ .symdepend ".cinit", ".bss"\r
+ .symdepend ".cinit", ".text"\r
+ .symdepend ".bss", ".text"\r
+ .endif\r
+\r
+;******************************************************\r
+;* UNDEFINED REFERENCES *\r
+;******************************************************\r
+ .global _stkchk_called\r
+ .global __STACK_SIZE\r
+ .global PRE_INIT_RTN\r
+ .global AUTO_INIT_RTN\r
+ .global ARGS_MAIN_RTN\r
+ .global MAIN_FUNC_SP\r
+ .global EXIT_RTN\r
+ .weak __mpu_init\r
+ .global undefInstructionExptnHandler\r
+ .global swIntrExptnHandler\r
+ .global prefetchAbortExptnHandler\r
+ .global dataAbortExptnHandler\r
+ .global rsvdExptnHandler\r
+ .global irqExptnHandler\r
+ .global fiqExptnHandler\r
+\r
+;****************************************************************************\r
+; Setup reserved Handler\r
+;****************************************************************************\r
+ .global _cslRsvdHandler\r
+_cslRsvdHandler:\r
+ .asmfunc\r
+ b _cslRsvdHandler\r
+ .endasmfunc\r
+;****************************************************************************\r
+; Setup Reset Vectors always in ARM mode\r
+;****************************************************************************\r
+ .arm\r
+ .global _resetvectors\r
+ .sect ".rstvectors"\r
+_resetvectors:\r
+ .asmfunc\r
+ LDR pc, c_int00_addr ; Reset\r
+ LDR pc, undefInst_addr ; Undefined Instruction\r
+ LDR pc, swi_addr ; Software interrupt\r
+ LDR pc, preAbort_addr ; Abort (prefetch)\r
+ LDR pc, dataAbort_addr ; Abort (data)\r
+ LDR pc, rsvd_addr ; rsvd\r
+ LDR pc, irq_addr ; IRQ\r
+ LDR pc, fiq_addr ; FIQ\r
+ .endasmfunc\r
+\r
+\r
+c_int00_addr .long _c_int00\r
+undefInst_addr .long undefInstructionExptnHandler\r
+swi_addr .long swIntrExptnHandler\r
+preAbort_addr .long prefetchAbortExptnHandler\r
+dataAbort_addr .long dataAbortExptnHandler\r
+rsvd_addr .long _cslRsvdHandler\r
+irq_addr .long irqExptnHandler\r
+fiq_addr .long fiqExptnHandler\r
+ .end\r
diff --git a/packages/ti/board/diag/common/am64x/linker_mcu1_0.lds b/packages/ti/board/diag/common/am64x/linker_mcu1_0.lds
--- /dev/null
@@ -0,0 +1,92 @@
+/* Linker Settings */\r
+--retain="*(.bootCode)"\r
+--retain="*(.startupCode)"\r
+--retain="*(.startupData)"\r
+--retain="*(.intvecs)"\r
+--retain="*(.intc_text)"\r
+--retain="*(.rstvectors)"\r
+--retain="*(.irqStack)"\r
+--retain="*(.fiqStack)"\r
+--retain="*(.abortStack)"\r
+--retain="*(.undStack)"\r
+--retain="*(.svcStack)"\r
+--fill_value=0\r
+--stack_size=0x2000\r
+--heap_size=0x1000\r
+--entry_point=_resetvectors /* Default C RTS boot.asm */\r
+\r
+-stack 0x2000 /* SOFTWARE STACK SIZE */\r
+-heap 0x2000 /* HEAP AREA SIZE */\r
+\r
+/* Stack Sizes for various modes */\r
+__IRQ_STACK_SIZE = 0x1000;\r
+__FIQ_STACK_SIZE = 0x1000;\r
+__ABORT_STACK_SIZE = 0x1000;\r
+__UND_STACK_SIZE = 0x1000;\r
+__SVC_STACK_SIZE = 0x1000;\r
+\r
+/* Memory Map */\r
+MEMORY\r
+{\r
+ \r
+ /* Reserved for SBL code/data */\r
+ SBL_RSVD (X) : origin=0x70000000 length=0x80000\r
+ \r
+ /* Reset Vectors base address(RESET_VECTORS) should be 64 bytes aligned */\r
+ RESET_VECTORS (X) : origin=0x70080000 length=0x100\r
+ /* am64x MCMS3 locations */\r
+ MSMC3 (RWIX) : origin=0x70080100 length=0x40000 - 0x1100\r
+\r
+ VECTORS (X) : origin=0x700BF000 length=0x1000\r
+ /* Reserved for SYSFW Secure Proxy */\r
+ MSMC3_H (RWIX) : origin=0x700C0000 length=0x100000 \r
+\r
+ /* Reserved by ROM for SYSFW */\r
+ SYSFW_RSVD_1 (X) : origin=0x71C00000 length=0x20000 \r
+ SYSFW_RSVD_2 (X) : origin=0x71E00000 length=0x20000 \r
+\r
+ DDR0 (RWIX) : origin=0x80000000 length=0x80000000 /* 2GB */\r
+}\r
+\r
+/* Section Configuration */\r
+SECTIONS\r
+{\r
+ /* 'intvecs' and 'intc_text' sections shall be placed within */\r
+ /* a range of +\- 16 MB */\r
+ .intvecs : {} palign(8) > VECTORS\r
+ .intc_text : {} palign(8) > VECTORS\r
+ .rstvectors : {} palign(8) > RESET_VECTORS \r
+ .bootCode : {} palign(8) > MSMC3\r
+ .startupCode : {} palign(8) > MSMC3\r
+ .startupData : {} palign(8) > MSMC3, type = NOINIT\r
+ .text : {} palign(8) > MSMC3\r
+ .const : {} palign(8) > MSMC3\r
+ .cinit : {} palign(8) > MSMC3\r
+ .pinit : {} palign(8) > MSMC3\r
+ .bss : {} align(4) > MSMC3\r
+ .far : {} align(4) > MSMC3\r
+ .data : {} palign(128) > MSMC3\r
+ .boardcfg_data : {} palign(128) > MSMC3\r
+ .sysmem : {} > MSMC3\r
+ .data_buffer : {} palign(128) > MSMC3\r
+\r
+ /* USB or any other LLD buffer for benchmarking */\r
+ .benchmark_buffer (NOLOAD) {} ALIGN (8) > DDR0\r
+\r
+ .stack : {} align(4) > MSMC3 (HIGH)\r
+ .irqStack : {. = . + __IRQ_STACK_SIZE;} align(4) > MSMC3 (HIGH)\r
+ RUN_START(__IRQ_STACK_START)\r
+ RUN_END(__IRQ_STACK_END)\r
+ .fiqStack : {. = . + __FIQ_STACK_SIZE;} align(4) > MSMC3 (HIGH)\r
+ RUN_START(__FIQ_STACK_START)\r
+ RUN_END(__FIQ_STACK_END)\r
+ .abortStack : {. = . + __ABORT_STACK_SIZE;} align(4) > MSMC3 (HIGH)\r
+ RUN_START(__ABORT_STACK_START)\r
+ RUN_END(__ABORT_STACK_END)\r
+ .undStack : {. = . + __UND_STACK_SIZE;} align(4) > MSMC3 (HIGH)\r
+ RUN_START(__UND_STACK_START)\r
+ RUN_END(__UND_STACK_END)\r
+ .svcStack : {. = . + __SVC_STACK_SIZE;} align(4) > MSMC3 (HIGH)\r
+ RUN_START(__SVC_STACK_START)\r
+ RUN_END(__SVC_STACK_END)\r
+}\r
diff --git a/packages/ti/board/diag/common/am64x/linker_mpu1_0.lds b/packages/ti/board/diag/common/am64x/linker_mpu1_0.lds
--- /dev/null
@@ -0,0 +1,192 @@
+__STACK_SIZE = 0x20000;\r
+__TI_STACK_SIZE = __STACK_SIZE;\r
+\r
+MEMORY\r
+{\r
+ /* am64x MCMS3 locations */\r
+ /* am64x Reserved Memory for ARM Trusted Firmware */\r
+ MSMC3_ARM_STARTUP (RWIX) : ORIGIN = 0x000070000000, LENGTH = 0x800\r
+ MSMC_MPU2 (RWX) : ORIGIN = 0x000070000800, LENGTH = 0x800\r
+ MSMC_MPU1 (RWX) : ORIGIN = 0x000070001000, LENGTH = 0x200000-0x1000\r
+ DDR_MPU1 (RWX) : ORIGIN = 0x80000000, LENGTH = 0x80000000\r
+\r
+}\r
+REGION_ALIAS("REGION_TEXT_EL3", MSMC_MPU2);\r
+REGION_ALIAS("BOOTVECTOR_EL3", MSMC_MPU2);\r
+REGION_ALIAS("BOOTVECTOR", MSMC_MPU2);\r
+REGION_ALIAS("REGION_TEXT", MSMC_MPU1);\r
+REGION_ALIAS("REGION_BSS", MSMC_MPU1);\r
+REGION_ALIAS("REGION_DATA", MSMC_MPU1);\r
+REGION_ALIAS("REGION_STACK", MSMC_MPU1);\r
+REGION_ALIAS("REGION_HEAP", MSMC_MPU1);\r
+REGION_ALIAS("REGION_ARM_EXIDX", MSMC_MPU1);\r
+REGION_ALIAS("REGION_ARM_EXTAB", MSMC_MPU1);\r
+REGION_ALIAS("REGION_TEXT_STARTUP", MSMC3_ARM_STARTUP);\r
+REGION_ALIAS("REGION_DATA_BUFFER", MSMC_MPU1);\r
+REGION_ALIAS("IPC_DATA_BUFFER_1", MSMC_MPU1);\r
+\r
+SECTIONS {\r
+\r
+ .vecs : {\r
+ *(.vecs)\r
+ } > BOOTVECTOR AT> MSMC_MPU2\r
+\r
+ .vectors : {\r
+ *(.vectors)\r
+ } > BOOTVECTOR_EL3 AT> MSMC_MPU2\r
+ .text.el3 : {\r
+ *(.text.el3)\r
+ /* Ensure 8-byte alignment for descriptors and ensure inclusion */\r
+ . = ALIGN(8);\r
+ __RT_SVC_DESCS_START__ = .;\r
+ KEEP(*(rt_svc_descs))\r
+ __RT_SVC_DESCS_END__ = .;\r
+ } > REGION_TEXT_EL3 AT> MSMC_MPU2\r
+\r
+ .text.csl_a53_startup : {\r
+ *(.text.csl_a53_startup)\r
+ *(.Entry)\r
+ } > REGION_TEXT_STARTUP AT> REGION_TEXT_STARTUP\r
+\r
+ .text : {\r
+ CREATE_OBJECT_SYMBOLS\r
+ *(.text)\r
+ *(.text.*)\r
+ . = ALIGN(0x8);\r
+ KEEP (*(.ctors))\r
+ . = ALIGN(0x4);\r
+ KEEP (*(.dtors))\r
+ . = ALIGN(0x8);\r
+ __init_array_start = .;\r
+ KEEP (*(.init_array*))\r
+ __init_array_end = .;\r
+ *(.init)\r
+ *(.fini*)\r
+ } > REGION_TEXT AT> REGION_TEXT\r
+\r
+ PROVIDE (__etext = .);\r
+ PROVIDE (_etext = .);\r
+ PROVIDE (etext = .);\r
+\r
+ .rodata : {\r
+ *(.rodata)\r
+ *(.rodata*)\r
+ } > REGION_TEXT AT> REGION_TEXT\r
+\r
+ .data_buffer : ALIGN (8) {\r
+ __data_buffer_load__ = LOADADDR (.data_buffer);\r
+ __data_buffer_start__ = .;\r
+ *(.data_buffer)\r
+ *(.data_buffer*)\r
+ . = ALIGN (8);\r
+ __data_buffer_end__ = .;\r
+ } > REGION_DATA_BUFFER AT> REGION_DATA_BUFFER\r
+\r
+ .data : ALIGN (8) {\r
+ __data_load__ = LOADADDR (.data);\r
+ __data_start__ = .;\r
+ *(.data)\r
+ *(.data*)\r
+ . = ALIGN (8);\r
+ __data_end__ = .;\r
+ } > REGION_DATA AT> REGION_TEXT\r
+\r
+ .ARM.exidx : {\r
+ __exidx_start = .;\r
+ *(.ARM.exidx* .gnu.linkonce.armexidx.*)\r
+ __exidx_end = .;\r
+ } > REGION_ARM_EXIDX AT> REGION_ARM_EXIDX\r
+\r
+ .ARM.extab : {\r
+ *(.ARM.extab* .gnu.linkonce.armextab.*)\r
+ } > REGION_ARM_EXTAB AT> REGION_ARM_EXTAB\r
+\r
+ .bss:extMemCache:ramdisk : {\r
+ } > DDR_MPU1 /* MSMC_MPU1 */\r
+\r
+ /* USB or any other LLD buffer for benchmarking */\r
+ .benchmark_buffer (NOLOAD) : ALIGN (32) {\r
+ } > DDR_MPU1\r
+\r
+ .bss:frameBuffer (NOLOAD) : ALIGN (32) {\r
+ } > DDR_MPU1\r
+\r
+ ipc_data_buffer (NOLOAD) : ALIGN (32) {\r
+ } > IPC_DATA_BUFFER_1\r
+\r
+ /* For NDK packet memory, we need to map this sections before .bss*/\r
+ .bss:NDK_PACKETMEM (NOLOAD) : ALIGN (128) {} > DDR_MPU1\r
+ .bss:NDK_MMBUFFER (NOLOAD) : ALIGN (128) {} > DDR_MPU1\r
+\r
+ .bss : {\r
+ __bss_start__ = .;\r
+ *(.shbss)\r
+ *(.bss)\r
+ *(.bss.*)\r
+ . = ALIGN (8);\r
+ __bss_end__ = .;\r
+ . = ALIGN (8);\r
+ *(COMMON)\r
+ } > REGION_BSS AT> REGION_BSS\r
+\r
+ .heap : {\r
+ __heap_start__ = .;\r
+ end = __heap_start__;\r
+ _end = end;\r
+ __end = end;\r
+ KEEP(*(.heap))\r
+ __heap_end__ = .;\r
+ __HeapLimit = __heap_end__;\r
+ } > REGION_HEAP AT> REGION_HEAP\r
+\r
+ .stack (NOLOAD) : ALIGN(16) {\r
+ _stack = .;\r
+ __stack = .;\r
+ KEEP(*(.stack))\r
+ } > REGION_STACK AT> REGION_STACK\r
+\r
+ __TI_STACK_BASE = __stack;\r
+\r
+ /* Stabs debugging sections. */\r
+ .stab 0 : { *(.stab) }\r
+ .stabstr 0 : { *(.stabstr) }\r
+ .stab.excl 0 : { *(.stab.excl) }\r
+ .stab.exclstr 0 : { *(.stab.exclstr) }\r
+ .stab.index 0 : { *(.stab.index) }\r
+ .stab.indexstr 0 : { *(.stab.indexstr) }\r
+ .comment 0 : { *(.comment) }\r
+ /*\r
+ * DWARF debug sections.\r
+ * Symbols in the DWARF debugging sections are relative to the beginning\r
+ * of the section so we begin them at 0.\r
+ */\r
+ /* DWARF 1 */\r
+ .debug 0 : { *(.debug) }\r
+ .line 0 : { *(.line) }\r
+ /* GNU DWARF 1 extensions */\r
+ .debug_srcinfo 0 : { *(.debug_srcinfo) }\r
+ .debug_sfnames 0 : { *(.debug_sfnames) }\r
+ /* DWARF 1.1 and DWARF 2 */\r
+ .debug_aranges 0 : { *(.debug_aranges) }\r
+ .debug_pubnames 0 : { *(.debug_pubnames) }\r
+ /* DWARF 2 */\r
+ .debug_info 0 : { *(.debug_info .gnu.linkonce.wi.*) }\r
+ .debug_abbrev 0 : { *(.debug_abbrev) }\r
+ .debug_line 0 : { *(.debug_line .debug_line.* .debug_line_end ) }\r
+ .debug_frame 0 : { *(.debug_frame) }\r
+ .debug_str 0 : { *(.debug_str) }\r
+ .debug_loc 0 : { *(.debug_loc) }\r
+ .debug_macinfo 0 : { *(.debug_macinfo) }\r
+ /* SGI/MIPS DWARF 2 extensions */\r
+ .debug_weaknames 0 : { *(.debug_weaknames) }\r
+ .debug_funcnames 0 : { *(.debug_funcnames) }\r
+ .debug_typenames 0 : { *(.debug_typenames) }\r
+ .debug_varnames 0 : { *(.debug_varnames) }\r
+ /* DWARF 3 */\r
+ .debug_pubtypes 0 : { *(.debug_pubtypes) }\r
+ .debug_ranges 0 : { *(.debug_ranges) }\r
+ /* DWARF Extension. */\r
+ .debug_macro 0 : { *(.debug_macro) }\r
+ .note.gnu.arm.ident 0 : { KEEP (*(.note.gnu.arm.ident)) }\r
+ /DISCARD/ : { *(.note.GNU-stack) *(.gnu_debuglink) *(.gnu.lto_*) }\r
+}\r
diff --git a/packages/ti/board/diag/temperature/src/temperature_test.c b/packages/ti/board/diag/temperature/src/temperature_test.c
index 6a3dcc26096488e02324328a5e9804a16ef52e83..7fd17bfc7becbe57e739092f5616c87ee79dce58 100755 (executable)
* using I2C interface and display it on the serial console
* by converting it to actual temperature reading(i.e; degree centigrade).
*
- * Supported SoCs: K2G, AM571x, AM572x, AM437x, AM335x, AM65xx, J721E, J7200 & TPR12
+ * Supported SoCs: K2G, AM571x, AM572x, AM437x, AM335x, AM65xx, J721E, J7200, TPR12 & AM64x
*
* Supported Platforms: evmK2G, evmAM571x, evmAM572x, idkAM437x, evmAM335x,
- * am65xx_evm, am65xx_idk, j721e_evm, j7200_evm & tpr12_evm.
+ * am65xx_evm, am65xx_idk, j721e_evm, j7200_evm, tpr12_evm & am64x_evm.
*
*/
* \param delayVal [IN] Delay count.
*
*/
-#if (!((defined(SOC_AM65XX)) || (defined(SOC_J721E)) || (defined(SOC_J7200)) || (defined(SOC_TPR12))))
+#if (!((defined(SOC_AM65XX)) || (defined(SOC_J721E)) || (defined(SOC_J7200)) || (defined(SOC_TPR12)) || (defined(SOC_AM64X))))
void BoardDiag_AppDelay(uint32_t delayVal)
{
uint32_t cnt = 0;
I2C_Params i2cParams;
I2C_HwAttrs i2cConfig;
I2C_Handle handle = NULL;
-#if ((defined(SOC_AM65XX)) || (defined(SOC_J721E)) || (defined(SOC_J7200)))
+#if ((defined(SOC_AM65XX)) || (defined(SOC_J721E)) || (defined(SOC_J7200)) || (defined(SOC_AM64X)))
bool isBoardAlpha = FALSE;
#endif
/* Initializes the I2C Parameters */
I2C_Params_init(&i2cParams);
-#if ((defined(SOC_AM65XX)) || (defined(SOC_J721E)) || (defined(SOC_J7200)) || (defined(SOC_TPR12)))
+#if ((defined(SOC_AM65XX)) || (defined(SOC_J721E)) || (defined(SOC_J7200)) || (defined(SOC_TPR12)) || (defined(SOC_AM64X)))
i2cParams.bitRate = I2C_400kHz;
#endif
/* Configures the I2C instance with the passed parameters*/
BoardDiag_convert_temp(temp));
}
-#if ((defined(SOC_AM65XX)) || (defined(SOC_J721E)) || (defined(SOC_J7200)))
+#if ((defined(SOC_AM65XX)) || (defined(SOC_J721E)) || (defined(SOC_J7200)) || (defined(SOC_AM64X)))
/* Second temperature sensor will not be aailable on initial
versions of the boards with socket */
#endif
Board_init(boardCfg);
-#if defined(SOC_AM65XX) && !defined (__aarch64__)
+#if (defined(SOC_AM65XX) || defined(SOC_AM64X)) && !defined (__aarch64__)
/* MCU I2C instance will be active by default for R5 core.
* Need update HW attrs to enable MAIN I2C instance.
*/
diff --git a/packages/ti/board/diag/temperature/src/temperature_test.h b/packages/ti/board/diag/temperature/src/temperature_test.h
index ae40e7c6d09051ac5a7f0e6a8b33a9b2b68bd616..f83ce5c8dfc026d9b20f0341c379e4ace20dccfd 100755 (executable)
#include "board.h"
#include "board_cfg.h"
-#if (defined(SOC_AM65XX) || defined(SOC_K2G) || defined(SOC_J721E) || defined(SOC_J7200) || defined(SOC_TPR12))
+#if (defined(SOC_AM65XX) || defined(SOC_K2G) || defined(SOC_J721E) || defined(SOC_J7200) || defined(SOC_TPR12) || defined(SOC_AM64X))
#include "diag_common_cfg.h"
#endif
/* Board specific definitions */
#if defined (EVM_K2G) || defined (EVM_AM335x) || defined (EVM_AM437x)
#define I2C_INSTANCE (1U)
-#elif (defined(SOC_AM65XX) || defined(SOC_J721E) || defined(SOC_J7200) || defined(SOC_TPR12))
+#elif (defined(SOC_AM65XX) || defined(SOC_J721E) || defined(SOC_J7200) || defined(SOC_TPR12) || defined(SOC_AM64X))
#define I2C_INSTANCE (BOARD_TEMP_SENSOR_I2C_INSTANCE)
#else
#define I2C_INSTANCE (0U)
#if defined(evmK2G) || defined(evmAM335x) || defined(evmAM437x) || defined(evmAM571x) || defined(evmAM572x)
#define TEMP_SLAVE_DEVICE1_ADDR (0x48U)
-#elif (defined(SOC_AM65XX) || defined(SOC_J721E) || defined(SOC_J7200))
+#elif (defined(SOC_AM65XX) || defined(SOC_J721E) || defined(SOC_J7200) || defined(SOC_AM64X))
#define TEMP_SLAVE_DEVICE1_ADDR BOARD_TEMP_SENSOR_I2C_SLAVE_DEVICE1_ADDR
#define TEMP_SLAVE_DEVICE2_ADDR BOARD_TEMP_SENSOR_I2C_SLAVE_DEVICE2_ADDR
#elif defined(SOC_TPR12)
diff --git a/packages/ti/board/src/am64x_evm/board_utils.c b/packages/ti/board/src/am64x_evm/board_utils.c
--- /dev/null
@@ -0,0 +1,73 @@
+/******************************************************************************\r
+ * Copyright (c) 2020 Texas Instruments Incorporated - http://www.ti.com\r
+ *\r
+ * Redistribution and use in source and binary forms, with or without\r
+ * modification, are permitted provided that the following conditions\r
+ * are met:\r
+ *\r
+ * Redistributions of source code must retain the above copyright\r
+ * notice, this list of conditions and the following disclaimer.\r
+ *\r
+ * Redistributions in binary form must reproduce the above copyright\r
+ * notice, this list of conditions and the following disclaimer in the\r
+ * documentation and/or other materials provided with the\r
+ * distribution.\r
+ *\r
+ * Neither the name of Texas Instruments Incorporated nor the names of\r
+ * its contributors may be used to endorse or promote products derived\r
+ * from this software without specific prior written permission.\r
+ *\r
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS\r
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT\r
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR\r
+ * A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT\r
+ * OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,\r
+ * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT\r
+ * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,\r
+ * DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY\r
+ * THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT\r
+ * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE\r
+ * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.\r
+ *\r
+ *****************************************************************************/\r
+\r
+/**\r
+ * \file board_utils.c\r
+ *\r
+ * \brief Implements multiple board utility functions\r
+ *\r
+ */\r
+\r
+#include <stdio.h>\r
+#include <string.h>\r
+#include "board_internal.h"\r
+#include "board_utils.h"\r
+#include "board_cfg.h"\r
+#include <ti/osal/osal.h>\r
+\r
+/**\r
+ * \brief Function to generate delay in micro seconds\r
+ *\r
+ * This function takes the delay parameters in usecs but the generated\r
+ * delay will be in multiples of msecs due to the osal function which\r
+ * generates delay in msecs. Delay parameter passed will be converted to\r
+ * msecs and fractional value will be adjusted to nearest msecs value.\r
+ * Minimum delay generated by this function is 1 msec.\r
+ * Function parameter is kept in usecs to match with existing\r
+ * platforms which has delay function for usecs.\r
+ *\r
+ * \param usecs [IN] Specifies the time to delay in micro seconds.\r
+ *\r
+ */\r
+void BOARD_delay(uint32_t usecs)\r
+{\r
+ uint32_t msecs;\r
+\r
+ msecs = usecs/1000;\r
+ if(usecs%1000)\r
+ {\r
+ msecs += 1;\r
+ }\r
+\r
+ Osal_delay(msecs);\r
+}\r
diff --git a/packages/ti/board/src/am64x_evm/include/board_utils.h b/packages/ti/board/src/am64x_evm/include/board_utils.h
--- /dev/null
@@ -0,0 +1,115 @@
+/******************************************************************************
+ * Copyright (c) 2020 Texas Instruments Incorporated - http://www.ti.com
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ *
+ * 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.
+ *
+ * Neither the name of Texas Instruments Incorporated 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.
+ *
+ *****************************************************************************/
+
+/**
+ * \file board_utils.h
+ *
+ * \brief Board utility functions header file
+ *
+ */
+
+#ifndef _BOARD_UTILS_H_
+#define _BOARD_UTILS_H_
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/*****************************************************************************
+ * Include Files *
+ *****************************************************************************/
+#include <ti/csl/csl_types.h>
+#include <ti/csl/cslr_device.h>
+
+#include <ti/board/board.h>
+#include <ti/csl/tistdtypes.h>
+#include <stdio.h>
+#include <stdbool.h>
+
+/**
+ * \brief Structure to configure the board I2C parameters
+ */
+typedef struct Board_I2cInitCfg_s
+{
+ /** I2C controller instance */
+ uint32_t i2cInst;
+ /** SoC domain of the I2C controller */
+ uint32_t socDomain;
+ /** I2C controller interrupt enable/disable flag */
+ bool enableIntr;
+} Board_I2cInitCfg_t;
+
+/**
+ * \brief Function to get I2C configurations used by board
+ *
+ * \return BOARD_SOK in case of success or appropriate error code.
+ *
+ */
+Board_STATUS Board_getI2cInitConfig(Board_I2cInitCfg_t *i2cCfg);
+
+/**
+ * \brief Function to configure I2C configurations used by board
+ *
+ * This function is used to set the I2C controller instance and
+ * SoC domain used by the board module for board ID info read.
+ *
+ * Usage:
+ * Call Board_setI2cInitConfig to set the I2C configurations
+ * Call Board ID info read/write
+ *
+ * \return BOARD_SOK in case of success or appropriate error code.
+ *
+ */
+Board_STATUS Board_setI2cInitConfig(Board_I2cInitCfg_t *i2cCfg);
+
+/**
+ * \brief Function to generate delay in micro seconds
+ *
+ * This function takes the delay parameters in usecs but the generated
+ * delay will be in multiples of msecs due to the osal function which
+ * generates delay in msecs. Delay parameter passed will be converted to
+ * msecs and fractional value will be adjusted to nearest msecs value.
+ * Minimum delay generated by this function is 1 msec.
+ * Function parameter is kept in usecs to match with existing
+ * platforms which has delay function for usecs.
+ *
+ * \param usecs [IN] Specifies the time to delay in micro seconds.
+ *
+ */
+void BOARD_delay(uint32_t usecs);
+
+#ifdef __cplusplus
+}
+#endif /* __cplusplus */
+
+#endif /* _BOARD_UTILS_H_ */
diff --git a/packages/ti/board/src/am64x_evm/src_files_am64x_evm.mk b/packages/ti/board/src/am64x_evm/src_files_am64x_evm.mk
index 13c98e63d23c9ecb037177c0a2d543954b60dcb1..f6f9c9a31e07a6d83be2e20dea026d4d8ff9a8de 100644 (file)
INCDIR += src/am64x_evm src/am64x_evm/include\r
\r
# Common source files across all platforms and cores\r
-SRCS_COMMON += board_init.c board_lld_init.c board_clock.c board_mmr.c board_pll.c\r
+SRCS_COMMON += board_init.c board_lld_init.c board_clock.c board_mmr.c board_pll.c board_utils.c\r
SRCS_COMMON += board_ddr.c board_info.c board_ethernet_config.c board_pinmux.c board_serdes_cfg.c AM64xx_pinmux_data.c\r
\r
PACKAGE_SRCS_COMMON = src/am64x_evm/src_files_am64x_evm.mk\r