summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--arch/arm/mach-omap2/omap5/Kconfig4
-rw-r--r--board/compulab/cl-som-am57x/Kconfig12
-rw-r--r--board/compulab/cl-som-am57x/MAINTAINERS6
-rw-r--r--board/compulab/cl-som-am57x/Makefile17
-rw-r--r--board/compulab/cl-som-am57x/cl-som-am57x.c76
-rw-r--r--board/compulab/cl-som-am57x/eth.c198
-rw-r--r--board/compulab/cl-som-am57x/mux.c123
-rw-r--r--board/compulab/cl-som-am57x/spl.c234
-rw-r--r--board/intercontrol/digsy_mtc/digsy_mtc.c4
-rw-r--r--configs/cl-som-am57x_defconfig41
-rw-r--r--doc/README.cfi31
-rw-r--r--include/configs/cl-som-am57x.h197
-rw-r--r--include/configs/omap3_logic.h6
-rwxr-xr-xtools/binman/binman.py2
14 files changed, 938 insertions, 13 deletions
diff --git a/arch/arm/mach-omap2/omap5/Kconfig b/arch/arm/mach-omap2/omap5/Kconfig
index 018e584e07..242d1ee928 100644
--- a/arch/arm/mach-omap2/omap5/Kconfig
+++ b/arch/arm/mach-omap2/omap5/Kconfig
@@ -40,6 +40,9 @@ choice
prompt "OMAP5 board select"
optional
+config TARGET_CL_SOM_AM57X
+ bool "CompuLab CL-SOM-AM57x"
+
config TARGET_CM_T54
bool "CompuLab CM-T54"
@@ -179,6 +182,7 @@ endchoice
endmenu
endif
+source "board/compulab/cl-som-am57x/Kconfig"
source "board/compulab/cm_t54/Kconfig"
source "board/ti/omap5_uevm/Kconfig"
source "board/ti/dra7xx/Kconfig"
diff --git a/board/compulab/cl-som-am57x/Kconfig b/board/compulab/cl-som-am57x/Kconfig
new file mode 100644
index 0000000000..85fc9a1fdb
--- /dev/null
+++ b/board/compulab/cl-som-am57x/Kconfig
@@ -0,0 +1,12 @@
+if TARGET_CL_SOM_AM57X
+
+config SYS_BOARD
+ default "cl-som-am57x"
+
+config SYS_VENDOR
+ default "compulab"
+
+config SYS_CONFIG_NAME
+ default "cl-som-am57x"
+
+endif
diff --git a/board/compulab/cl-som-am57x/MAINTAINERS b/board/compulab/cl-som-am57x/MAINTAINERS
new file mode 100644
index 0000000000..e0195f4610
--- /dev/null
+++ b/board/compulab/cl-som-am57x/MAINTAINERS
@@ -0,0 +1,6 @@
+CL-SOM-AM57x BOARD
+M: Uri Mashiach <uri.mashiach@compulab.co.il>
+S: Maintained
+F: board/compulab/cl-som-am57x/
+F: include/configs/cl-som-am57x.h
+F: configs/cl-som-am57x_defconfig
diff --git a/board/compulab/cl-som-am57x/Makefile b/board/compulab/cl-som-am57x/Makefile
new file mode 100644
index 0000000000..566366bf6e
--- /dev/null
+++ b/board/compulab/cl-som-am57x/Makefile
@@ -0,0 +1,17 @@
+#
+# Makefile
+#
+# (C) Copyright 2016 CompuLab, Ltd. <www.compulab.co.il>
+#
+# Author: Dmitry Lifshitz <lifshitz@compulab.co.il>
+#
+# SPDX-License-Identifier: GPL-2.0+
+#
+
+ifdef CONFIG_SPL_BUILD
+obj-y += spl.o mux.o
+else
+obj-y += cl-som-am57x.o mux.o
+endif
+
+obj-$(CONFIG_DRIVER_TI_CPSW) += eth.o
diff --git a/board/compulab/cl-som-am57x/cl-som-am57x.c b/board/compulab/cl-som-am57x/cl-som-am57x.c
new file mode 100644
index 0000000000..bdd0a2ba19
--- /dev/null
+++ b/board/compulab/cl-som-am57x/cl-som-am57x.c
@@ -0,0 +1,76 @@
+/*
+ * Board functions for CompuLab cl_som_am57x board
+ *
+ * (C) Copyright 2016 CompuLab, Ltd. http://compulab.co.il/
+ *
+ * Author: Dmitry Lifshitz <lifshitz@compulab.co.il>
+ *
+ * SPDX-License-Identifier: GPL-2.0+
+ */
+
+#include <common.h>
+#include <palmas.h>
+#include <usb.h>
+#include <asm/gpio.h>
+#include <asm/arch/mmc_host_def.h>
+#include <asm/arch/sys_proto.h>
+#include "../common/common.h"
+#include "../common/eeprom.h"
+
+DECLARE_GLOBAL_DATA_PTR;
+
+const struct omap_sysinfo sysinfo = {
+ "Board: CL-SOM-AM57x\n"
+};
+
+int board_init(void)
+{
+ /* Disable PMIC Powerhold feature, DEV_CTRL.DEV_ON = 1 */
+ palmas_i2c_write_u8(TPS65903X_CHIP_P1, 0xA0, 0x1);
+
+ gd->bd->bi_boot_params = CONFIG_SYS_SDRAM_BASE + 0x100;
+
+ return 0;
+}
+
+#ifdef CONFIG_GENERIC_MMC
+#define SB_SOM_CD_GPIO 187
+#define SB_SOM_WP_GPIO 188
+
+int board_mmc_init(bd_t *bis)
+{
+ int ret0, ret1;
+
+ ret0 = omap_mmc_init(0, 0, 0, SB_SOM_CD_GPIO, SB_SOM_WP_GPIO);
+ if (ret0)
+ printf("cl-som-am57x: failed to initialize mmc0\n");
+
+ ret1 = omap_mmc_init(1, 0, 0, -1, -1);
+ if (ret1)
+ printf("cl-som-am57x: failed to initialize mmc1\n");
+
+ return ret0 && ret1;
+}
+#endif /* CONFIG_GENERIC_MMC */
+
+#ifdef CONFIG_USB_XHCI_OMAP
+int board_usb_init(int index, enum usb_init_type init)
+{
+ setbits_le32((*prcm)->cm_l3init_usb_otg_ss1_clkctrl,
+ OTG_SS_CLKCTRL_MODULEMODE_HW | OPTFCLKEN_REFCLK960M);
+
+ return 0;
+}
+#endif /* CONFIG_USB_XHCI_OMAP */
+
+int misc_init_r(void)
+{
+ cl_print_pcb_info();
+
+ return 0;
+}
+
+u32 get_board_rev(void)
+{
+ return cl_eeprom_get_board_rev(CONFIG_SYS_I2C_EEPROM_BUS);
+}
diff --git a/board/compulab/cl-som-am57x/eth.c b/board/compulab/cl-som-am57x/eth.c
new file mode 100644
index 0000000000..0c4bf91c13
--- /dev/null
+++ b/board/compulab/cl-som-am57x/eth.c
@@ -0,0 +1,198 @@
+/*
+ * Ethernet specific code for CompuLab CL-SOM-AM57x module
+ *
+ * (C) Copyright 2016 CompuLab, Ltd. http://compulab.co.il/
+ *
+ * Author: Uri Mashiach <uri.mashiach@compulab.co.il>
+ *
+ * SPDX-License-Identifier: GPL-2.0+
+ */
+
+#include <common.h>
+#include <cpsw.h>
+#include <miiphy.h>
+#include <asm/gpio.h>
+#include <asm/arch/sys_proto.h>
+#include "../common/eeprom.h"
+
+static void cpsw_control(int enabled)
+{
+ /* VTP can be added here */
+}
+
+static struct cpsw_slave_data cl_som_am57x_cpsw_slaves[] = {
+ {
+ .slave_reg_ofs = 0x208,
+ .sliver_reg_ofs = 0xd80,
+ .phy_addr = 0,
+ .phy_if = PHY_INTERFACE_MODE_RMII,
+ },
+ {
+ .slave_reg_ofs = 0x308,
+ .sliver_reg_ofs = 0xdc0,
+ .phy_addr = 1,
+ .phy_if = PHY_INTERFACE_MODE_RMII,
+
+ },
+};
+
+static struct cpsw_platform_data cl_som_am57_cpsw_data = {
+ .mdio_base = CPSW_MDIO_BASE,
+ .cpsw_base = CPSW_BASE,
+ .mdio_div = 0xff,
+ .channels = 8,
+ .cpdma_reg_ofs = 0x800,
+ .slaves = 2,
+ .slave_data = cl_som_am57x_cpsw_slaves,
+ .ale_reg_ofs = 0xd00,
+ .ale_entries = 1024,
+ .host_port_reg_ofs = 0x108,
+ .hw_stats_reg_ofs = 0x900,
+ .bd_ram_ofs = 0x2000,
+ .mac_control = (1 << 5),
+ .control = cpsw_control,
+ .host_port_num = 0,
+ .version = CPSW_CTRL_VERSION_2,
+};
+
+/*
+ * cl_som_am57x_efuse_read_mac_addr() - read Ethernet port MAC address.
+ * The information is retrieved from the SOC's registers.
+ * @buff: read buffer.
+ * @port_num: port number.
+ */
+static void cl_som_am57x_efuse_read_mac_addr(uchar *buff, uint port_num)
+{
+ uint32_t mac_hi, mac_lo;
+
+ if (port_num) {
+ mac_lo = readl((*ctrl)->control_core_mac_id_1_lo);
+ mac_hi = readl((*ctrl)->control_core_mac_id_1_hi);
+ } else {
+ mac_lo = readl((*ctrl)->control_core_mac_id_0_lo);
+ mac_hi = readl((*ctrl)->control_core_mac_id_0_hi);
+ }
+
+ buff[0] = (mac_hi & 0xFF0000) >> 16;
+ buff[1] = (mac_hi & 0xFF00) >> 8;
+ buff[2] = mac_hi & 0xFF;
+ buff[3] = (mac_lo & 0xFF0000) >> 16;
+ buff[4] = (mac_lo & 0xFF00) >> 8;
+ buff[5] = mac_lo & 0xFF;
+}
+
+/*
+ * cl_som_am57x_handle_mac_address() - set MAC address in the U-Boot
+ * environment.
+ * The address is retrieved retrieved from an EEPROM field or from the
+ * SOC's registers.
+ * @env_name: U-Boot environment name.
+ * @field_name: EEPROM field name.
+ * @port_num: SOC's port number.
+ */
+static int cl_som_am57x_handle_mac_address(char *env_name, uint port_num)
+{
+ int ret;
+ uint8_t enetaddr[6];
+
+ ret = eth_getenv_enetaddr(env_name, enetaddr);
+ if (ret)
+ return 0;
+
+ ret = cl_eeprom_read_mac_addr(enetaddr, CONFIG_SYS_I2C_EEPROM_BUS);
+
+ if (ret || !is_valid_ethaddr(enetaddr))
+ cl_som_am57x_efuse_read_mac_addr(enetaddr, port_num);
+
+ if (!is_valid_ethaddr(enetaddr))
+ return -1;
+
+ ret = eth_setenv_enetaddr(env_name, enetaddr);
+ if (ret)
+ printf("cl-som-am57x: Failed to set Eth port %d MAC address\n",
+ port_num);
+
+ return ret;
+}
+
+#define CL_SOM_AM57X_PHY_ADDR2 0x01
+#define AR8033_PHY_DEBUG_ADDR_REG 0x1d
+#define AR8033_PHY_DEBUG_DATA_REG 0x1e
+#define AR8033_DEBUG_RGMII_RX_CLK_DLY_REG 0x00
+#define AR8033_DEBUG_RGMII_TX_CLK_DLY_REG 0x05
+#define AR8033_DEBUG_RGMII_RX_CLK_DLY_MASK (1 << 15)
+#define AR8033_DEBUG_RGMII_TX_CLK_DLY_MASK (1 << 8)
+
+/*
+ * cl_som_am57x_rgmii_clk_delay() - Set RGMII clock delay.
+ * Enable RX delay, disable TX delay.
+ */
+static void cl_som_am57x_rgmii_clk_delay(void)
+{
+ uint16_t mii_reg_val;
+ const char *devname;
+
+ devname = miiphy_get_current_dev();
+ /* PHY 2 */
+ miiphy_write(devname, CL_SOM_AM57X_PHY_ADDR2, AR8033_PHY_DEBUG_ADDR_REG,
+ AR8033_DEBUG_RGMII_RX_CLK_DLY_REG);
+ miiphy_read(devname, CL_SOM_AM57X_PHY_ADDR2, AR8033_PHY_DEBUG_DATA_REG,
+ &mii_reg_val);
+ mii_reg_val |= AR8033_DEBUG_RGMII_RX_CLK_DLY_MASK;
+ miiphy_write(devname, CL_SOM_AM57X_PHY_ADDR2, AR8033_PHY_DEBUG_DATA_REG,
+ mii_reg_val);
+
+ miiphy_write(devname, CL_SOM_AM57X_PHY_ADDR2, AR8033_PHY_DEBUG_ADDR_REG,
+ AR8033_DEBUG_RGMII_TX_CLK_DLY_REG);
+ miiphy_read(devname, CL_SOM_AM57X_PHY_ADDR2, AR8033_PHY_DEBUG_DATA_REG,
+ &mii_reg_val);
+ mii_reg_val &= ~AR8033_DEBUG_RGMII_TX_CLK_DLY_MASK;
+ miiphy_write(devname, CL_SOM_AM57X_PHY_ADDR2, AR8033_PHY_DEBUG_DATA_REG,
+ mii_reg_val);
+}
+
+#define CL_SOM_AM57X_GPIO_PHY1_RST 92 /* GPIO3_28 */
+#define CL_SOM_AM57X_RGMII_PORT1 1
+
+int board_eth_init(bd_t *bis)
+{
+ int ret;
+ uint32_t ctrl_val;
+ char *cpsw_phy_envval;
+ int cpsw_act_phy = 1;
+
+ /* SB-SOM-AM57x primary Eth (P21) is routed to RGMII1 */
+ ret = cl_som_am57x_handle_mac_address("ethaddr",
+ CL_SOM_AM57X_RGMII_PORT1);
+
+ if (ret)
+ return -1;
+
+ /* Select RGMII for GMII1_SEL */
+ ctrl_val = readl((*ctrl)->control_core_control_io1) & (~0x33);
+ ctrl_val |= 0x22;
+ writel(ctrl_val, (*ctrl)->control_core_control_io1);
+ mdelay(10);
+
+ gpio_request(CL_SOM_AM57X_GPIO_PHY1_RST, "phy1_rst");
+ gpio_direction_output(CL_SOM_AM57X_GPIO_PHY1_RST, 0);
+ mdelay(20);
+
+ gpio_set_value(CL_SOM_AM57X_GPIO_PHY1_RST, 1);
+ mdelay(20);
+
+ cpsw_phy_envval = getenv("cpsw_phy");
+ if (cpsw_phy_envval != NULL)
+ cpsw_act_phy = simple_strtoul(cpsw_phy_envval, NULL, 0);
+
+ cl_som_am57_cpsw_data.active_slave = cpsw_act_phy;
+
+ ret = cpsw_register(&cl_som_am57_cpsw_data);
+ if (ret < 0)
+ printf("Error %d registering CPSW switch\n", ret);
+
+ /* Set RGMII clock delay */
+ cl_som_am57x_rgmii_clk_delay();
+
+ return ret;
+}
diff --git a/board/compulab/cl-som-am57x/mux.c b/board/compulab/cl-som-am57x/mux.c
new file mode 100644
index 0000000000..5b7197578c
--- /dev/null
+++ b/board/compulab/cl-som-am57x/mux.c
@@ -0,0 +1,123 @@
+/*
+ * Pinmux configuration for CompuLab CL-SOM-AM57x board
+ *
+ * (C) Copyright 2016 CompuLab, Ltd. http://compulab.co.il/
+ *
+ * Author: Dmitry Lifshitz <lifshitz@compulab.co.il>
+ *
+ * SPDX-License-Identifier: GPL-2.0+
+ */
+#include <asm/arch/sys_proto.h>
+#include <asm/arch/mux_dra7xx.h>
+
+/* Serial console */
+static const struct pad_conf_entry cl_som_am57x_padconf_console[] = {
+ {UART3_RXD, (FSC | IEN | PDIS | PTU | M0)}, /* UART3_RXD */
+ {UART3_TXD, (FSC | IEN | PDIS | PTU | M0)}, /* UART3_TXD */
+};
+
+/* PMIC I2C */
+static const struct pad_conf_entry cl_som_am57x_padconf_pmic[] = {
+ {MCASP1_ACLKR, (IEN | PEN | M10)}, /* MCASP1_ACLKR.I2C4_SDA */
+ {MCASP1_FSR, (IEN | PEN | M10)}, /* MCASP1_FSR.I2C4_SCL */
+};
+
+/* Green GPIO led */
+static const struct pad_conf_entry cl_som_am57x_padconf_green_led[] = {
+ {GPMC_A15, (IDIS | PDIS | PTD | M14)}, /* GPMC_A15.GPIO2_5 */
+};
+
+/* MMC/SD Card */
+static const struct pad_conf_entry cl_som_am57x_padconf_sd_card[] = {
+ {MMC1_CLK, (IEN | PDIS | PTU | M0) }, /* MMC1_CLK */
+ {MMC1_CMD, (IEN | PDIS | PTU | M0) }, /* MMC1_CMD */
+ {MMC1_DAT0, (IEN | PDIS | PTU | M0) }, /* MMC1_DAT0 */
+ {MMC1_DAT1, (IEN | PDIS | PTU | M0) }, /* MMC1_DAT1 */
+ {MMC1_DAT2, (IEN | PDIS | PTU | M0) }, /* MMC1_DAT2 */
+ {MMC1_DAT3, (IEN | PDIS | PTU | M0) }, /* MMC1_DAT3 */
+ {MMC1_SDCD, (IEN | PEN | M14)}, /* MMC1_SDCD */
+ {MMC1_SDWP, (IEN | PEN | M14)}, /* MMC1_SDWP */
+};
+
+/* WiFi - must be in the safe mode on boot */
+static const struct pad_conf_entry cl_som_am57x_padconf_wifi[] = {
+ {UART1_CTSN, (IEN | M15)}, /* UART1_CTSN */
+ {UART1_RTSN, (IEN | M15)}, /* UART1_RTSN */
+ {UART2_RXD, (IEN | M15)}, /* UART2_RXD */
+ {UART2_TXD, (IEN | M15)}, /* UART2_TXD */
+ {UART2_CTSN, (IEN | M15)}, /* UART2_CTSN */
+ {UART2_RTSN, (IEN | M15)}, /* UART2_RTSN */
+};
+
+/* QSPI */
+static const struct pad_conf_entry cl_som_am57x_padconf_qspi[] = {
+ {GPMC_A13, (IEN | PEN | M1)}, /* GPMC_A13.QSPI1_RTCLK */
+ {GPMC_A18, (IEN | PEN | M1)}, /* GPMC_A18.QSPI1_SCLK */
+ {GPMC_A16, (IEN | PEN | M1)}, /* GPMC_A16.QSPI1_D0 */
+ {GPMC_A17, (IEN | PEN | M1)}, /* GPMC_A17.QSPI1_D1 */
+ {GPMC_CS2, (IEN | PDIS | PTU | M1)}, /* GPMC_CS2.QSPI1_CS0 */
+};
+
+/* GPIO Expander I2C */
+static const struct pad_conf_entry cl_som_am57x_padconf_i2c_gpio[] = {
+ {MCASP1_AXR0, (IEN | PEN | M10)}, /* MCASP1_AXR0.I2C5_SDA */
+ {MCASP1_AXR1, (IEN | PEN | M10)}, /* MCASP1_AXR1.I2C5_SCL */
+};
+
+/* eMMC internal storage */
+static const struct pad_conf_entry cl_som_am57x_padconf_emmc[] = {
+ {GPMC_A19, (IEN | PDIS | PTU | M1)}, /* GPMC_A19.MMC2_DAT4 */
+ {GPMC_A20, (IEN | PDIS | PTU | M1)}, /* GPMC_A20.MMC2_DAT5 */
+ {GPMC_A21, (IEN | PDIS | PTU | M1)}, /* GPMC_A21.MMC2_DAT6 */
+ {GPMC_A22, (IEN | PDIS | PTU | M1)}, /* GPMC_A22.MMC2_DAT7 */
+ {GPMC_A23, (IEN | PDIS | PTU | M1)}, /* GPMC_A23.MMC2_CLK */
+ {GPMC_A24, (IEN | PDIS | PTU | M1)}, /* GPMC_A24.MMC2_DAT0 */
+ {GPMC_A25, (IEN | PDIS | PTU | M1)}, /* GPMC_A25.MMC2_DAT1 */
+ {GPMC_A26, (IEN | PDIS | PTU | M1)}, /* GPMC_A26.MMC2_DAT2 */
+ {GPMC_A27, (IEN | PDIS | PTU | M1)}, /* GPMC_A27.MMC2_DAT3 */
+ {GPMC_CS1, (IEN | PDIS | PTU | M1)}, /* GPMC_CS1.MMC2_CMD */
+};
+
+/* usb1_drvvbus */
+static const struct pad_conf_entry cl_som_am57x_padconf_usb[] = {
+ {USB1_DRVVBUS, (M0 | FSC) }, /* USB1_DRVVBUS.USB1_DRVVBUS */
+};
+
+/* Ethernet */
+static const struct pad_conf_entry cl_som_am57x_padconf_ethernet[] = {
+ /* MDIO bus */
+ {VIN2A_D10, (PDIS | PTU | M3) }, /* VIN2A_D10.MDIO_MCLK */
+ {VIN2A_D11, (IEN | PDIS | PTU | M3) }, /* VIN2A_D11.MDIO_D */
+ /* EMAC Slave 1 at addr 0x1 - Default interface */
+ {VIN2A_D12, (IDIS | PEN | M3) }, /* VIN2A_D12.RGMII1_TXC */
+ {VIN2A_D13, (IDIS | PEN | M3) }, /* VIN2A_D13.RGMII1_TXCTL */
+ {VIN2A_D14, (IDIS | PEN | M3) }, /* VIN2A_D14.RGMII1_TXD3 */
+ {VIN2A_D15, (IDIS | PEN | M3) }, /* VIN2A_D15.RGMII1_TXD2 */
+ {VIN2A_D16, (IDIS | PEN | M3) }, /* VIN2A_D16.RGMII1_TXD1 */
+ {VIN2A_D17, (IDIS | PEN | M3) }, /* VIN2A_D17.RGMII1_TXD0 */
+ {VIN2A_D18, (IEN | PDIS | PTD | M3) }, /* VIN2A_D18.RGMII1_RXC */
+ {VIN2A_D19, (IEN | PDIS | PTD | M3) }, /* VIN2A_D19.RGMII1_RXCTL */
+ {VIN2A_D20, (IEN | PDIS | PTD | M3) }, /* VIN2A_D20.RGMII1_RXD3 */
+ {VIN2A_D21, (IEN | PDIS | PTD | M3) }, /* VIN2A_D21.RGMII1_RXD2 */
+ {VIN2A_D22, (IEN | PDIS | PTD | M3) }, /* VIN2A_D22.RGMII1_RXD1 */
+ {VIN2A_D23, (IEN | PDIS | PTD | M3) }, /* VIN2A_D23.RGMII1_RXD0 */
+ /* Eth PHY1 reset GPIOs*/
+ {VIN1B_CLK1, (IDIS | PDIS | PTD | M14)}, /* VIN1B_CLK1.GPIO2_31 */
+};
+
+#define SET_MUX(mux_array) do_set_mux32((*ctrl)->control_padconf_core_base, \
+ mux_array, ARRAY_SIZE(mux_array))
+
+void set_muxconf_regs(void)
+{
+ SET_MUX(cl_som_am57x_padconf_console);
+ SET_MUX(cl_som_am57x_padconf_pmic);
+ SET_MUX(cl_som_am57x_padconf_green_led);
+ SET_MUX(cl_som_am57x_padconf_sd_card);
+ SET_MUX(cl_som_am57x_padconf_wifi);
+ SET_MUX(cl_som_am57x_padconf_qspi);
+ SET_MUX(cl_som_am57x_padconf_i2c_gpio);
+ SET_MUX(cl_som_am57x_padconf_emmc);
+ SET_MUX(cl_som_am57x_padconf_usb);
+ SET_MUX(cl_som_am57x_padconf_ethernet);
+}
diff --git a/board/compulab/cl-som-am57x/spl.c b/board/compulab/cl-som-am57x/spl.c
new file mode 100644
index 0000000000..855678fd5f
--- /dev/null
+++ b/board/compulab/cl-som-am57x/spl.c
@@ -0,0 +1,234 @@
+/*
+ * SPL data and initialization for CompuLab CL-SOM-AM57x board
+ *
+ * (C) Copyright 2016 CompuLab, Ltd. http://compulab.co.il/
+ *
+ * Author: Uri Mashiach <uri.mashiach@compulab.co.il>
+ *
+ * SPDX-License-Identifier: GPL-2.0+
+ */
+
+#include <asm/emif.h>
+#include <asm/omap_common.h>
+#include <asm/arch/sys_proto.h>
+
+static const struct dmm_lisa_map_regs cl_som_am57x_lisa_regs = {
+ .dmm_lisa_map_3 = 0x80740300,
+ .is_ma_present = 0x1
+};
+
+void emif_get_dmm_regs(const struct dmm_lisa_map_regs **dmm_lisa_regs)
+{
+ *dmm_lisa_regs = &cl_som_am57x_lisa_regs;
+}
+
+static const struct emif_regs cl_som_am57x_emif1_ddr3_532mhz_emif_regs = {
+ .sdram_config_init = 0x61852332,
+ .sdram_config = 0x61852332,
+ .sdram_config2 = 0x00000000,
+ .ref_ctrl = 0x000040f1,
+ .ref_ctrl_final = 0x00001040,
+ .sdram_tim1 = 0xeeef36f3,
+ .sdram_tim2 = 0x348f7fda,
+ .sdram_tim3 = 0x027f88a8,
+ .read_idle_ctrl = 0x00050000,
+ .zq_config = 0x1007190b,
+ .temp_alert_config = 0x00000000,
+ .emif_ddr_phy_ctlr_1_init = 0x0034400b,
+ .emif_ddr_phy_ctlr_1 = 0x0e34400b,
+ .emif_ddr_ext_phy_ctrl_1 = 0x04040100,
+ .emif_ddr_ext_phy_ctrl_2 = 0x00740074,
+ .emif_ddr_ext_phy_ctrl_3 = 0x00780078,
+ .emif_ddr_ext_phy_ctrl_4 = 0x007c007c,
+ .emif_ddr_ext_phy_ctrl_5 = 0x007b007b,
+ .emif_rd_wr_lvl_rmp_win = 0x00000000,
+ .emif_rd_wr_lvl_rmp_ctl = 0x80000000,
+ .emif_rd_wr_lvl_ctl = 0x00000000,
+ .emif_rd_wr_exec_thresh = 0x00000305
+};
+
+/* Ext phy ctrl regs 1-35 */
+static const u32 cl_som_am57x_emif1_ddr3_ext_phy_ctrl_regs[] = {
+ 0x10040100,
+ 0x00740074,
+ 0x00780078,
+ 0x007c007c,
+ 0x007b007b,
+ 0x00800080,
+ 0x00360036,
+ 0x00340034,
+ 0x00360036,
+ 0x00350035,
+ 0x00350035,
+
+ 0x01ff01ff,
+ 0x01ff01ff,
+ 0x01ff01ff,
+ 0x01ff01ff,
+ 0x01ff01ff,
+
+ 0x00430043,
+ 0x003e003e,
+ 0x004a004a,
+ 0x00470047,
+ 0x00400040,
+
+ 0x00000000,
+ 0x00600020,
+ 0x40011080,
+ 0x08102040,
+
+ 0x00400040,
+ 0x00400040,
+ 0x00400040,
+ 0x00400040,
+ 0x00400040,
+ 0x0,
+ 0x0,
+ 0x0,
+ 0x0,
+ 0x0
+};
+
+static const struct emif_regs cl_som_am57x_emif2_ddr3_532mhz_emif_regs = {
+ .sdram_config_init = 0x61852332,
+ .sdram_config = 0x61852332,
+ .sdram_config2 = 0x00000000,
+ .ref_ctrl = 0x000040f1,
+ .ref_ctrl_final = 0x00001040,
+ .sdram_tim1 = 0xeeef36f3,
+ .sdram_tim2 = 0x348f7fda,
+ .sdram_tim3 = 0x027f88a8,
+ .read_idle_ctrl = 0x00050000,
+ .zq_config = 0x1007190b,
+ .temp_alert_config = 0x00000000,
+ .emif_ddr_phy_ctlr_1_init = 0x0034400b,
+ .emif_ddr_phy_ctlr_1 = 0x0e34400b,
+ .emif_ddr_ext_phy_ctrl_1 = 0x04040100,
+ .emif_ddr_ext_phy_ctrl_2 = 0x00740074,
+ .emif_ddr_ext_phy_ctrl_3 = 0x00780078,
+ .emif_ddr_ext_phy_ctrl_4 = 0x007c007c,
+ .emif_ddr_ext_phy_ctrl_5 = 0x007b007b,
+ .emif_rd_wr_lvl_rmp_win = 0x00000000,
+ .emif_rd_wr_lvl_rmp_ctl = 0x80000000,
+ .emif_rd_wr_lvl_ctl = 0x00000000,
+ .emif_rd_wr_exec_thresh = 0x00000305
+};
+
+static const u32 cl_som_am57x_emif2_ddr3_ext_phy_ctrl_regs[] = {
+ 0x10040100,
+ 0x00820082,
+ 0x008b008b,
+ 0x00800080,
+ 0x007e007e,
+ 0x00800080,
+ 0x00370037,
+ 0x00390039,
+ 0x00360036,
+ 0x00370037,
+ 0x00350035,
+ 0x01ff01ff,
+ 0x01ff01ff,
+ 0x01ff01ff,
+ 0x01ff01ff,
+ 0x01ff01ff,
+ 0x00540054,
+ 0x00540054,
+ 0x004e004e,
+ 0x004c004c,
+ 0x00400040,
+
+ 0x00000000,
+ 0x00600020,
+ 0x40011080,
+ 0x08102040,
+
+ 0x00400040,
+ 0x00400040,
+ 0x00400040,
+ 0x00400040,
+ 0x00400040,
+ 0x0,
+ 0x0,
+ 0x0,
+ 0x0,
+ 0x0
+};
+
+static struct vcores_data cl_som_am57x_volts = {
+ .mpu.value[OPP_NOM] = VDD_MPU_DRA7_NOM,
+ .mpu.efuse.reg[OPP_NOM] = STD_FUSE_OPP_VMIN_MPU_NOM,
+ .mpu.efuse.reg_bits = DRA752_EFUSE_REGBITS,
+ .mpu.addr = TPS659038_REG_ADDR_SMPS12,
+ .mpu.pmic = &tps659038,
+
+ .eve.value[OPP_NOM] = VDD_EVE_DRA7_NOM,
+ .eve.value[OPP_OD] = VDD_EVE_DRA7_OD,
+ .eve.value[OPP_HIGH] = VDD_EVE_DRA7_HIGH,
+ .eve.efuse.reg[OPP_NOM] = STD_FUSE_OPP_VMIN_DSPEVE_NOM,
+ .eve.efuse.reg[OPP_OD] = STD_FUSE_OPP_VMIN_DSPEVE_OD,
+ .eve.efuse.reg[OPP_HIGH] = STD_FUSE_OPP_VMIN_DSPEVE_HIGH,
+ .eve.efuse.reg_bits = DRA752_EFUSE_REGBITS,
+ .eve.addr = TPS659038_REG_ADDR_SMPS45,
+ .eve.pmic = &tps659038,
+
+ .gpu.value[OPP_NOM] = VDD_GPU_DRA7_NOM,
+ .gpu.value[OPP_OD] = VDD_GPU_DRA7_OD,
+ .gpu.value[OPP_HIGH] = VDD_GPU_DRA7_HIGH,
+ .gpu.efuse.reg[OPP_NOM] = STD_FUSE_OPP_VMIN_GPU_NOM,
+ .gpu.efuse.reg[OPP_OD] = STD_FUSE_OPP_VMIN_GPU_OD,
+ .gpu.efuse.reg[OPP_HIGH] = STD_FUSE_OPP_VMIN_GPU_HIGH,
+ .gpu.efuse.reg_bits = DRA752_EFUSE_REGBITS,
+ .gpu.addr = TPS659038_REG_ADDR_SMPS6,
+ .gpu.pmic = &tps659038,
+
+ .core.value[OPP_NOM] = VDD_CORE_DRA7_NOM,
+ .core.efuse.reg[OPP_NOM] = STD_FUSE_OPP_VMIN_CORE_NOM,
+ .core.efuse.reg_bits = DRA752_EFUSE_REGBITS,
+ .core.addr = TPS659038_REG_ADDR_SMPS7,
+ .core.pmic = &tps659038,
+
+ .iva.value[OPP_NOM] = VDD_IVA_DRA7_NOM,
+ .iva.value[OPP_OD] = VDD_IVA_DRA7_OD,
+ .iva.value[OPP_HIGH] = VDD_IVA_DRA7_HIGH,
+ .iva.efuse.reg[OPP_NOM] = STD_FUSE_OPP_VMIN_IVA_NOM,
+ .iva.efuse.reg[OPP_OD] = STD_FUSE_OPP_VMIN_IVA_OD,
+ .iva.efuse.reg[OPP_HIGH] = STD_FUSE_OPP_VMIN_IVA_HIGH,
+ .iva.efuse.reg_bits = DRA752_EFUSE_REGBITS,
+ .iva.addr = TPS659038_REG_ADDR_SMPS8,
+ .iva.pmic = &tps659038,
+};
+
+void hw_data_init(void)
+{
+ *prcm = &dra7xx_prcm;
+ *dplls_data = &dra7xx_dplls;
+ *omap_vcores = &cl_som_am57x_volts;
+ *ctrl = &dra7xx_ctrl;
+}
+
+void emif_get_reg_dump(u32 emif_nr, const struct emif_regs **regs)
+{
+ switch (emif_nr) {
+ case 1:
+ *regs = &cl_som_am57x_emif1_ddr3_532mhz_emif_regs;
+ break;
+ case 2:
+ *regs = &cl_som_am57x_emif2_ddr3_532mhz_emif_regs;
+ break;
+ }
+}
+
+void emif_get_ext_phy_ctrl_const_regs(u32 emif_nr, const u32 **regs, u32 *size)
+{
+ switch (emif_nr) {
+ case 1:
+ *regs = cl_som_am57x_emif1_ddr3_ext_phy_ctrl_regs;
+ *size = ARRAY_SIZE(cl_som_am57x_emif1_ddr3_ext_phy_ctrl_regs);
+ break;
+ case 2:
+ *regs = cl_som_am57x_emif2_ddr3_ext_phy_ctrl_regs;
+ *size = ARRAY_SIZE(cl_som_am57x_emif2_ddr3_ext_phy_ctrl_regs);
+ break;
+ }
+}
diff --git a/board/intercontrol/digsy_mtc/digsy_mtc.c b/board/intercontrol/digsy_mtc/digsy_mtc.c
index 37eb6c7624..05d673dc89 100644
--- a/board/intercontrol/digsy_mtc/digsy_mtc.c
+++ b/board/intercontrol/digsy_mtc/digsy_mtc.c
@@ -41,7 +41,7 @@ extern int usb_cpu_init(void);
#if defined(CONFIG_DIGSY_REV5)
/*
- * The M29W128GH needs a specail reset command function,
+ * The M29W128GH needs a special reset command function,
* details see the doc/README.cfi file
*/
void flash_cmd_reset(flash_info_t *info)
@@ -76,7 +76,7 @@ static void sdram_start(int hi_addr)
/*
* ATTENTION: Although partially referenced initdram does NOT make real use
* use of CONFIG_SYS_SDRAM_BASE. The code does not work if
- * CONFIG_SYS_SDRAM_BASE is something else than 0x00000000.
+ * CONFIG_SYS_SDRAM_BASE is something other than 0x00000000.
*/
phys_size_t initdram(int board_type)
diff --git a/configs/cl-som-am57x_defconfig b/configs/cl-som-am57x_defconfig
new file mode 100644
index 0000000000..9eadf42152
--- /dev/null
+++ b/configs/cl-som-am57x_defconfig
@@ -0,0 +1,41 @@
+CONFIG_ARM=y
+CONFIG_OMAP54XX=y
+# CONFIG_SPL_NAND_SUPPORT is not set
+CONFIG_TARGET_CL_SOM_AM57X=y
+CONFIG_VERSION_VARIABLE=y
+CONFIG_SPL=y
+CONFIG_HUSH_PARSER=y
+CONFIG_CMD_BOOTZ=y
+# CONFIG_CMD_IMLS is not set
+CONFIG_CMD_ASKENV=y
+# CONFIG_CMD_FLASH is not set
+CONFIG_CMD_MMC=y
+CONFIG_CMD_SF=y
+CONFIG_CMD_SPI=y
+CONFIG_CMD_I2C=y
+CONFIG_CMD_GPIO=y
+# CONFIG_CMD_SETEXPR is not set
+CONFIG_CMD_DHCP=y
+CONFIG_CMD_MII=y
+CONFIG_CMD_PING=y
+CONFIG_CMD_EXT2=y
+CONFIG_CMD_EXT4=y
+CONFIG_CMD_EXT4_WRITE=y
+CONFIG_CMD_FAT=y
+CONFIG_CMD_FS_GENERIC=y
+CONFIG_SPI_FLASH=y
+CONFIG_SPI_FLASH_BAR=y
+CONFIG_SPI_FLASH_ATMEL=y
+CONFIG_SPI_FLASH_EON=y
+CONFIG_SPI_FLASH_GIGADEVICE=y
+CONFIG_SPI_FLASH_MACRONIX=y
+CONFIG_SPI_FLASH_SPANSION=y
+CONFIG_SPI_FLASH_STMICRO=y
+CONFIG_SPI_FLASH_SST=y
+CONFIG_SPI_FLASH_WINBOND=y
+CONFIG_SYS_NS16550=y
+CONFIG_TI_QSPI=y
+CONFIG_USB=y
+CONFIG_USB_XHCI_HCD=y
+CONFIG_USB_XHCI_DWC3=y
+CONFIG_OF_LIBFDT=y
diff --git a/doc/README.cfi b/doc/README.cfi
index 81e7cf1d7e..ad52850818 100644
--- a/doc/README.cfi
+++ b/doc/README.cfi
@@ -1,7 +1,7 @@
The common CFI driver provides this weak default implementation for
flash_cmd_reset():
-void __flash_cmd_reset(flash_info_t *info)
+static void __flash_cmd_reset(flash_info_t *info)
{
/*
* We do not yet know what kind of commandset to use, so we issue
@@ -9,22 +9,43 @@ void __flash_cmd_reset(flash_info_t *info)
* that AMD flash roms ignore the Intel command.
*/
flash_write_cmd(info, 0, 0, AMD_CMD_RESET);
+ udelay(1);
flash_write_cmd(info, 0, 0, FLASH_CMD_RESET);
}
void flash_cmd_reset(flash_info_t *info)
__attribute__((weak,alias("__flash_cmd_reset")));
+Some flash chips seem to have trouble with this reset sequence.
+In this case, board-specific code can override this weak default
+version with a board-specific function.
-Some flash chips seems to have trouble with this reset sequence. In this case
-the board specific code can override this weak default version with a board
-specific function. For example the digsy_mtc board equipped with the M29W128GH
-from Numonyx needs this version to function properly:
+At the time of writing, there are two boards that define their own
+routine for this.
+
+First, the digsy_mtc board equipped with the M29W128GH from Numonyx
+needs this version to function properly:
void flash_cmd_reset(flash_info_t *info)
{
flash_write_cmd(info, 0, 0, AMD_CMD_RESET);
}
+In addition, the t3corp board defines the routine thusly:
+
+void flash_cmd_reset(flash_info_t *info)
+{
+ /*
+ * FLASH at address CONFIG_SYS_FLASH_BASE is a Spansion chip and
+ * needs the Spansion type reset commands. The other flash chip
+ * is located behind a FPGA (Xilinx DS617) and needs the Intel type
+ * reset command.
+ */
+ if (info->start[0] == CONFIG_SYS_FLASH_BASE)
+ flash_write_cmd(info, 0, 0, AMD_CMD_RESET);
+ else
+ flash_write_cmd(info, 0, 0, FLASH_CMD_RESET);
+}
+
see also:
http://www.mail-archive.com/u-boot@lists.denx.de/msg24368.html
diff --git a/include/configs/cl-som-am57x.h b/include/configs/cl-som-am57x.h
new file mode 100644
index 0000000000..8297182a6c
--- /dev/null
+++ b/include/configs/cl-som-am57x.h
@@ -0,0 +1,197 @@
+/*
+ * Configuration settings for CompuLab CL-SOM-AM57x board
+ *
+ * (C) Copyright 2016 CompuLab, Ltd. http://compulab.co.il/
+ *
+ * Author: Dmitry Lifshitz <lifshitz@compulab.co.il>
+ *
+ * SPDX-License-Identifier: GPL-2.0+
+ */
+
+#ifndef __CONFIG_CL_SOM_AM57X_H
+#define __CONFIG_CL_SOM_AM57X_H
+
+#define CONFIG_DRA7XX
+
+#define CONFIG_NR_DRAM_BANKS 2
+
+#define CONSOLEDEV "ttyO2"
+#define CONFIG_SYS_NS16550_COM3 UART3_BASE /* UART3 */
+#define CONFIG_CONS_INDEX 3
+#define CONFIG_BAUDRATE 115200
+
+#define CONFIG_SYS_OMAP_ABE_SYSCK
+
+#include <configs/ti_omap5_common.h>
+
+/* misc */
+#define CONFIG_MISC_INIT_R
+#define CONFIG_REVISION_TAG
+
+/* Status LED */
+#define CONFIG_STATUS_LED /* Status LED enabled */
+#define CONFIG_GPIO_LED
+#define CONFIG_BOARD_SPECIFIC_LED
+#define GREEN_LED_DEV 0
+ /* cl_som_am57x Green LED is GPIO2_5 */
+#define GREEN_LED_GPIO 37
+#define STATUS_LED_BIT GREEN_LED_GPIO
+#define STATUS_LED_STATE STATUS_LED_ON
+#define STATUS_LED_PERIOD (CONFIG_SYS_HZ / 2)
+
+/* PMIC I2C bus number */
+#define CONFIG_SYS_SPD_BUS_NUM 3
+
+/* SPI Flash support */
+#undef CONFIG_OMAP3_SPI
+
+#define CONFIG_TI_SPI_MMAP
+#define CONFIG_SF_DEFAULT_SPEED 48000000
+#define CONFIG_DEFAULT_SPI_MODE SPI_MODE_3
+
+/* SPI SPL defines */
+/* Offsets: 0K - SPL1, 64K - SPL2, 128K - SPL3, 192K - SPL4, 256K - U-Boot */
+#define CONFIG_SYS_SPI_U_BOOT_OFFS (256 * 1024)
+#define CONFIG_SPL_SPI_SUPPORT
+#define CONFIG_SPL_SPI_FLASH_SUPPORT
+#define CONFIG_SPL_SPI_LOAD
+
+/* SD/MMC RAW boot */
+#undef CONFIG_SPL_FS_LOAD_PAYLOAD_NAME
+#undef CONFIG_SYS_MMCSD_FS_BOOT_PARTITION
+
+/* Environment */
+#define CONFIG_ENV_SIZE (16 << 10) /* 16 KiB env size */
+#define CONFIG_ENV_VARS_UBOOT_RUNTIME_CONFIG
+
+#define CONFIG_ENV_IS_IN_SPI_FLASH
+#define CONFIG_ENV_SECT_SIZE (64 * 1024)
+#define CONFIG_ENV_OFFSET (768 * 1024)
+#define CONFIG_ENV_SPI_MAX_HZ 48000000
+
+/* EEPROM */
+#define CONFIG_SYS_I2C_EEPROM_ADDR 0x50
+#define CONFIG_SYS_I2C_EEPROM_ADDR_LEN 1
+#define CONFIG_SYS_I2C_EEPROM_BUS 3
+
+#define CONFIG_CMD_EEPROM
+#define CONFIG_CMD_EEPROM_LAYOUT
+#define CONFIG_ENV_EEPROM_IS_ON_I2C
+#define CONFIG_SYS_EEPROM_SIZE 256
+
+#ifndef CONFIG_SPL_BUILD
+/* SATA */
+#define CONFIG_CMD_SCSI
+#define CONFIG_LIBATA
+#define CONFIG_SCSI_AHCI
+#define CONFIG_SCSI_AHCI_PLAT
+#define CONFIG_SYS_SCSI_MAX_SCSI_ID 1
+#define CONFIG_SYS_SCSI_MAX_LUN 1
+#define CONFIG_SYS_SCSI_MAX_DEVICE (CONFIG_SYS_SCSI_MAX_SCSI_ID * \
+ CONFIG_SYS_SCSI_MAX_LUN)
+/* PCA9555 GPIO expander support */
+#define CONFIG_PCA953X
+#define CONFIG_CMD_PCA953X
+#define CONFIG_CMD_PCA953X_INFO
+#define CONFIG_SYS_I2C_PCA953X_ADDR 0x20
+#define CONFIG_SYS_I2C_PCA953X_WIDTH { {0x20, 16} }
+
+/* GPT */
+#define CONFIG_CMD_GPT
+#define CONFIG_EFI_PARTITION
+
+/* USB xHCI HOST */
+#define CONFIG_USB_XHCI_OMAP
+#define CONFIG_SYS_USB_XHCI_MAX_ROOT_PORTS 2
+
+#define CONFIG_OMAP_USB_PHY
+#define CONFIG_OMAP_USB3PHY1_HOST
+
+/* USB Networking options */
+#define CONFIG_USB_HOST_ETHER
+#define CONFIG_USB_ETHER_SMSC95XX
+#define CONFIG_USB_ETHER_RNDIS
+#define CONFIG_USB_ETHER_ASIX
+#define CONFIG_USB_ETHER_MCS7830
+
+/* CPSW Ethernet */
+#define CONFIG_DRIVER_TI_CPSW
+#define CONFIG_MII
+#define CONFIG_BOOTP_DEFAULT
+#define CONFIG_BOOTP_SEND_HOSTNAME
+#define CONFIG_BOOTP_GATEWAY
+#define CONFIG_PHY_GIGE
+#define CONFIG_PHY_ATHEROS
+#define CONFIG_PHYLIB
+#define CONFIG_SYS_RX_ETH_BUFFER 64
+#define PHY_ANEG_TIMEOUT 8000
+
+#define CONFIG_BOOTP_DNS
+#define CONFIG_BOOTP_DNS2
+#define CONFIG_BOOTP_SUBNETMASK
+#define CONFIG_NET_RETRY_COUNT 10
+
+#endif /* !CONFIG_SPL_BUILD */
+
+/* Default environment */
+#undef CONFIG_EXTRA_ENV_SETTINGS
+#define CONFIG_EXTRA_ENV_SETTINGS \
+ DEFAULT_LINUX_BOOT_ENV \
+ "autoload=no\0" \
+ "baudrate=115200\0" \
+ "console=ttyO2,115200n8\0" \
+ "bootdelay=3\0" \
+ "fdtfile=am57xx-sbc-am57x.dtb\0" \
+ "kernel=zImage-cl-som-am57x\0" \
+ "bootscr=bootscr.img\0" \
+ "displaytype=hdmi\0" \
+ "bootkernel=bootz ${loadaddr} - ${fdtaddr}\0" \
+ "mmcloadfdt=load mmc ${mmcdev} ${fdtaddr} ${fdtfile}\0" \
+ "mmcloadkernel=load mmc ${mmcdev} ${loadaddr} ${kernel}\0" \
+ "load_mmc=mmc dev ${mmcdev} && mmc rescan && " \
+ "run mmcloadkernel run mmcloadfdt\0" \
+ "mmcroot=/dev/mmcblk1p2\0" \
+ "mmcrootfstype=ext4 rw rootwait\0" \
+ "mmcargs=setenv bootargs console=${console} root=${mmcroot} " \
+ "rootfstype=${mmcrootfstype}\0" \
+ "mmcbootscript=setenv mmcdev 0; mmc dev ${mmcdev} && mmc rescan && " \
+ "load mmc ${mmcdev} ${loadaddr} ${bootscr} && " \
+ "echo Running bootscript from MMC/SD Card ... && " \
+ "source ${loadaddr}\0" \
+ "mmcboot=setenv mmcdev 0 && run load_mmc && " \
+ "run mmcargs && echo Booting from MMC/SD Card ... && " \
+ "run bootkernel\0" \
+ "emmcroot=/dev/mmcblk0p2\0" \
+ "emmcrootfstype=ext4 rw rootwait\0" \
+ "emmcargs=setenv bootargs console=${console} " \
+ "root=${emmcroot} " \
+ "rootfstype=${emmcrootfstype}\0" \
+ "emmcbootscript=setenv mmcdev 1; mmc dev ${mmcdev} && mmc rescan && " \
+ "load mmc ${mmcdev} ${loadaddr} ${bootscr} && " \
+ "echo Running bootscript from eMMC ... && " \
+ "source ${loadaddr}\0" \
+ "emmcboot=setenv mmcdev 1 && run load_mmc && " \
+ "run emmcargs && echo Booting from eMMC ... && " \
+ "run bootkernel\0" \
+ "sataroot=/dev/sda2\0" \
+ "satarootfstype=ext4 rw rootwait\0" \
+ "load_sata=load scsi 0 ${loadaddr} ${kernel} && " \
+ "load scsi 0 ${fdtaddr} ${fdtfile}\0" \
+ "sataargs=setenv bootargs console=${console} " \
+ "root=${sataroot} " \
+ "rootfstype=${satarootfstype}\0" \
+ "satabootscript=load scsi 0 ${loadaddr} ${bootscr} && " \
+ "echo Running bootscript from SATA ... && " \
+ "source ${loadaddr}\0" \
+ "sataboot=run load_sata && run sataargs && " \
+ "echo Booting from SATA ... && " \
+ "run bootkernel\0" \
+
+#undef CONFIG_BOOTCOMMAND
+#define CONFIG_BOOTCOMMAND \
+ "run mmcbootscript || run mmcboot || " \
+ "run satabootscript || run sataboot || " \
+ "run emmcbootscript || run emmcboot"
+
+
+#endif /* __CONFIG_CL_SOM_AM57X_H */
diff --git a/include/configs/omap3_logic.h b/include/configs/omap3_logic.h
index abce61ae36..b38811e98d 100644
--- a/include/configs/omap3_logic.h
+++ b/include/configs/omap3_logic.h
@@ -143,7 +143,6 @@
"else run defaultboot; fi\0" \
"defaultboot=run mmcramboot\0" \
"consoledevice=ttyO0\0" \
- "display=15\0" \
"setconsole=setenv console ${consoledevice},${baudrate}n8\0" \
"dump_bootargs=echo 'Bootargs: '; echo $bootargs\0" \
"rotation=0\0" \
@@ -153,7 +152,7 @@
"fi\0" \
"optargs=ignore_loglevel early_printk no_console_suspend\0" \
"addmtdparts=setenv bootargs ${bootargs} ${mtdparts}\0" \
- "common_bootargs=setenv bootargs ${bootargs} display=${display} " \
+ "common_bootargs=setenv bootargs ${bootargs} " \
"${optargs};" \
"run addmtdparts; " \
"run vrfb_arg\0" \
@@ -241,8 +240,6 @@
/* **** PISMO SUPPORT *** */
#if defined(CONFIG_CMD_NAND)
#define CONFIG_SYS_FLASH_BASE NAND_BASE
-#elif defined(CONFIG_CMD_ONENAND)
-#define CONFIG_SYS_FLASH_BASE ONENAND_MAP
#endif
/* Monitor at start of flash */
@@ -250,7 +247,6 @@
#define CONFIG_ENV_IS_IN_NAND 1
#define CONFIG_ENV_SIZE (128 << 10) /* 128 KiB */
-#define ONENAND_ENV_OFFSET 0x260000 /* environment starts here */
#define SMNAND_ENV_OFFSET 0x260000 /* environment starts here */
#define CONFIG_SYS_ENV_SECT_SIZE (128 << 10) /* 128 KiB */
diff --git a/tools/binman/binman.py b/tools/binman/binman.py
index 7fb67cb25f..4cc431fbbe 100755
--- a/tools/binman/binman.py
+++ b/tools/binman/binman.py
@@ -1,4 +1,4 @@
-#!/usr/bin/python
+#!/usr/bin/env python
# Copyright (c) 2016 Google, Inc
# Written by Simon Glass <sjg@chromium.org>