summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--Makefile.rules2
-rw-r--r--board/npcx_evb/gpio.inc3
-rw-r--r--board/npcx_evb_arm/gpio.inc3
-rw-r--r--chip/npcx/build.mk20
-rw-r--r--chip/npcx/clock.c10
-rw-r--r--chip/npcx/config_chip.h18
-rw-r--r--chip/npcx/gpio.c26
-rw-r--r--chip/npcx/hwtimer.c18
-rw-r--r--chip/npcx/i2c.c107
-rw-r--r--chip/npcx/keyboard_raw.c11
-rw-r--r--chip/npcx/lpc.c238
-rw-r--r--chip/npcx/peci.c2
-rw-r--r--chip/npcx/registers.h44
-rw-r--r--chip/npcx/spiflashfw/ec_npcxflash.c3
-rw-r--r--chip/npcx/uart.c3
-rw-r--r--core/cortex-m/task.c19
-rw-r--r--util/build.mk3
-rwxr-xr-xutil/ecst.c2335
-rwxr-xr-xutil/ecst.h258
-rw-r--r--util/openocd/npcx.cfg6
-rw-r--r--util/openocd/npcx_cmds.tcl18
21 files changed, 2948 insertions, 199 deletions
diff --git a/Makefile.rules b/Makefile.rules
index 4b3b64f12c..018bb993f2 100644
--- a/Makefile.rules
+++ b/Makefile.rules
@@ -44,7 +44,7 @@ cmd_flat_to_obj = $(CC) -T $(out)/firmware_image.lds -nostdlib $(CPPFLAGS) \
-Wl,--build-id=none -o $@ $<
cmd_elf_to_flat = $(OBJCOPY) -O binary $(patsubst %.flat,%.elf,$@) $@
# Allow the .roshared section to overlap other sections (itself)
-cmd_ec_elf_to_flat = $(OBJCOPY) --set-section-flags .roshared=share \
+cmd_ec_elf_to_flat ?= $(OBJCOPY) --set-section-flags .roshared=share \
-O binary $(patsubst %.flat,%.elf,$@) $@
cmd_elf_to_dis = $(OBJDUMP) -D $< > $@
cmd_elf_to_hex = $(OBJCOPY) -O ihex $< $@
diff --git a/board/npcx_evb/gpio.inc b/board/npcx_evb/gpio.inc
index c51ecc9c05..149b045a7a 100644
--- a/board/npcx_evb/gpio.inc
+++ b/board/npcx_evb/gpio.inc
@@ -8,7 +8,7 @@
/********************** Inputs with interrupt handlers are first for efficiency **********************/
/* TODO: Redefine debug 2 inputs */
GPIO_INT(RECOVERY_L, PIN(0, 0), GPIO_PULL_UP | GPIO_INT_BOTH, switch_interrupt) /* Recovery signal from servo */
-GPIO_INT(WP_L, PIN(9, 3), GPIO_PULL_DOWN | GPIO_INT_BOTH, switch_interrupt) /* Write protect input */
+GPIO_INT(WP_L, PIN(9, 3), GPIO_PULL_UP | GPIO_INT_BOTH, switch_interrupt) /* Write protect input */
/* For testing keyboard commands, we need the following 4 GPIOs */
/* TODO: Redefine 4 inputs */
@@ -52,6 +52,7 @@ ALTERNATE(PIN_MASK(B, 0x30), 1, MODULE_I2C, 0) /* I2C0SDA/I2C0SCL
#endif
ALTERNATE(PIN_MASK(8, 0x80), 1, MODULE_I2C, 0) /* I2C1SDA GPIO87 */
ALTERNATE(PIN_MASK(9, 0x07), 1, MODULE_I2C, 0) /* I2C1SCL/I2C2SDA/I2C2SCL GPIO90/91/92 */
+ALTERNATE(PIN_MASK(D, 0x03), 1, MODULE_I2C, 0) /* I2C3SDA/I2C3SCL GPIOD0/D1 */
ALTERNATE(PIN_MASK(4, 0x38), 1, MODULE_ADC, 0) /* ADC GPIO45/44/43 */
ALTERNATE(PIN_MASK(A, 0x0A), 1, MODULE_SPI, 0) /* SPIP_MOSI/SPIP_SCLK GPIOA3/A1 */
ALTERNATE(PIN_MASK(9, 0x20), 1, MODULE_SPI, 0) /* SPIP_MISO GPIO95 */
diff --git a/board/npcx_evb_arm/gpio.inc b/board/npcx_evb_arm/gpio.inc
index 410ac90894..30e19ef1a9 100644
--- a/board/npcx_evb_arm/gpio.inc
+++ b/board/npcx_evb_arm/gpio.inc
@@ -8,7 +8,7 @@
/********************** Inputs with interrupt handlers are first for efficiency **********************/
/* TODO: Redefine debug 2 inputs */
GPIO_INT(RECOVERY_L, PIN(0, 0), GPIO_PULL_UP | GPIO_INT_BOTH, switch_interrupt) /* Recovery signal from servo */
-GPIO_INT(WP_L, PIN(9, 3), GPIO_PULL_DOWN | GPIO_INT_BOTH, switch_interrupt) /* Write protect input */
+GPIO_INT(WP_L, PIN(9, 3), GPIO_PULL_UP | GPIO_INT_BOTH, switch_interrupt) /* Write protect input */
/* Used for ARM based platform */
GPIO_INT(SHI_CS_L, PIN(5, 3), GPIO_INT_FALLING,shi_cs_event) /* SHI CS Ready, Low Active. */
/* For testing keyboard commands, we need the following 4 GPIOs */
@@ -52,6 +52,7 @@ ALTERNATE(PIN_MASK(B, 0x30), 1, MODULE_I2C, 0) /* I2C0SDA/I2C0SCL
#endif
ALTERNATE(PIN_MASK(8, 0x80), 1, MODULE_I2C, 0) /* I2C1SDA GPIO87 */
ALTERNATE(PIN_MASK(9, 0x07), 1, MODULE_I2C, 0) /* I2C1SCL/I2C2SDA/I2C2SCL GPIO90/91/92 */
+ALTERNATE(PIN_MASK(D, 0x03), 1, MODULE_I2C, 0) /* I2C3SDA/I2C3SCL GPIOD0/D1 */
ALTERNATE(PIN_MASK(4, 0x38), 1, MODULE_ADC, 0) /* ADC GPIO45/44/43 */
ALTERNATE(PIN_MASK(A, 0x0A), 1, MODULE_SPI, 0) /* SPIP_MOSI/SPIP_SCLK GPIOA3/A1 */
ALTERNATE(PIN_MASK(9, 0x20), 1, MODULE_SPI, 0) /* SPIP_MISO GPIO95 */
diff --git a/chip/npcx/build.mk b/chip/npcx/build.mk
index 011396eccc..6a5cd5e213 100644
--- a/chip/npcx/build.mk
+++ b/chip/npcx/build.mk
@@ -32,3 +32,23 @@ chip-$(HAS_TASK_KEYSCAN)+=keyboard_raw.o
npcx-flash-fw=chip/npcx/spiflashfw/ec_npcxflash
npcx-flash-fw-bin=${out}/$(npcx-flash-fw).bin
PROJECT_EXTRA+=${npcx-flash-fw-bin}
+
+# ECST tool is for filling the header used by booter of npcx EC
+show_esct_cmd=$(if $(V),,echo ' ECST ' $(subst $(out)/,,$@) ; )
+
+# ECST options for header
+bld_ecst=${out}/util/ecst -usearmrst -mode bt -ph -i $(1) -o $(2) -nohcrc \
+-nofcrc -flashsize 8 -spimaxclk 50 -spireadmode dual 1> /dev/null
+
+# Replace original one with the flat file including header
+moveflat=mv -f $(1) $(2)
+
+# Commands for ECST
+cmd_ecst=$(show_esct_cmd)$(call moveflat,$@,$@.tmp);$(call bld_ecst,$@.tmp,$@)
+
+# Commands to append npcx header in ec.RO.flat
+cmd_org_ec_elf_to_flat = $(OBJCOPY) --set-section-flags .roshared=share \
+ -O binary $(patsubst %.flat,%.elf,$@) $@
+cmd_npcx_ro_elf_to_flat=$(cmd_org_ec_elf_to_flat);$(cmd_ecst)
+cmd_ec_elf_to_flat = $(if $(filter $(out)/RO/ec.RO.flat, $@), \
+ $(cmd_npcx_ro_elf_to_flat), $(cmd_org_ec_elf_to_flat) )
diff --git a/chip/npcx/clock.c b/chip/npcx/clock.c
index c59516043b..449e4dd8bd 100644
--- a/chip/npcx/clock.c
+++ b/chip/npcx/clock.c
@@ -196,22 +196,18 @@ void clock_uart2gpio(void)
/* Set to GPIO */
npcx_uart2gpio();
/* Enable MIWU for GPIO (UARTRX) */
- npcx_enable_wakeup(1);
- /* Clear Pending bit of GPIO (UARTRX) */
- npcx_clear_wakeup_event();
+ uart_enable_wakeup(1);
}
}
void clock_gpio2uart(void)
{
/* Is Pending bit of GPIO (UARTRX) */
- if (npcx_is_wakeup_from_gpio()) {
- /* Clear Pending bit of GPIO (UARTRX) */
- uart_clear_wakeup_event();
+ if (uart_is_wakeup_from_gpio()) {
/* Refresh console in-use timer */
clock_refresh_console_in_use();
/* Disable MIWU for GPIO (UARTRX) */
- uart_enable_miwu_wakeup(0);
+ uart_enable_wakeup(0);
/* Go back CR_SIN*/
npcx_gpio2uart();
/* Enable uart again */
diff --git a/chip/npcx/config_chip.h b/chip/npcx/config_chip.h
index f7e1541250..f8314f6282 100644
--- a/chip/npcx/config_chip.h
+++ b/chip/npcx/config_chip.h
@@ -19,8 +19,11 @@
#undef CONFIG_UART_TX_BUF_SIZE
#define CONFIG_UART_TX_BUF_SIZE 8192
-/* Interval between HOOK_TICK notifications */
-#define HOOK_TICK_INTERVAL_MS 250
+/*
+ * Interval between HOOK_TICK notifications
+ * Notice instant wake-up from deep-idle cannot exceed 200 ms
+ */
+#define HOOK_TICK_INTERVAL_MS 200
#define HOOK_TICK_INTERVAL (HOOK_TICK_INTERVAL_MS * MSEC)
/* Maximum number of deferrable functions */
@@ -46,12 +49,15 @@
#define CONFIG_STACK_SIZE 4096
/* non-standard task stack sizes */
-#define IDLE_TASK_STACK_SIZE 512
-#define LARGER_TASK_STACK_SIZE 768
-#define SMALLER_TASK_STACK_SIZE 384
+#define IDLE_TASK_STACK_SIZE 512
+#define LARGER_TASK_STACK_SIZE 640
+
+#define CHARGER_TASK_STACK_SIZE 640
+#define HOOKS_TASK_STACK_SIZE 640
+#define CONSOLE_TASK_STACK_SIZE 640
/* Default task stack size */
-#define TASK_STACK_SIZE 512
+#define TASK_STACK_SIZE 512
/* Address of RAM log used by Booter */
#define ADDR_BOOT_RAMLOG 0x100C7FC0
diff --git a/chip/npcx/gpio.c b/chip/npcx/gpio.c
index 34634943b3..51e3d844c8 100644
--- a/chip/npcx/gpio.c
+++ b/chip/npcx/gpio.c
@@ -551,20 +551,34 @@ void gpio_pre_init(void)
int flags;
int i, j;
- uint32_t ksi_mask = (~((1<<KEYBOARD_ROWS)-1)) & KB_ROW_MASK;
- uint32_t ks0_mask = (~((1<<KEYBOARD_COLS)-1)) & KB_COL_MASK;
+ uint32_t ksi_mask = (~((1<<KEYBOARD_ROWS)-1)) & KB_ROW_MASK;
+ uint32_t kso_mask = ((~((1<<KEYBOARD_COLS)-1))
+ << CONFIG_KEYBOARD_KSO_BASE) & KB_COL_MASK;
- /* Set necessary pin mux first */
+#ifdef CONFIG_KEYBOARD_COL2_INVERTED
+ kso_mask |= 1 << (CONFIG_KEYBOARD_KSO_BASE + 2);
+#endif
+
+ /* Set necessary pin mux to GPIO first */
/* Pin_Mux for KSO0-17 & KSI0-7 */
NPCX_DEVALT(ALT_GROUP_7) = (uint8_t)(ksi_mask);
- NPCX_DEVALT(ALT_GROUP_8) = (uint8_t)(ks0_mask);
- NPCX_DEVALT(ALT_GROUP_9) = (uint8_t)(ks0_mask >> 8);
- NPCX_DEVALT(ALT_GROUP_A) |= (uint8_t)(ks0_mask >> 16);
+ NPCX_DEVALT(ALT_GROUP_8) = (uint8_t)(kso_mask);
+ NPCX_DEVALT(ALT_GROUP_9) = (uint8_t)(kso_mask >> 8);
+ NPCX_DEVALT(ALT_GROUP_A) |= (uint8_t)(kso_mask >> 16);
/* Pin_Mux for FIU/SPI (set to GPIO) */
SET_BIT(NPCX_DEVALT(0), NPCX_DEVALT0_GPIO_NO_SPIP);
SET_BIT(NPCX_DEVALT(0), NPCX_DEVALT0_NO_F_SPI);
+ /* Pin_Mux for PWRGD */
+ SET_BIT(NPCX_DEVALT(1), NPCX_DEVALT1_NO_PWRGD);
+
+ /* Pin_Mux for PECI */
+#ifndef CONFIG_PECI
+ SET_BIT(NPCX_DEVALT(0xA), NPCX_DEVALTA_NO_PECI_EN);
+#endif
+
+ /* Pin_Mux for LPC & SHI */
#ifdef CONFIG_SHI
/* Switching to eSPI mode for SHI interface */
NPCX_DEVCNT |= 0x08;
diff --git a/chip/npcx/hwtimer.c b/chip/npcx/hwtimer.c
index 5607222b4d..2104ac942f 100644
--- a/chip/npcx/hwtimer.c
+++ b/chip/npcx/hwtimer.c
@@ -34,6 +34,14 @@ static volatile uint32_t evt_cnt_us_dbg;
static volatile uint32_t cur_cnt_us_dbg;
#endif
+#if !(DEBUG_TMR)
+#define CPUTS(...)
+#define CPRINTS(...)
+#else
+#define CPUTS(outstr) cputs(CC_CLOCK, outstr)
+#define CPRINTS(format, args...) cprints(CC_CLOCK, format, ## args)
+#endif
+
/*****************************************************************************/
/* Internal functions */
void init_hw_timer(int itim_no, enum ITIM_SOURCE_CLOCK_T source)
@@ -57,7 +65,7 @@ void init_hw_timer(int itim_no, enum ITIM_SOURCE_CLOCK_T source)
void __hw_clock_event_set(uint32_t deadline)
{
float inv_evt_tick = INT_32K_CLOCK/(float)SECOND;
- uint32_t evt_cnt_us;
+ int32_t evt_cnt_us;
/* Is deadline min value? */
if (evt_expired_us != 0 && evt_expired_us < deadline)
return;
@@ -68,6 +76,9 @@ void __hw_clock_event_set(uint32_t deadline)
#if DEBUG_TMR
evt_cnt_us_dbg = deadline - __hw_clock_source_read();
#endif
+ /* Deadline is behind current timer */
+ if (evt_cnt_us < 0)
+ evt_cnt_us = 1;
/* Event module disable */
CLEAR_BIT(NPCX_ITCTS(ITIM_EVENT_NO), NPCX_ITCTS_ITEN);
@@ -76,8 +87,11 @@ void __hw_clock_event_set(uint32_t deadline)
* It must exceed evt_expired_us for process_timers function
*/
evt_cnt = ((uint32_t)(evt_cnt_us*inv_evt_tick)+1)-1;
- if (evt_cnt > TICK_EVT_MAX_CNT)
+ if (evt_cnt > TICK_EVT_MAX_CNT) {
+ CPRINTS("Event overflow! 0x%08x, us is %d\r\n",
+ evt_cnt, evt_cnt_us);
evt_cnt = TICK_EVT_MAX_CNT;
+ }
NPCX_ITCNT16(ITIM_EVENT_NO) = evt_cnt;
/* Event module enable */
diff --git a/chip/npcx/i2c.c b/chip/npcx/i2c.c
index fd21aebbf9..d9940b688a 100644
--- a/chip/npcx/i2c.c
+++ b/chip/npcx/i2c.c
@@ -25,9 +25,13 @@
#define CPRINTS(format, args...) cprints(CC_I2C, format, ## args)
#endif
+/* Pull-up bit for I2C */
+#define NPCX_I2C_PUBIT(port, bus) \
+ ((port*2) + bus)
+
/* Data abort timeout unit:ms*/
-#define I2C_ABORT_TIMEOUT 10000
-/* Maximum time we allow for an I2C transfer */
+#define I2C_ABORT_TIMEOUT 35
+/* Maximum time we allow for an I2C transfer (SMB stardard is 25 ms) */
#define I2C_TIMEOUT_US (100*MSEC)
/* Marco functions of I2C */
#define I2C_START(port) SET_BIT(NPCX_SMBCTL1(port), NPCX_SMBCTL1_START)
@@ -94,31 +98,30 @@ int i2c_bus_busy(int port)
return IS_BIT_SET(NPCX_SMBCST(port), NPCX_SMBCST_BB) ? 1 : 0;
}
-void i2c_abort_data(int port)
+int i2c_abort_data(int port)
{
uint16_t timeout = I2C_ABORT_TIMEOUT;
- /* Generate a STOP condition */
- I2C_STOP(port);
-
/* Clear NEGACK, STASTR and BER bits */
SET_BIT(NPCX_SMBST(port), NPCX_SMBST_BER);
SET_BIT(NPCX_SMBST(port), NPCX_SMBST_STASTR);
- /*
- * In Master mode, NEGACK should be cleared only
- * after generating STOP
- */
SET_BIT(NPCX_SMBST(port), NPCX_SMBST_NEGACK);
/* Wait till STOP condition is generated */
while (--timeout) {
- msleep(1);
if (!IS_BIT_SET(NPCX_SMBCTL1(port), NPCX_SMBCTL1_STOP))
break;
+ msleep(1);
}
/* Clear BB (BUS BUSY) bit */
SET_BIT(NPCX_SMBCST(port), NPCX_SMBCST_BB);
+
+ if (timeout == 0) {
+ cprints(CC_I2C, "Abort i2c %02x fail!", port);
+ return 0;
+ } else
+ return 1;
}
void i2c_reset(int port)
@@ -128,21 +131,27 @@ void i2c_reset(int port)
CLEAR_BIT(NPCX_SMBCTL2(port), NPCX_SMBCTL2_ENABLE);
while (--timeout) {
- msleep(1);
/* WAIT FOR SCL & SDA IS HIGH */
if (IS_BIT_SET(NPCX_SMBCTL3(port), NPCX_SMBCTL3_SCL_LVL) &&
IS_BIT_SET(NPCX_SMBCTL3(port), NPCX_SMBCTL3_SDA_LVL))
break;
+ msleep(1);
}
+ if (timeout == 0)
+ cprints(CC_I2C, "Reset i2c %02x fail!", port);
+
/* Enable the SMB module */
SET_BIT(NPCX_SMBCTL2(port), NPCX_SMBCTL2_ENABLE);
}
void i2c_recovery(int port)
{
+ CPUTS("RECOVERY\r\n");
/* Abort data, generating STOP condition */
- i2c_abort_data(port);
+ if (i2c_abort_data(port) == 1 &&
+ i2c_stsobjs[port].err_code == SMB_MASTER_NO_ADDRESS_MATCH)
+ return;
/* Reset i2c port by re-enable i2c port*/
i2c_reset(port);
@@ -204,12 +213,12 @@ inline void i2c_handle_sda_irq(int port)
/* Write the address to the bus R bit*/
I2C_WRITE_BYTE(port, (addr | 0x1));
- CPUTS("-ARR");
+ CPRINTS("-ARR-0x%02x", addr);
} else {/* Transmit mode */
p_status->oper_state = SMB_WRITE_OPER;
/* Write the address to the bus W bit*/
I2C_WRITE_BYTE(port, addr);
- CPUTS("-ARW");
+ CPRINTS("-ARW-0x%02x", addr);
}
/* Completed handling START condition */
return;
@@ -324,6 +333,9 @@ void i2c_master_int_handler (int port)
volatile struct i2c_status *p_status = i2c_stsobjs + port;
/* Condition 1 : A Bus Error has been identified */
if (IS_BIT_SET(NPCX_SMBST(port), NPCX_SMBST_BER)) {
+ /* Generate a STOP condition */
+ I2C_STOP(port);
+ CPUTS("-SP");
/* Clear BER Bit */
SET_BIT(NPCX_SMBST(port), NPCX_SMBST_BER);
/* Set error code */
@@ -336,6 +348,9 @@ void i2c_master_int_handler (int port)
/* Condition 2: A negative acknowledge has occurred */
if (IS_BIT_SET(NPCX_SMBST(port), NPCX_SMBST_NEGACK)) {
+ /* Generate a STOP condition */
+ I2C_STOP(port);
+ CPUTS("-SP");
/* Clear NEGACK Bit */
SET_BIT(NPCX_SMBST(port), NPCX_SMBST_NEGACK);
/* Set error code */
@@ -379,12 +394,20 @@ int chip_i2c_xfer(int port, int slave_addr, const uint8_t *out, int out_size,
{
volatile struct i2c_status *p_status = i2c_stsobjs + port;
- if (port < 0 || port >= i2c_ports_used)
- return EC_ERROR_INVAL;
-
if (out_size == 0 && in_size == 0)
return EC_SUCCESS;
+ interrupt_disable();
+ /* make sure bus is not occupied by the other task */
+ if (p_status->task_waiting != TASK_ID_INVALID) {
+ interrupt_enable();
+ return EC_ERROR_BUSY;
+ }
+
+ /* Assign current task ID */
+ p_status->task_waiting = task_get_current();
+ interrupt_enable();
+
/* Copy data to port struct */
p_status->flags = flags;
p_status->tx_buf = out;
@@ -402,7 +425,6 @@ int chip_i2c_xfer(int port, int slave_addr, const uint8_t *out, int out_size,
p_status->idx_buf = 0;
p_status->err_code = SMB_OK;
-
/* Make sure we're in a good state to start */
if ((flags & I2C_XFER_START) && (i2c_bus_busy(port)
|| (i2c_get_line_levels(port) != I2C_LINE_IDLE))) {
@@ -419,9 +441,6 @@ int chip_i2c_xfer(int port, int slave_addr, const uint8_t *out, int out_size,
CPUTS("\n");
- /* Assign current task ID */
- p_status->task_waiting = task_get_current();
-
/* Start master transaction */
i2c_master_transaction(port);
@@ -485,12 +504,11 @@ int i2c_raw_get_sda(int port)
/* Hooks */
static void i2c_freq_changed(void)
{
- /* I2C is under APB2 */
- int freq;
- int port;
+ int freq, i;
- for (port = 0; port < i2c_ports_used; port++) {
- int bus_freq = i2c_ports[port].kbps;
+ for (i = 0; i < i2c_ports_used; i++) {
+ int bus_freq = i2c_ports[i].kbps;
+ int port = i2c_ports[i].port;
int scl_time;
/* SMB0/1 use core clock & SMB2/3 use apb2 clock */
@@ -520,7 +538,7 @@ DECLARE_HOOK(HOOK_FREQ_CHANGE, i2c_freq_changed, HOOK_PRIO_DEFAULT);
static void i2c_init(void)
{
- int port = 0;
+ int i;
/* Configure pins from GPIOs to I2Cs */
gpio_config_module(MODULE_I2C, 1);
@@ -533,16 +551,37 @@ static void i2c_init(void)
/*
* initialize smb status and register
*/
- for (port = 0; port < i2c_ports_used; port++) {
+ for (i = 0; i < i2c_ports_used; i++) {
+ int port = i2c_ports[i].port;
volatile struct i2c_status *p_status = i2c_stsobjs + port;
/* Configure pull-up for SMB interface pins */
-#ifndef SMB_SUPPORT18V
- /* Enable 3.3V pull-up */
- SET_BIT(NPCX_DEVPU0, port);
+
+ /* Enable 3.3V pull-up or turn to 1.8V support */
+ if (port == NPCX_I2C_PORT0) {
+#if NPCX_I2C0_BUS2
+ SET_BIT(NPCX_DEVPU0, NPCX_I2C_PUBIT(port, 1));
+#else
+ SET_BIT(NPCX_DEVPU0, NPCX_I2C_PUBIT(port, 0));
+#endif
+ } else if (port == NPCX_I2C_PORT2) {
+#ifdef NPCX_I2C2_1P8V
+ SET_BIT(NPCX_LV_GPIO_CTL1, NPCX_LV_GPIO_CTL1_SC2_0_LV);
+ SET_BIT(NPCX_LV_GPIO_CTL1, NPCX_LV_GPIO_CTL1_SD2_0_LV);
#else
- /* Set GPIO Pin voltage judgment to 1.8V */
- SET_BIT(NPCX_LV_GPIO_CTL1, port+1);
+ SET_BIT(NPCX_DEVPU0, NPCX_I2C_PUBIT(port, 0));
#endif
+ } else if (port == NPCX_I2C_PORT3) {
+#ifdef NPCX_I2C3_1P8V
+ SET_BIT(NPCX_LV_GPIO_CTL1, NPCX_LV_GPIO_CTL1_SC3_0_LV);
+ SET_BIT(NPCX_LV_GPIO_CTL1, NPCX_LV_GPIO_CTL1_SD3_0_LV);
+#else
+ SET_BIT(NPCX_DEVPU0, NPCX_I2C_PUBIT(port, 0));
+#endif
+
+ SET_BIT(NPCX_DEVPU0, NPCX_I2C_PUBIT(port, 0));
+ } else {
+ SET_BIT(NPCX_DEVPU0, NPCX_I2C_PUBIT(port, 0));
+ }
/* Enable module - before configuring CTL1 */
SET_BIT(NPCX_SMBCTL2(port), NPCX_SMBCTL2_ENABLE);
diff --git a/chip/npcx/keyboard_raw.c b/chip/npcx/keyboard_raw.c
index f43488a3fa..b52ab61b53 100644
--- a/chip/npcx/keyboard_raw.c
+++ b/chip/npcx/keyboard_raw.c
@@ -84,20 +84,23 @@ test_mockable void keyboard_raw_drive_column(int col)
* Nuvoton Keyboard Scan IP supports 18x8 Matrix
* It also support automatic scan functionality
*/
- uint32_t mask;
+ uint32_t mask, col_out;
+
+ /* Add support for CONFIG_KEYBOARD_KSO_BASE shifting */
+ col_out = col + CONFIG_KEYBOARD_KSO_BASE;
/* Drive all lines to high */
if (col == KEYBOARD_COLUMN_NONE) {
mask = KB_COL_MASK;
#ifdef CONFIG_KEYBOARD_COL2_INVERTED
- gpio_set_level(GPIO_KBD_KSO2, 1);
+ gpio_set_level(GPIO_KBD_KSO2, 0);
#endif
}
/* Set KBSOUT to zero to detect key-press */
else if (col == KEYBOARD_COLUMN_ALL) {
mask = 0;
#ifdef CONFIG_KEYBOARD_COL2_INVERTED
- gpio_set_level(GPIO_KBD_KSO2, 0);
+ gpio_set_level(GPIO_KBD_KSO2, 1);
#endif
}
/* Drive one line for detection */
@@ -108,7 +111,7 @@ test_mockable void keyboard_raw_drive_column(int col)
else
gpio_set_level(GPIO_KBD_KSO2, 0);
#endif
- mask = ((~(1 << col)) & KB_COL_MASK);
+ mask = ((~(1 << col_out)) & KB_COL_MASK);
}
/* Set KBSOUT */
diff --git a/chip/npcx/lpc.c b/chip/npcx/lpc.c
index 6a2a85742f..5f01627c68 100644
--- a/chip/npcx/lpc.c
+++ b/chip/npcx/lpc.c
@@ -25,13 +25,19 @@
#include "system_chip.h"
/* Console output macros */
+#if !(DEBUG_LPC)
+#define CPUTS(...)
+#define CPRINTS(...)
+#else
#define CPUTS(outstr) cputs(CC_LPC, outstr)
#define CPRINTS(format, args...) cprints(CC_LPC, format, ## args)
+#endif
#define LPC_SYSJUMP_TAG 0x4c50 /* "LP" */
-/* Timeout to wait PLTRST is deasserted */
-#define LPC_PLTRST_TIMEOUT_US 800000
+/* PM channel definitions */
+#define PMC_ACPI PM_CHAN_1
+#define PMC_HOST_CMD PM_CHAN_2
/* Super-IO index and register definitions */
#define SIO_OFFSET 0x4E
@@ -39,6 +45,7 @@
#define INDEX_CHPREV 0x24
#define INDEX_SRID 0x27
+static uint8_t plt_rst_l; /* Platform reset assert status */
static uint32_t host_events; /* Currently pending SCI/SMI events */
static uint32_t event_mask[3]; /* Event masks for each type */
static struct host_packet lpc_packet;
@@ -55,9 +62,11 @@ static uint8_t * const cmd_params = (uint8_t *)shm_mem_host_cmd +
static struct ec_lpc_host_args * const lpc_host_args =
(struct ec_lpc_host_args *)shm_mem_host_cmd;
-#ifdef CONFIG_KEYBOARD_IRQ_GPIO
+/*****************************************************************************/
+/* IC specific low-level driver */
static void keyboard_irq_assert(void)
{
+#ifdef CONFIG_KEYBOARD_IRQ_GPIO
/*
* Enforce signal-high for long enough for the signal to be pulled high
* by the external pullup resistor. This ensures the host will see the
@@ -71,27 +80,22 @@ static void keyboard_irq_assert(void)
udelay(4);
/* Set signal high, now that we've generated the edge */
gpio_set_level(CONFIG_KEYBOARD_IRQ_GPIO, 1);
-}
#else
-static inline void keyboard_irq_assert(void)
-{
- /* Use serirq method. */
- /* Using manual IRQ for KBC */
- SET_BIT(NPCX_HIIRQC, 0); /* set IRQ1B to high */
- CLEAR_BIT(NPCX_HICTRL, 0); /* set IRQ1 control by IRQB1 */
-}
+ /*
+ * SERIRQ is automatically sent by KBC
+ */
#endif
+}
-static void lpc_task_enable_irq(void){
-
- task_enable_irq(NPCX_IRQ_SHM);
+static void lpc_task_enable_irq(void)
+{
task_enable_irq(NPCX_IRQ_KBC_IBF);
task_enable_irq(NPCX_IRQ_PM_CHAN_IBF);
task_enable_irq(NPCX_IRQ_PORT80);
}
-static void lpc_task_disable_irq(void){
- task_disable_irq(NPCX_IRQ_SHM);
+static void lpc_task_disable_irq(void)
+{
task_disable_irq(NPCX_IRQ_KBC_IBF);
task_disable_irq(NPCX_IRQ_PM_CHAN_IBF);
task_disable_irq(NPCX_IRQ_PORT80);
@@ -116,7 +120,7 @@ static void lpc_generate_smi(void)
/* Set signal high, now that we've generated the edge */
gpio_set_level(GPIO_PCH_SMI_L, 1);
#else
- NPCX_HIPMIE(PM_CHAN_1) |= NPCX_HIPMIE_SMIE;
+ NPCX_HIPMIE(PMC_ACPI) |= NPCX_HIPMIE_SMIE;
#endif
if (host_events & event_mask[LPC_HOST_EVENT_SMI])
CPRINTS("smi 0x%08x",
@@ -138,7 +142,7 @@ static void lpc_generate_sci(void)
/* Set signal high, now that we've generated the edge */
gpio_set_level(CONFIG_SCI_GPIO, 1);
#else
- SET_BIT(NPCX_HIPMIE(PM_CHAN_1), NPCX_HIPMIE_SCIE);
+ SET_BIT(NPCX_HIPMIE(PMC_ACPI), NPCX_HIPMIE_SCIE);
#endif
if (host_events & event_mask[LPC_HOST_EVENT_SCI])
@@ -206,9 +210,9 @@ static void lpc_send_response(struct host_cmd_handler_args *args)
args->result = EC_RES_INVALID_RESPONSE;
/* Write result to the data byte. This sets the TOH status bit. */
- NPCX_HIPMDO(PM_CHAN_2) = args->result;
+ NPCX_HIPMDO(PMC_HOST_CMD) = args->result;
/* Clear processing flag */
- CLEAR_BIT(NPCX_HIPMST(PM_CHAN_2), 2);
+ CLEAR_BIT(NPCX_HIPMST(PMC_HOST_CMD), 2);
}
static void lpc_send_response_packet(struct host_packet *pkt)
@@ -218,37 +222,43 @@ static void lpc_send_response_packet(struct host_packet *pkt)
return;
/* Write result to the data byte. This sets the TOH status bit. */
- NPCX_HIPMDO(PM_CHAN_2) = pkt->driver_result;
+ NPCX_HIPMDO(PMC_HOST_CMD) = pkt->driver_result;
/* Clear processing flag */
- CLEAR_BIT(NPCX_HIPMST(PM_CHAN_2), 2);
+ CLEAR_BIT(NPCX_HIPMST(PMC_HOST_CMD), 2);
}
int lpc_keyboard_has_char(void)
{
- /* if OBF '1', that mean still have a data in the FIFO */
+ /* if OBF bit is '1', that mean still have a data in DBBOUT */
return (NPCX_HIKMST&0x01) ? 1 : 0;
}
-/* Return true if the FRMH is set */
int lpc_keyboard_input_pending(void)
{
+ /* if IBF bit is '1', that mean still have a data in DBBIN */
return (NPCX_HIKMST&0x02) ? 1 : 0;
}
/* Put a char to host buffer and send IRQ if specified. */
void lpc_keyboard_put_char(uint8_t chr, int send_irq)
{
- UPDATE_BIT(NPCX_HICTRL, NPCX_HICTRL_OBFKIE, send_irq);
NPCX_HIKDO = chr;
- task_enable_irq(NPCX_IRQ_KBC_OBF);
+ CPRINTS("KB put %02x", chr);
+
+ /* Enable OBE interrupt to detect host read data out */
+ SET_BIT(NPCX_HICTRL, NPCX_HICTRL_OBFCIE);
+ task_enable_irq(NPCX_IRQ_KBC_OBE);
+ if (send_irq) {
+ keyboard_irq_assert();
+ }
}
void lpc_keyboard_clear_buffer(void)
{
/* Make sure the previous TOH and IRQ has been sent out. */
udelay(4);
- /*FW_OBF write 1*/
- NPCX_HICTRL |= 0x80;
+ /* Clear OBE flag in host STATUS and HIKMST regs*/
+ SET_BIT(NPCX_HICTRL, NPCX_HICTRL_FW_OBF);
/* Ensure there is no TOH set in this period. */
udelay(4);
}
@@ -278,18 +288,18 @@ static void update_host_event_status(void)
lpc_task_disable_irq();
if (host_events & event_mask[LPC_HOST_EVENT_SMI]) {
/* Only generate SMI for first event */
- if (!(NPCX_HIPMIE(PM_CHAN_1) & NPCX_HIPMIE_SMIE))
+ if (!(NPCX_HIPMIE(PMC_ACPI) & NPCX_HIPMIE_SMIE))
need_smi = 1;
- SET_BIT(NPCX_HIPMIE(PM_CHAN_1), NPCX_HIPMIE_SMIE);
+ SET_BIT(NPCX_HIPMIE(PMC_ACPI), NPCX_HIPMIE_SMIE);
} else
- CLEAR_BIT(NPCX_HIPMIE(PM_CHAN_1), NPCX_HIPMIE_SMIE);
+ CLEAR_BIT(NPCX_HIPMIE(PMC_ACPI), NPCX_HIPMIE_SMIE);
if (host_events & event_mask[LPC_HOST_EVENT_SCI]) {
/* Generate SCI for every event */
need_sci = 1;
- SET_BIT(NPCX_HIPMIE(PM_CHAN_1), NPCX_HIPMIE_SCIE);
+ SET_BIT(NPCX_HIPMIE(PMC_ACPI), NPCX_HIPMIE_SCIE);
} else
- CLEAR_BIT(NPCX_HIPMIE(PM_CHAN_1), NPCX_HIPMIE_SCIE);
+ CLEAR_BIT(NPCX_HIPMIE(PMC_ACPI), NPCX_HIPMIE_SCIE);
/* Copy host events to mapped memory */
*(uint32_t *)host_get_memmap(EC_MEMMAP_HOST_EVENTS) = host_events;
@@ -358,12 +368,24 @@ uint32_t lpc_get_host_event_mask(enum lpc_host_event_type type)
void lpc_set_acpi_status_mask(uint8_t mask)
{
- /* TODO (crbug.com/p/38224): Implement */
+ NPCX_HIPMST(PMC_ACPI) |= mask;
}
void lpc_clear_acpi_status_mask(uint8_t mask)
{
- /* TODO (crbug.com/p/38224): Implement */
+ NPCX_HIPMST(PMC_ACPI) &= ~mask;
+}
+
+/* Enable LPC ACPI-EC interrupts */
+void lpc_enable_acpi_interrupts(void)
+{
+ SET_BIT(NPCX_HIPMCTL(PMC_ACPI), NPCX_HIPMCTL_IBFIE);
+}
+
+/* Disable LPC ACPI-EC interrupts */
+void lpc_disable_acpi_interrupts(void)
+{
+ CLEAR_BIT(NPCX_HIPMCTL(PMC_ACPI), NPCX_HIPMCTL_IBFIE);
}
/**
@@ -376,11 +398,11 @@ static void handle_acpi_write(int is_cmd)
uint8_t value, result;
/* Read command/data; this clears the FRMH status bit. */
- value = NPCX_HIPMDI(PM_CHAN_1);
+ value = NPCX_HIPMDI(PMC_ACPI);
/* Handle whatever this was. */
if (acpi_ap_to_ec(is_cmd, value, &result))
- NPCX_HIPMDO(PM_CHAN_1) = result;
+ NPCX_HIPMDO(PMC_ACPI) = result;
/*
* ACPI 5.0-12.6.1: Generate SCI for Input Buffer Empty / Output Buffer
@@ -400,7 +422,7 @@ static void handle_host_write(int is_cmd)
* Read the command byte. This clears the FRMH bit in
* the status byte.
*/
- host_cmd_args.command = NPCX_HIPMDI(PM_CHAN_2);
+ host_cmd_args.command = NPCX_HIPMDI(PMC_HOST_CMD);
host_cmd_args.result = EC_RES_SUCCESS;
host_cmd_args.send_response = lpc_send_response;
@@ -422,7 +444,7 @@ static void handle_host_write(int is_cmd)
lpc_packet.driver_result = EC_RES_SUCCESS;
/* Set processing flag */
- SET_BIT(NPCX_HIPMST(PM_CHAN_2), 2);
+ SET_BIT(NPCX_HIPMST(PMC_HOST_CMD), 2);
host_packet_receive(&lpc_packet);
return;
@@ -473,46 +495,55 @@ static void handle_host_write(int is_cmd)
host_command_received(&host_cmd_args);
}
-
-void lpc_shm_interrupt(void){
-}
-DECLARE_IRQ(NPCX_IRQ_SHM, lpc_shm_interrupt, 2);
-
+/*****************************************************************************/
+/* Interrupt handlers */
+#ifdef HAS_TASK_KEYPROTO
+/* KB controller input buffer full ISR */
void lpc_kbc_ibf_interrupt(void)
{
-#ifdef CONFIG_KEYBOARD_PROTOCOL_8042
/* If "command" input 0, else 1*/
- keyboard_host_write(NPCX_HIKMDI, (NPCX_HIKMST & 0x08) ? 1 : 0);
-#endif
+ if (lpc_keyboard_input_pending())
+ keyboard_host_write(NPCX_HIKMDI, (NPCX_HIKMST & 0x08) ? 1 : 0);
+ CPRINTS("ibf isr %02x", NPCX_HIKMDI);
+ task_wake(TASK_ID_KEYPROTO);
}
DECLARE_IRQ(NPCX_IRQ_KBC_IBF, lpc_kbc_ibf_interrupt, 2);
-void lpc_kbc_obf_interrupt(void){
- /* reserve for future handle */
- if (!IS_BIT_SET(NPCX_HICTRL, 0)) {
- SET_BIT(NPCX_HICTRL, 0); /* back to H/W control of IRQ1 */
- CLEAR_BIT(NPCX_HIIRQC, 0); /* back to default of IRQB1 */
- }
- task_disable_irq(NPCX_IRQ_KBC_OBF);
+/* KB controller output buffer empty ISR */
+void lpc_kbc_obe_interrupt(void)
+{
+ /* Disable KBC OBE interrupt */
+ CLEAR_BIT(NPCX_HICTRL, NPCX_HICTRL_OBFCIE);
+ task_disable_irq(NPCX_IRQ_KBC_OBE);
+
+ CPRINTS("obe isr %02x", NPCX_HIKMST);
+ task_wake(TASK_ID_KEYPROTO);
}
-DECLARE_IRQ(NPCX_IRQ_KBC_OBF, lpc_kbc_obf_interrupt, 2);
+DECLARE_IRQ(NPCX_IRQ_KBC_OBE, lpc_kbc_obe_interrupt, 2);
+#endif
-void lpc_pmc_ibf_interrupt(void){
+/* PM channel input buffer full ISR */
+void lpc_pmc_ibf_interrupt(void)
+{
/* Channel-1 for ACPI usage*/
/* Channel-2 for Host Command usage , so the argument data had been
* put on the share memory firstly*/
- if (NPCX_HIPMST(PM_CHAN_1) & 0x02)
- handle_acpi_write((NPCX_HIPMST(PM_CHAN_1)&0x08) ? 1 : 0);
- else if (NPCX_HIPMST(PM_CHAN_2)&0x02)
- handle_host_write((NPCX_HIPMST(PM_CHAN_2)&0x08) ? 1 : 0);
+ if (NPCX_HIPMST(PMC_ACPI) & 0x02)
+ handle_acpi_write((NPCX_HIPMST(PMC_ACPI)&0x08) ? 1 : 0);
+ else if (NPCX_HIPMST(PMC_HOST_CMD) & 0x02)
+ handle_host_write((NPCX_HIPMST(PMC_HOST_CMD)&0x08) ? 1 : 0);
}
DECLARE_IRQ(NPCX_IRQ_PM_CHAN_IBF, lpc_pmc_ibf_interrupt, 2);
-void lpc_pmc_obf_interrupt(void){
+/* PM channel output buffer empty ISR */
+void lpc_pmc_obe_interrupt(void)
+{
}
-DECLARE_IRQ(NPCX_IRQ_PM_CHAN_OBF, lpc_pmc_obf_interrupt, 2);
+DECLARE_IRQ(NPCX_IRQ_PM_CHAN_OBE, lpc_pmc_obe_interrupt, 2);
+
-void lpc_port80_interrupt(void){
+void lpc_port80_interrupt(void)
+{
port_80_write((NPCX_GLUE_SDPD0<<0) | (NPCX_GLUE_SDPD1<<8));
/* No matter what , just clear error status bit */
SET_BIT(NPCX_DP80STS, 7);
@@ -546,12 +577,6 @@ static void lpc_post_sysjump(void)
memcpy(event_mask, prev_mask, sizeof(event_mask));
}
-int lpc_get_pltrst_asserted(void)
-{
- /* Read PLTRST status */
- return (NPCX_MSWCTL1 & 0x04) ? 1 : 0;
-}
-
/* Super-IO read/write function */
void lpc_sib_write_reg(uint8_t io_offset, uint8_t index_value,
uint8_t io_data)
@@ -650,20 +675,17 @@ uint8_t lpc_sib_read_reg(uint8_t io_offset, uint8_t index_value)
}
/* For LPC host register initial via SIB module */
-void lpc_host_register_init(void){
-
- timestamp_t deadline;
-
- deadline.val = 0;
- deadline = get_time();
- deadline.val += LPC_PLTRST_TIMEOUT_US;
+void lpc_host_register_init(void)
+{
+ /* enable ACPI*/
+ lpc_sib_write_reg(SIO_OFFSET, 0x07, 0x11);
+ lpc_sib_write_reg(SIO_OFFSET, 0x30, 0x01);
- /* Make sure PLTRST is de-asserted. Or any setting for LPC is useless */
- while (lpc_get_pltrst_asserted())
- if (timestamp_expired(deadline, NULL)) {
- CPRINTS("PLTRST is asserted. LPC settings are ignored");
- return;
- }
+ /* enable KBC*/
+ lpc_sib_write_reg(SIO_OFFSET, 0x07, 0x05);
+ lpc_sib_write_reg(SIO_OFFSET, 0x30, 0x01);
+ lpc_sib_write_reg(SIO_OFFSET, 0x07, 0x06);
+ lpc_sib_write_reg(SIO_OFFSET, 0x30, 0x01);
/* Setting PMC2 */
/* LDN register = 0x12(PMC2) */
@@ -696,6 +718,25 @@ void lpc_host_register_init(void){
lpc_sib_write_reg(SIO_OFFSET, 0xF8, 0x00);
/* enable SHM */
lpc_sib_write_reg(SIO_OFFSET, 0x30, 0x01);
+ CPRINTS("Host settings are done!");
+
+}
+
+int lpc_get_pltrst_asserted(void)
+{
+ uint8_t cur_plt_rst_l;
+ /* Read current PLTRST status */
+ cur_plt_rst_l = (NPCX_MSWCTL1 & 0x04) ? 1 : 0;
+
+ /*
+ * If plt_rst is deasserted for the first time
+ * Initialize all lpc settings
+ */
+ if (cur_plt_rst_l == 0 && plt_rst_l == 1)
+ lpc_host_register_init();
+
+ plt_rst_l = cur_plt_rst_l;
+ return plt_rst_l;
}
static void lpc_init(void)
@@ -741,12 +782,12 @@ static void lpc_init(void)
NPCX_WIN_WR_PROT(1) = 0xFF;
/* Turn on PMC2 for Host Command usage */
- SET_BIT(NPCX_HIPMCTL(PM_CHAN_2), 0);
- SET_BIT(NPCX_HIPMCTL(PM_CHAN_2), 1);
+ SET_BIT(NPCX_HIPMCTL(PMC_HOST_CMD), 0);
+ SET_BIT(NPCX_HIPMCTL(PMC_HOST_CMD), 1);
/* enable PMC2 IRQ */
- SET_BIT(NPCX_HIPMIE(PM_CHAN_2), 0);
+ SET_BIT(NPCX_HIPMIE(PMC_HOST_CMD), 0);
/* IRQ control from HW */
- SET_BIT(NPCX_HIPMIE(PM_CHAN_2), 3);
+ SET_BIT(NPCX_HIPMIE(PMC_HOST_CMD), 3);
/*
* Set required control value (avoid setting HOSTWAIT bit at this stage)
*/
@@ -757,11 +798,12 @@ static void lpc_init(void)
/*
* Init KBC
- * Clear OBF status, PM1 IBF/OBF INT enable, IRQ11 enable,
- * IBF(K&M) INT enable, OBF(K&M) empty INT enable ,
+ * Clear OBF status flag, PM1 IBF/OBE INT enable, IRQ11 enable,
+ * IBF(K&M) INT enable, OBE(K&M) empty INT enable ,
* OBF Mouse Full INT enable and OBF KB Full INT enable
*/
NPCX_HICTRL = 0xFF;
+
/* Normally Polarity IRQ1,12,11 type (level + high) setting */
NPCX_HIIRQC = 0x00; /* Make sure to default */
@@ -771,9 +813,11 @@ static void lpc_init(void)
*/
NPCX_DP80CTL = 0x29;
SET_BIT(NPCX_GLUE_SDP_CTS, 3);
+#if SUPPORT_P80_SEG
SET_BIT(NPCX_GLUE_SDP_CTS, 0);
+#endif
/* Just turn on IRQE */
- NPCX_HIPMIE(PM_CHAN_1) = 0x01;
+ NPCX_HIPMIE(PMC_ACPI) = 0x01;
lpc_task_enable_irq();
/* Initialize host args and memory map to all zero */
@@ -785,8 +829,6 @@ static void lpc_init(void)
EC_HOST_CMD_FLAG_LPC_ARGS_SUPPORTED |
EC_HOST_CMD_FLAG_VERSION_3;
-
-
/* Restore event masks if needed */
lpc_post_sysjump();
@@ -794,7 +836,6 @@ static void lpc_init(void)
init_done = 1;
/* Update host events now that we can copy them to memmap */
-
update_host_event_status();
/*
@@ -809,19 +850,6 @@ static void lpc_init(void)
lpc_host_register_init();
#endif
}
-
-/* Enable LPC ACPI-EC interrupts */
-void lpc_enable_acpi_interrupts(void)
-{
- SET_BIT(NPCX_HIPMCTL(PM_CHAN_1), 0);
-}
-
-/* Disable LPC ACPI-EC interrupts */
-void lpc_disable_acpi_interrupts(void)
-{
- CLEAR_BIT(NPCX_HIPMCTL(PM_CHAN_1), 0);
-}
-
/*
* Set prio to higher than default; this way LPC memory mapped data is ready
* before other inits try to initialize their memmap data.
diff --git a/chip/npcx/peci.c b/chip/npcx/peci.c
index 2850ce793c..64fcf62a0f 100644
--- a/chip/npcx/peci.c
+++ b/chip/npcx/peci.c
@@ -27,7 +27,7 @@
/* PECI Time-out */
-#define PECI_DONE_TIMEOUT_US (100*MSEC)
+#define PECI_DONE_TIMEOUT_US (10*MSEC)
/* Task Event for PECI */
#define TASK_EVENT_PECI_DONE TASK_EVENT_CUSTOM(1<<26)
diff --git a/chip/npcx/registers.h b/chip/npcx/registers.h
index aa741ba805..d981540bb6 100644
--- a/chip/npcx/registers.h
+++ b/chip/npcx/registers.h
@@ -34,9 +34,10 @@
#define SUPPORT_LCT 1
#define SUPPORT_WDG 1
#define SUPPORT_HIB 1
+#define SUPPORT_P80_SEG 0 /* Note: it uses KSO10 & KSO11 */
/* Switcher of debugging */
#define DEBUG_I2C 0
-#define DEBUG_TMR 1
+#define DEBUG_TMR 0
#define DEBUG_WDG 0
#define DEBUG_GPIO 1
#define DEBUG_FAN 0
@@ -45,7 +46,8 @@
#define DEBUG_FLH 0
#define DEBUG_PECI 0
#define DEBUG_SHI 1
-#define DEBUG_CLK 1
+#define DEBUG_CLK 0
+#define DEBUG_LPC 0
/* Modules Map */
#define NPCX_MDC_BASE_ADDR 0x4000C000
@@ -78,7 +80,7 @@
#define NPCX_PM_CH_BASE_ADDR(mdl) (0x400C9000 + ((mdl) * 0x2000L))
#define NPCX_SMB_BASE_ADDR(mdl) ((mdl < 2) ? (0x40009000 + \
((mdl) * 0x2000L)) : \
- (0x400C0000 + ((mdl) * 0x2000L)))
+ (0x400C0000 + ((mdl - 2) * 0x2000L)))
/*
* NPCX-IRQ numbers
@@ -151,7 +153,7 @@
#define NPCX_IRQ0_NOUSED NPCX_IRQ_0
#define NPCX_IRQ1_NOUSED NPCX_IRQ_1
#define NPCX_IRQ_KBSCAN NPCX_IRQ_2
-#define NPCX_IRQ_PM_CHAN_OBF NPCX_IRQ_3
+#define NPCX_IRQ_PM_CHAN_OBE NPCX_IRQ_3
#define NPCX_IRQ_PECI NPCX_IRQ_4
#define NPCX_IRQ5_NOUSED NPCX_IRQ_5
#define NPCX_IRQ_PORT80 NPCX_IRQ_6
@@ -204,7 +206,7 @@
#define NPCX_IRQ_WKINTG_1 NPCX_IRQ_53
#define NPCX_IRQ_WKINTH_1 NPCX_IRQ_54
#define NPCX_IRQ55_NOUSED NPCX_IRQ_55
-#define NPCX_IRQ_KBC_OBF NPCX_IRQ_56
+#define NPCX_IRQ_KBC_OBE NPCX_IRQ_56
#define NPCX_IRQ_SPI NPCX_IRQ_57
#define NPCX_IRQ58_NOUSED NPCX_IRQ_58
#define NPCX_IRQ59_NOUSED NPCX_IRQ_59
@@ -564,8 +566,14 @@ enum {
#define NPCX_DEVALTC_TA2_SL2 6
#define NPCX_DEVALTC_TB2_SL2 7
+/* Others bit definitions */
#define NPCX_LFCGCALCNT_LPREG_CTL_EN 1
+#define NPCX_LV_GPIO_CTL1_SC2_0_LV 0
+#define NPCX_LV_GPIO_CTL1_SD2_0_LV 1
+#define NPCX_LV_GPIO_CTL1_SC3_0_LV 2
+#define NPCX_LV_GPIO_CTL1_SD3_0_LV 3
+
/******************************************************************************/
/* Development and Debug Support (DBG) Registers */
#define NPCX_DBGCTRL REG8(NPCX_SCFG_BASE_ADDR + 0x074)
@@ -758,7 +766,8 @@ enum NPCX_PMC_PWDWN_CTL_T {
(1 << NPCX_PWDWN_CTL2_PWM1_PD))
#define CGC_I2C_MASK ((1 << NPCX_PWDWN_CTL3_SMB0_PD) | \
(1 << NPCX_PWDWN_CTL3_SMB1_PD) | \
- (1 << NPCX_PWDWN_CTL3_SMB2_PD))
+ (1 << NPCX_PWDWN_CTL3_SMB2_PD) | \
+ (1 << NPCX_PWDWN_CTL3_SMB3_PD))
#define CGC_ADC_MASK (1 << NPCX_PWDWN_CTL4_ADC_PD)
#define CGC_PECI_MASK (1 << NPCX_PWDWN_CTL4_PECI_PD)
#define CGC_SPI_MASK (1 << NPCX_PWDWN_CTL4_SPIP_PD)
@@ -886,8 +895,14 @@ enum NPCX_PMC_PWDWN_CTL_T {
#define NPCX_SHIKMDI REG8(NPCX_KBC_BASE_ADDR + 0x00B)
/* KBC register field */
-#define NPCX_HICTRL_OBFKIE 0
-#define NPCX_HICTRL_OBFMIE 1
+#define NPCX_HICTRL_OBFKIE 0 /* Automatic Serial IRQ1 for KBC */
+#define NPCX_HICTRL_OBFMIE 1 /* Automatic Serial IRQ12 for Mouse*/
+#define NPCX_HICTRL_OBFCIE 2 /* KBC OBE interrupt enable */
+#define NPCX_HICTRL_IBFCIE 3 /* KBC IBF interrupt enable */
+#define NPCX_HICTRL_PMIHIE 4 /* Automatic Serial IRQ11 for PMC1 */
+#define NPCX_HICTRL_PMIOCIE 5 /* PMC1 OBE interrupt enable */
+#define NPCX_HICTRL_PMICIE 6 /* PMC1 IBF interrupt enable */
+#define NPCX_HICTRL_FW_OBF 7 /* Firmware control over OBF */
/******************************************************************************/
/* PM Channel Registers */
@@ -906,6 +921,7 @@ enum NPCX_PMC_PWDWN_CTL_T {
/* PM Channel register field */
#define NPCX_HIPMIE_SCIE 1
#define NPCX_HIPMIE_SMIE 2
+#define NPCX_HIPMCTL_IBFIE 0
/*
* PM Channel enumeration
@@ -1296,16 +1312,6 @@ static inline int uart_is_wakeup_from_gpio(void)
#endif
}
-/* This routine clear pending bit of GPIO wake-up functionality */
-static inline void uart_clear_wakeup_event(void)
-{
-#if NPCX_UART_MODULE2
- SET_BIT(NPCX_WKPND(1, 6), 4);
-#else
- SET_BIT(NPCX_WKPND(1, 1), 0);
-#endif
-}
-
/* This routine checks wake-up functionality from GPIO is enabled or not */
static inline int uart_is_enable_wakeup(void)
{
@@ -1340,8 +1346,10 @@ static inline int npcx_is_uart(void)
static inline void npcx_uart2gpio(void)
{
#if NPCX_UART_MODULE2
+ UPDATE_BIT(NPCX_WKEDG(1, 6), 4, 1);
CLEAR_BIT(NPCX_DEVALT(0x0C), NPCX_DEVALTC_UART_SL2);
#else
+ UPDATE_BIT(NPCX_WKEDG(1, 1), 0, 1);
CLEAR_BIT(NPCX_DEVALT(0x0A), NPCX_DEVALTA_UART_SL1);
#endif
}
diff --git a/chip/npcx/spiflashfw/ec_npcxflash.c b/chip/npcx/spiflashfw/ec_npcxflash.c
index 41e833b273..ccaff16872 100644
--- a/chip/npcx/spiflashfw/ec_npcxflash.c
+++ b/chip/npcx/spiflashfw/ec_npcxflash.c
@@ -273,6 +273,9 @@ sspi_flash_upload(int spi_offset, int spi_size)
NPCX_WDSDM = 0x61;
NPCX_WDSDM = 0x63;
+ /* UMA Unlock */
+ CLEAR_BIT(NPCX_UMA_ECTS, NPCX_UMA_ECTS_UMA_LOCK);
+
/* Set pinmux first */
sspi_flash_pinmux(1);
diff --git a/chip/npcx/uart.c b/chip/npcx/uart.c
index 570ded4285..51ef975bc3 100644
--- a/chip/npcx/uart.c
+++ b/chip/npcx/uart.c
@@ -101,6 +101,9 @@ void uart_write_char(char c)
;
NPCX_UTBUF = c;
+#ifdef CONFIG_LOW_POWER_IDLE
+ clock_refresh_console_in_use();
+#endif
}
int uart_read_char(void)
diff --git a/core/cortex-m/task.c b/core/cortex-m/task.c
index 09d7108e7b..9f275391d3 100644
--- a/core/cortex-m/task.c
+++ b/core/cortex-m/task.c
@@ -66,11 +66,30 @@ extern int __task_start(int *task_stack_ready);
void __idle(void)
{
while (1) {
+#ifdef CHIP_NPCX
+ /*
+ * TODO (ML): A interrupt that occurs shortly before entering
+ * idle mode starts getting services while the Core transitions
+ * into idle mode. The results in a hard fault when the Core,
+ * shortly therefore, resumes execution on exiting idle mode.
+ * Workaround: Replace the idle function with the followings
+ */
+ asm (
+ "cpsid i\n" /* Disable interrupt */
+ "push {r0-r5}\n" /* Save needed registers */
+ "ldr r0, =0x100A8000\n" /* Set r0 to a valid RAM addr */
+ "wfi\n" /* Wait for int to enter idle */
+ "ldm r0, {r0-r5}\n" /* Add a delay after WFI */
+ "pop {r0-r5}\n" /* Restore regs before enabling ints */
+ "cpsie i\n" /* Enable interrupts */
+ );
+#else
/*
* Wait for the next irq event. This stops the CPU clock
* (sleep / deep sleep, depending on chip config).
*/
asm("wfi");
+#endif
}
}
#endif /* !CONFIG_LOW_POWER_IDLE */
diff --git a/util/build.mk b/util/build.mk
index 74466ba1f0..3c8480da80 100644
--- a/util/build.mk
+++ b/util/build.mk
@@ -7,6 +7,9 @@
#
host-util-bin=ectool lbplay stm32mon ec_sb_firmware_update lbcc
+ifeq ($(CHIP),npcx)
+host-util-bin+=ecst
+endif
build-util-bin=ec_uartd iteflash
comm-objs=$(util-lock-objs:%=lock/%) comm-host.o comm-dev.o
diff --git a/util/ecst.c b/util/ecst.c
new file mode 100755
index 0000000000..b356e3469f
--- /dev/null
+++ b/util/ecst.c
@@ -0,0 +1,2335 @@
+/*
+ * Copyright (c) 2015 The Chromium OS Authors. All rights reserved.
+ * Use of this source code is governed by a BSD-style license that can be
+ * found in the LICENSE file.
+ */
+
+/* Include */
+#include "ecst.h"
+
+/* Global Variables */
+enum verbose_level g_verbose;
+char input_file_name[NAME_SIZE];
+char output_file_name[NAME_SIZE];
+char arg_file_name[NAME_SIZE];
+char g_hdr_input_name[NAME_SIZE];
+char hdr_args[MAX_ARGS][ARG_SIZE];
+char tmp_hdr_args[MAX_ARGS][ARG_SIZE];
+FILE *input_file_pointer;
+FILE *g_hfd_pointer;
+FILE *arg_file_pointer;
+FILE *api_file_pointer;
+FILE *g_hdr_pointer;
+void *gh_console;
+unsigned short g_text_atrib;
+unsigned short g_bg_atrib;
+enum calc_type g_calc_type;
+unsigned int ptr_fw_addr;
+unsigned int fw_offset;
+int is_ptr_merge;
+unsigned int g_ram_start_address;
+unsigned int g_ram_size;
+unsigned int api_file_size_bytes;
+
+/* Chips information, RAM start address and RAM size. */
+struct chip_info chip_info[] = {{NPCX5M5G_RAM_ADDR, NPCX5M5G_RAM_SIZE},
+ {NPCX5M6G_RAM_ADDR, NPCX5M6G_RAM_SIZE} };
+
+static unsigned int calc_api_csum_bin(void);
+static unsigned int initialize_crc_32(void);
+static unsigned int update_crc_32(unsigned int crc, char c);
+static unsigned int finalize_crc_32(unsigned int crc);
+
+/*
+ *----------------------------------------------------------------------
+ * Function: main()
+ * Parameters: argc, argv
+ * Return: 0
+ * Description: Parse the arguments
+ * Chose manipulation routine according to arguments
+ *
+ * In case of bin, save optional parameters given by user
+ *----------------------------------------------------------------------
+ */
+int main(int argc, char *argv[])
+
+{
+
+ int mode_choose = FALSE;
+ /* Do we get a bin File? */
+ int main_fw_hdr_flag = FALSE;
+ /* Do we get a API bin File? */
+ int main_api_flag = FALSE;
+ /* Do we need to create a BootLoader Header file? */
+ int main_hdr_flag = FALSE;
+
+ /* Following variables: common to all modes */
+ int main_status = TRUE;
+ unsigned int main_temp = 0L;
+ char main_str_temp[TMP_STR_SIZE];
+
+ int arg_num;
+ int arg_ind;
+ int tmp_ind;
+ int tmp_arg_num;
+ int cur_arg_index;
+ FILE *tmp_file;
+
+ /* Following variables are used when bin file is provided */
+ struct tbinparams bin_params;
+ bin_params.bin_params = 0;
+
+ input_file_name[0] = '\0';
+ memset(input_file_name, 0, NAME_SIZE);
+ output_file_name[0] = '\0';
+ memset(output_file_name, 0, NAME_SIZE);
+ arg_file_name[0] = '\0';
+ memset(arg_file_name, 0, NAME_SIZE);
+ g_hdr_input_name[0] = '\0';
+ memset(g_hdr_input_name, 0, NAME_SIZE);
+
+ /* Initialize Global variables */
+ g_verbose = NO_VERBOSE;
+
+ g_ram_start_address = chip_info[NPCX5M5G].ram_addr;
+ g_ram_size = chip_info[NPCX5M5G].ram_size;
+
+ /* Set default values */
+ g_calc_type = CALC_TYPE_NONE;
+ bin_params.spi_max_clk = SPI_MAX_CLOCK_DEAFULT;
+ bin_params.spi_read_mode = SPI_READ_MODE_DEAFULT;
+ bin_params.fw_load_addr =
+ chip_info[NPCX5M5G].ram_addr;
+ bin_params.fw_ep =
+ chip_info[NPCX5M5G].ram_addr;
+ bin_params.fw_err_detec_s_addr = FW_CRC_START_ADDR;
+ bin_params.fw_err_detec_e_addr = FW_CRC_START_ADDR;
+ bin_params.flash_size = FLASH_SIZE_DEAFULT;
+ bin_params.fw_hdr_offset = 0;
+
+ ptr_fw_addr = 0x00000000;
+ fw_offset = 0x00000000;
+ is_ptr_merge = FALSE;
+
+ /* Get Standard Output Handler */
+
+ /* Wrong Number of Arguments ? No problem */
+ if (argc < 3)
+ exit_with_usage();
+
+ /* Read all arguments to local array. */
+ for (arg_num = 0; arg_num < argc; arg_num++)
+ strncpy(hdr_args[arg_num], argv[arg_num], ARG_SIZE);
+
+ /* Loop all arguments. */
+ /* Parse the Arguments - supports ecrp and bin */
+ for (arg_ind = 1; arg_ind < arg_num; arg_ind++) {
+ /* -h display help screen */
+ if (str_cmp_no_case(hdr_args[arg_ind], "-h") == 0)
+ exit_with_usage();
+
+ /* -v verbose */
+ else if (str_cmp_no_case(hdr_args[arg_ind], "-v") == 0)
+ g_verbose = REGULAR_VERBOSE;
+
+ /* Super verbose. */
+ else if (str_cmp_no_case(hdr_args[arg_ind], "-vv") == 0)
+ g_verbose = SUPER_VERBOSE;
+
+ else if (str_cmp_no_case(hdr_args[arg_ind],
+ "-mode") == 0) {
+ mode_choose = TRUE;
+ arg_ind++;
+ if ((hdr_args[arg_ind] == NULL) ||
+ (sscanf(hdr_args[arg_ind],
+ "%s", main_str_temp) != 1)) {
+ my_printf(TERR, "\nCannot read operation mode");
+ my_printf(TERR, ", bt, bh or api. !\n");
+ main_status = FALSE;
+ } else {
+ /* bt, bh and api should not coexist */
+ if (main_fw_hdr_flag ||
+ main_api_flag ||
+ main_hdr_flag) {
+ my_printf(TERR, "\nOperation modes bt");
+ my_printf(TERR, ", bh, and api should");
+ my_printf(TERR, " not coexist.\n");
+ main_status = FALSE;
+ }
+
+ if (str_cmp_no_case(main_str_temp, "bt") == 0)
+ main_fw_hdr_flag = TRUE;
+ else if (str_cmp_no_case(main_str_temp,
+ "bh") == 0)
+ main_hdr_flag = TRUE;
+ else if (str_cmp_no_case(main_str_temp,
+ "api") == 0)
+ main_api_flag = TRUE;
+ else {
+ my_printf(TERR,
+ "\nInvalid operation mode ");
+ my_printf(TERR,
+ "(%s)\n", main_str_temp);
+ main_status = FALSE;
+ }
+ }
+ }
+
+ else if (str_cmp_no_case(hdr_args[arg_ind], "-chip") == 0) {
+ arg_ind++;
+ if ((hdr_args[arg_ind] == NULL) ||
+ (sscanf(hdr_args[arg_ind],
+ "%s",
+ main_str_temp) != 1)) {
+ my_printf(TERR, "\nCannot read chip name, ");
+ my_printf(TERR, "npcx5m5g or npcx5m6g.\n");
+ main_status = FALSE;
+ } else {
+ if (str_cmp_no_case(main_str_temp,
+ "npcx5m5g") == 0) {
+ if ((bin_params.bin_params
+ & BIN_FW_LOAD_START_ADDR) ==
+ 0x00000000)
+ bin_params.fw_load_addr =
+ chip_info[NPCX5M5G].ram_addr;
+
+ if ((bin_params.bin_params &
+ BIN_FW_ENTRY_POINT) == 0x00000000)
+ bin_params.fw_ep =
+ chip_info[NPCX5M5G].ram_addr;
+
+ g_ram_start_address =
+ chip_info[NPCX5M5G].ram_addr;
+ g_ram_size =
+ chip_info[NPCX5M5G].ram_size;
+ } else if (str_cmp_no_case(main_str_temp,
+ "npcx5m6g") == 0) {
+ if ((bin_params.bin_params &
+ BIN_FW_LOAD_START_ADDR) ==
+ 0x00000000)
+ bin_params.fw_load_addr =
+ chip_info[NPCX5M6G].ram_addr;
+
+ if ((bin_params.bin_params &
+ BIN_FW_ENTRY_POINT) ==
+ 0x00000000)
+ bin_params.fw_ep =
+ chip_info[NPCX5M6G].ram_addr;
+
+ g_ram_start_address =
+ chip_info[NPCX5M6G].ram_addr;
+ g_ram_size =
+ chip_info[NPCX5M6G].ram_size;
+
+ } else {
+ my_printf(TERR,
+ "\nInvalid chip name (%s) ",
+ main_str_temp);
+ my_printf(TERR, "should be npcx5m5g ");
+ my_printf(TERR, "or npcx5m6g.\n");
+ main_status = FALSE;
+ }
+
+ }
+ /* -argfile Read argument file. File name must be after it.*/
+ } else if (str_cmp_no_case(hdr_args[arg_ind],
+ "-argfile") == 0) {
+ arg_ind++;
+ if (arg_ind < arg_num) {
+ strncpy(arg_file_name,
+ hdr_args[arg_ind],
+ sizeof(arg_file_name));
+ arg_file_pointer = fopen(arg_file_name, "rt");
+ if (arg_file_pointer == NULL) {
+ my_printf(TERR,
+ "\n\nCannot open %s\n\n",
+ arg_file_name);
+ main_status = FALSE;
+ } else {
+ cur_arg_index = arg_ind;
+
+ /* Copy the arguments to temp array. */
+ for (tmp_ind = 0;
+ (tmp_ind + arg_ind + 1) < arg_num;
+ tmp_ind++)
+ strncpy(tmp_hdr_args[tmp_ind],
+ hdr_args
+ [tmp_ind+arg_ind+1],
+ ARG_SIZE);
+
+ tmp_arg_num = tmp_ind;
+
+ /* Read arguments from file to array */
+ for (arg_ind++;
+ fscanf(arg_file_pointer,
+ "%s",
+ hdr_args[arg_ind]) == 1;
+ arg_ind++)
+ ;
+
+ fclose(arg_file_pointer);
+ arg_file_pointer = NULL;
+
+ /* Copy back the restored arguments. */
+ for (tmp_ind = 0;
+ tmp_ind < tmp_arg_num;
+ tmp_ind++) {
+ strncpy(hdr_args[arg_ind++],
+ tmp_hdr_args[tmp_ind],
+ ARG_SIZE);
+ }
+ arg_num = arg_ind;
+ arg_ind = cur_arg_index;
+ }
+
+ } else {
+ my_printf(TERR,
+ "\nMissing Argument File Name\n");
+ main_status = FALSE;
+ }
+ /* -i get input file name. */
+ } else if (str_cmp_no_case(hdr_args[arg_ind], "-i") == 0) {
+ arg_ind++;
+ if (arg_ind < arg_num) {
+ strncpy(input_file_name,
+ hdr_args[arg_ind],
+ sizeof(input_file_name));
+ } else {
+ my_printf(TERR, "\nMissing Input File Name\n");
+ main_status = FALSE;
+ }
+ /* -o Get output file name. */
+ } else if (str_cmp_no_case(hdr_args[arg_ind], "-o") == 0) {
+ arg_ind++;
+ if (arg_ind < arg_num) {
+ strncpy(output_file_name,
+ hdr_args[arg_ind],
+ sizeof(output_file_name));
+ } else {
+ my_printf(TERR,
+ "\nMissing Output File Name.\n");
+ main_status = FALSE;
+ }
+ /* -usearmrst get FW entry point from FW image offset 4.*/
+ } else if (str_cmp_no_case(hdr_args[arg_ind],
+ "-usearmrst") == 0) {
+ if ((bin_params.bin_params &
+ BIN_FW_ENTRY_POINT) != 0x00000000) {
+ my_printf(TERR, "\n-usearmrst not allowed, ");
+ my_printf(TERR, "FW entry point already set ");
+ my_printf(TERR, "using -fwep !\n");
+ main_status = FALSE;
+ } else
+ bin_params.bin_params |=
+ BIN_FW_USER_ARM_RESET;
+ /* -nohcrs disable header CRC*/
+ } else if (str_cmp_no_case(hdr_args[arg_ind], "-nohcrc") == 0)
+ bin_params.bin_params |=
+ BIN_FW_HDR_CRC_DISABLE;
+ /* -ph merg header in BIN file. */
+ else if (str_cmp_no_case(hdr_args[arg_ind], "-ph") == 0) {
+ bin_params.bin_params |=
+ BIN_FW_HDR_OFFSET;
+ if ((strlen(hdr_args[arg_ind+1]) == 0) ||
+ (sscanf(hdr_args[arg_ind+1],
+ "%x",
+ &main_temp) != 1))
+ bin_params.fw_hdr_offset = 0;
+ else {
+ arg_ind++;
+ bin_params.fw_hdr_offset = main_temp;
+ }
+ /* -spimacclk Get SPI flash mac clock. */
+ } else if (str_cmp_no_case(hdr_args[arg_ind],
+ "-spimaxclk") == 0) {
+ arg_ind++;
+ if ((hdr_args[arg_ind] == NULL) ||
+ (sscanf(hdr_args[arg_ind],
+ "%d", &main_temp) != 1)) {
+ my_printf(TERR, "\nCannot read SPI Flash Max");
+ my_printf(TERR, " Clock !\n");
+ main_status = FALSE;
+ } else
+ bin_params.spi_max_clk =
+ (unsigned char)main_temp;
+ /* spireadmode get SPI read mode. */
+ } else if (str_cmp_no_case(hdr_args[arg_ind],
+ "-spireadmode") == 0) {
+ arg_ind++;
+ if ((hdr_args[arg_ind] == NULL) ||
+ (sscanf(hdr_args[arg_ind],
+ "%20s",
+ main_str_temp) != 1)) {
+ my_printf(TERR, "\nCannot read SPI Flash");
+ my_printf(TERR, " Read Mode !\n");
+ main_status = FALSE;
+ } else {
+ if (str_cmp_no_case(main_str_temp,
+ SPI_NORMAL_MODE_VAL) == 0)
+ bin_params.spi_read_mode =
+ (unsigned char) SPI_NORMAL_MODE;
+ else if (str_cmp_no_case(main_str_temp,
+ SPI_SINGLE_MODE_VAL) == 0)
+ bin_params.spi_read_mode =
+ (unsigned char)
+ SPI_SINGLE_MODE;
+ else if (str_cmp_no_case(main_str_temp,
+ SPI_DUAL_MODE_VAL) == 0)
+ bin_params.spi_read_mode =
+ (unsigned char)
+ SPI_DUAL_MODE;
+ else if (str_cmp_no_case(main_str_temp,
+ SPI_QUAD_MODE_VAL) == 0)
+ bin_params.spi_read_mode =
+ (unsigned char)
+ SPI_QUAD_MODE;
+ else {
+ my_printf(TERR,
+ "\nInvalid SPI Flash Read "
+ "Mode (%s), it should be "
+ "normal, singleMode, "
+ "dualMode or quadMode !\n",
+ main_str_temp);
+ main_status = FALSE;
+ }
+ }
+ /* -nofcrc disable FW CRC. */
+ } else if (str_cmp_no_case(hdr_args[arg_ind], "-nofcrc") == 0)
+ bin_params.bin_params |=
+ BIN_FW_CRC_DISABLE;
+
+ /* -fwloadaddr, Get the FW load address. */
+ else if (str_cmp_no_case(hdr_args[arg_ind],
+ "-fwloadaddr") == 0) {
+ arg_ind++;
+ if ((hdr_args[arg_ind] == NULL) ||
+ (sscanf(hdr_args[arg_ind],
+ "%x",
+ &main_temp) != 1)) {
+ my_printf(TERR, "\nCannot read FW Load ");
+ my_printf(TERR, "\nstart address !\n");
+ main_status = FALSE;
+ } else {
+ /* Check that the address is 16-bytes aligned */
+ if ((main_temp &
+ ADDR_16_BYTES_ALIGNED_MASK) != 0) {
+ my_printf(TERR,
+ "\nFW load address start "
+ "address (0x%08X) is not "
+ "16-bytes aligned !\n",
+ main_temp);
+ main_status = FALSE;
+ } else {
+ bin_params.fw_load_addr =
+ main_temp;
+ bin_params.bin_params |=
+ BIN_FW_LOAD_START_ADDR;
+ }
+ }
+ /* -fwep, Get the FW entry point. */
+ } else if (str_cmp_no_case(hdr_args[arg_ind], "-fwep") == 0) {
+ if ((bin_params.bin_params & BIN_FW_USER_ARM_RESET)
+ != 0x00000000) {
+ my_printf(TERR,
+ "\n-fwep not allowed, FW entry point"
+ " already set using -usearmrst!\n");
+ main_status = FALSE;
+ } else {
+ arg_ind++;
+ if ((hdr_args[arg_ind] == NULL) ||
+ (sscanf(hdr_args[arg_ind],
+ "%x",
+ &main_temp) != 1)) {
+ my_printf(TERR,
+ "\nCan't read FW E-Point\n");
+ main_status = FALSE;
+ } else {
+ bin_params.fw_ep =
+ main_temp;
+ bin_params.bin_params |=
+ BIN_FW_ENTRY_POINT;
+ }
+ }
+ /*
+ * -crcstart, Get the address from where to calculate
+ * the FW CRC.
+ */
+ } else if (str_cmp_no_case(hdr_args[arg_ind],
+ "-crcstart") == 0) {
+ arg_ind++;
+ if ((hdr_args[arg_ind] == NULL) ||
+ (sscanf(hdr_args[arg_ind],
+ "%x",
+ &main_temp) != 1)) {
+ my_printf(TERR,
+ "\nCannot read FW CRC"
+ " start address !\n");
+ main_status = FALSE;
+ } else {
+ bin_params.fw_err_detec_e_addr =
+ bin_params.fw_err_detec_e_addr -
+ bin_params.fw_err_detec_s_addr
+ + main_temp;
+ bin_params.fw_err_detec_s_addr =
+ main_temp;
+ bin_params.bin_params |= BIN_FW_CKS_START;
+ }
+ /* -crcsize, Get the area size that need to be CRCed. */
+ } else if (str_cmp_no_case(hdr_args[arg_ind],
+ "-crcsize") == 0) {
+ arg_ind++;
+ if ((hdr_args[arg_ind] == NULL) ||
+ (sscanf(hdr_args[arg_ind], "%x", &main_temp)
+ != 1)) {
+ my_printf(TERR, "\nCannot read FW CRC ");
+ my_printf(TERR, "\area size !\n");
+ main_status = FALSE;
+ } else {
+ bin_params.fw_err_detec_e_addr =
+ bin_params.fw_err_detec_s_addr
+ + main_temp - 1;
+ bin_params.bin_params |= BIN_FW_CKS_SIZE;
+ }
+ }
+ /* -fwlen, Get the FW length. */
+ else if (str_cmp_no_case(hdr_args[arg_ind], "-fwlen") == 0) {
+ arg_ind++;
+ if ((hdr_args[arg_ind] == NULL) ||
+ (sscanf(hdr_args[arg_ind],
+ "%x",
+ &main_temp) != 1)) {
+ my_printf(TERR, "\nCannot read FW length !\n");
+ main_status = FALSE;
+ } else {
+ bin_params.fw_len = main_temp;
+ bin_params.bin_params |= BIN_FW_LENGTH;
+ }
+ }
+ /* flashsize, Get the flash size. */
+ else if (str_cmp_no_case(hdr_args[arg_ind],
+ "-flashsize") == 0) {
+ arg_ind++;
+ if ((hdr_args[arg_ind] == NULL) ||
+ (sscanf(hdr_args[arg_ind],
+ "%d",
+ &main_temp) != 1)) {
+ my_printf(TERR, "\nCannot read Flash size !\n");
+ main_status = FALSE;
+ } else
+ bin_params.flash_size = main_temp;
+ /* -apisign, Get the method for error detect calculation. */
+ } else if (str_cmp_no_case(hdr_args[arg_ind],
+ "-apisign") == 0) {
+ arg_ind++;
+ if ((hdr_args[arg_ind] == NULL) ||
+ (sscanf(hdr_args[arg_ind],
+ "%s",
+ main_str_temp) != 1)) {
+ my_printf(TERR, "\nCannot read API sign, CRC,");
+ my_printf(TERR, " CheckSum or None. !\n");
+ main_status = FALSE;
+ } else {
+ if (!main_api_flag) {
+ my_printf(TERR, "\n-apisign is valid ");
+ my_printf(TERR, "-only with -api.\n");
+ main_status = FALSE;
+ }
+
+ if (str_cmp_no_case(main_str_temp, "crc") == 0)
+ g_calc_type = CALC_TYPE_CRC;
+
+ else if (str_cmp_no_case(main_str_temp,
+ "checksum") == 0)
+ g_calc_type = CALC_TYPE_CHECKSUM;
+
+ else {
+ my_printf(TERR,
+ "\nInvalid API sign (%s)\n",
+ main_str_temp);
+ main_status = FALSE;
+ }
+
+ }
+ /* -pointer, Get the FW image address. */
+ } else if (str_cmp_no_case(hdr_args[arg_ind],
+ "-pointer") == 0) {
+ arg_ind++;
+ if ((hdr_args[arg_ind] == NULL) ||
+ (sscanf(hdr_args[arg_ind],
+ "%x",
+ &main_temp) != 1)) {
+ my_printf(TERR,
+ "\nCannot read FW Image address !\n");
+ main_status = FALSE;
+ } else {
+ /* Check that the address is 16-bytes aligned */
+ if ((main_temp & ADDR_16_BYTES_ALIGNED_MASK)
+ != 0) {
+ my_printf(TERR,
+ "\nFW Image address (0x%08X)"
+ " isn't 16-bytes aligned !\n",
+ main_temp);
+ main_status = FALSE;
+ }
+
+ if (main_temp > MAX_FLASH_SIZE) {
+ my_printf(TERR,
+ "\nPointer address (0x%08X) ",
+ main_temp);
+ my_printf(TERR,
+ "is higher from flash size");
+ my_printf(TERR,
+ " (0x%08X) !\n",
+ MAX_FLASH_SIZE);
+ main_status = FALSE;
+ } else {
+ ptr_fw_addr = main_temp;
+ is_ptr_merge = FALSE;
+ }
+ }
+ }
+ /* -bhoffset, BootLoader Header Offset (BH location in BT). */
+ else if (str_cmp_no_case(hdr_args[arg_ind], "-bhoffset") == 0) {
+ arg_ind++;
+ if ((hdr_args[arg_ind] == NULL) ||
+ (sscanf(hdr_args[arg_ind], "%x", &main_temp)
+ != 1)) {
+ my_printf(TERR, "\nCannot read BootLoader");
+ my_printf(TERR, " Header Offset !\n");
+ main_status = FALSE;
+ } else {
+ /* Check that the address is 16-bytes aligned */
+ if ((main_temp & ADDR_16_BYTES_ALIGNED_MASK)
+ != 0) {
+ my_printf(TERR,
+ "\nFW Image address (0x%08X) "
+ "is not 16-bytes aligned !\n",
+ main_temp);
+ main_status = FALSE;
+ }
+
+ if (main_temp > MAX_FLASH_SIZE) {
+ my_printf(TERR,
+ "\nFW Image address (0x%08X)"
+ " is higher from flash size "
+ "(0x%08X) !\n",
+ main_temp,
+ MAX_FLASH_SIZE);
+ main_status = FALSE;
+ } else {
+ fw_offset = main_temp;
+ is_ptr_merge = TRUE;
+ }
+ }
+ } else {
+ my_printf(TERR,
+ "\nUnknown flag: %s\n",
+ hdr_args[arg_ind]);
+ main_status = FALSE;
+ }
+ }
+
+ /*
+ * If the input and output file have the same name then exit with error.
+ */
+ if (strcmp(output_file_name, input_file_name) == 0) {
+ my_printf(TINF,
+ "Input file name (%s) should be differed from\n",
+ input_file_name);
+ my_printf(TINF, "Output file name (%s).\n", output_file_name);
+ main_status = FALSE;
+ }
+
+ /* No problems reading argv? So go on... */
+ if (main_status) {
+
+ /* if output file already exist, then delete it. */
+ tmp_file = fopen(output_file_name, "w");
+ if (tmp_file != NULL)
+ fclose(tmp_file);
+
+ /* If no mode choose than "bt" is the default mode.*/
+ if (mode_choose == FALSE)
+ main_fw_hdr_flag = TRUE;
+
+ /* Chose manipulation routine according to arguments */
+ if (main_fw_hdr_flag)
+ main_status = main_bin(bin_params);
+ else if (main_api_flag)
+ main_status = main_api();
+ else if (main_hdr_flag)
+ main_status = main_hdr();
+ else
+ exit_with_usage();
+ }
+
+
+
+ /* Be sure there's no open file before you leave */
+ if (input_file_pointer)
+ fclose(input_file_pointer);
+ if (g_hfd_pointer)
+ fclose(g_hfd_pointer);
+ if (api_file_pointer)
+ fclose(api_file_pointer);
+
+ /* Delete temprary header file. */
+ remove(g_hdr_input_name);
+
+ /* Say Bye Bye */
+ if (main_status) {
+ my_printf(TPAS, "\n\n******************************");
+ my_printf(TPAS, "\n*** SUCCESS ***");
+ my_printf(TPAS, "\n******************************\n");
+
+ exit(EXIT_SUCCESS);
+ } else {
+ my_printf(TERR, "\n\n******************************");
+ my_printf(TERR, "\n*** FAILED ***");
+ my_printf(TERR, "\n******************************\n");
+
+ exit(EXIT_FAILURE);
+ }
+
+}
+
+
+/*
+ *-----------------------------------------------------------------------
+ * Function: exit_with_usage()
+ * Parameters: none
+ * Return: none
+ * Description: No Words...
+ *-----------------------------------------------------------------------
+ */
+void exit_with_usage(void)
+{
+ my_printf(TUSG,
+ "\nECST, Embedded Controller Sign Tool, version %d.%d.%d",
+ T_VER, T_REV_MAJOR, T_REV_MINOR);
+ my_printf(TUSG, "\n");
+ my_printf(TUSG, "\nUsage:");
+ my_printf(TUSG, "\n ");
+ my_printf(TUSG, "\n ECST -mode <bt|bh|api> -i <filename> [Flags]");
+ my_printf(TUSG, "\n ");
+ my_printf(TUSG, "\nOperation Modes: ");
+ my_printf(TUSG, "\n bt - BootLoader Table");
+ my_printf(TUSG, "\n bh - BootLoader Header");
+ my_printf(TUSG, "\n api - Download from Flash API");
+ my_printf(TUSG, "\n ");
+ my_printf(TUSG, "\nCommon flags:");
+ my_printf(TUSG, "\n -mode <type> - Operation mode: ");
+ my_printf(TUSG, "bt|bh|api (default is bt)");
+ my_printf(TUSG, "\n -i <filename> - Input file name; ");
+ my_printf(TUSG, "must differ from the output file name");
+ my_printf(TUSG, "\n -o <filename> - Output file name ");
+ my_printf(TUSG, "(default is out_<input_filename>.bin)");
+ my_printf(TUSG, "\n -argfile <filename> - Arguments file name; ");
+ my_printf(TUSG, "includes multiple flags");
+ my_printf(TUSG, "\n -chip <name> - EC Chip Name: ");
+ my_printf(TUSG, "npcx5m5g|npcx5m6g (default is npcx5m5g)");
+ my_printf(TUSG, "\n -v - Verbose; prints ");
+ my_printf(TUSG, "information messages");
+ my_printf(TUSG, "\n -vv - Super Verbose; prints ");
+ my_printf(TUSG, "intermediate calculations");
+ my_printf(TUSG, "\n -h - Show this help screen");
+ my_printf(TUSG, "\n ");
+ my_printf(TUSG, "\nBootLoader Table mode flags:");
+ my_printf(TUSG, "\n -nohcrc - Disable CRC on header ");
+ my_printf(TUSG, "(default is ON)");
+ my_printf(TUSG, "\n -nofcrc - Disable CRC on firmware ");
+ my_printf(TUSG, "(default is ON)");
+ my_printf(TUSG, "\n -spimaxclk <val> - SPI Flash Maximum Clock, in");
+ my_printf(TUSG, " MHz: 20|25|33|40|50 (default is 20)");
+ my_printf(TUSG, "\n -spireadmode <type> - SPI Flash Read Mode: ");
+ my_printf(TUSG, "normal|fast|dual|quad (default is normal)");
+ my_printf(TUSG, "\n -fwloadaddr <addr> - Firmware load start ");
+ my_printf(TUSG, "address (default is Start-of-RAM)");
+ my_printf(TUSG, "\n Located in code RAM, ");
+ my_printf(TUSG, "16-bytes aligned, hex format");
+ my_printf(TUSG, "\n -usearmrst - Use the ARM reset table ");
+ my_printf(TUSG, "entry as the Firmware Entry Point");
+ my_printf(TUSG, "\n Can't be used with -fwep");
+ my_printf(TUSG, "\n -fwep <addr> - Firmware entry ");
+ my_printf(TUSG, "point (default is Firmware Entry Point)");
+ my_printf(TUSG, "\n Located in firmware area,");
+ my_printf(TUSG, " hex format");
+ my_printf(TUSG, "\n -crcstart <offset> - Firmware CRC start offset ");
+ my_printf(TUSG, "(default is 00000000)");
+ my_printf(TUSG, "\n Offset from firmware image,");
+ my_printf(TUSG, " 4B-aligned, for partial CRC, hex format");
+ my_printf(TUSG, "\n -crcsize <val> - Firmware CRC size ");
+ my_printf(TUSG, "(default is entire firmware size)");
+ my_printf(TUSG, "\n 4B-aligned, for partial ");
+ my_printf(TUSG, "CRC, hex format");
+ my_printf(TUSG, "\n -fwlen <val> - Firmware length, ");
+ my_printf(TUSG, "16B-aligned, hex format (default is file size).");
+ my_printf(TUSG, "\n -flashsize <val> - Flash size, in MB: ");
+ my_printf(TUSG, "1|2|4|8|16 (default is 16)");
+ my_printf(TUSG, "\n -ph <offset> - Paste the Firmware ");
+ my_printf(TUSG, "Header in the input file copy at the selected");
+ my_printf(TUSG, "\n offset ");
+ my_printf(TUSG, "(default is 00000000), hex format.");
+ my_printf(TUSG, "\n The firmware itself is ");
+ my_printf(TUSG, "expected to start at offset + 64 bytes.");
+ my_printf(TUSG, "\n ");
+ my_printf(TUSG, "\nBootLoader Header mode flags:");
+ my_printf(TUSG, "\n -pointer <offset> - BootLoader Table location");
+ my_printf(TUSG, " in the flash, hex format");
+ my_printf(TUSG, "\n -bhoffset <offset> - BootLoader Header Offset");
+ my_printf(TUSG, " in file, hex format (BH location in BT)");
+ my_printf(TUSG, "\n ");
+ my_printf(TUSG, "\nAPI mode flags:");
+ my_printf(TUSG, "\n -apisign <type> - Signature type: ");
+ my_printf(TUSG, "crc|checksum (default is OFF)");
+ my_printf(TUSG, "\n\n");
+
+ exit(EXIT_FAILURE);
+}
+
+/*
+ *--------------------------------------------------------------------------
+ * Function: copy_file_to_file()
+ * Parameters: dst_file_name - Destination file name.
+ * src_file_name - Source file name.
+ * offset - number of bytes from the origin.
+ * origin - From where to seek, START, END, or CURRENT of
+ * file.
+ * Return: Number of copied bytes
+ * Description: Copy the source file to the end of the destination file.
+ *--------------------------------------------------------------------------
+ */
+int copy_file_to_file(char *dst_file_name,
+ char *src_file_name,
+ int offset,
+ int origin)
+{
+
+ int index;
+ int result = 0;
+ unsigned char local_val;
+ int src_file_size;
+ FILE *dst_file;
+ FILE *src_file;
+
+ /* Open the destination file for append. */
+ dst_file = fopen(dst_file_name, "r+b");
+ if (dst_file == NULL) {
+ /* destination file not exist, create it. */
+ dst_file = fopen(dst_file_name, "ab");
+ if (dst_file == NULL)
+ return 0;
+ }
+
+ /* Open the source file for read. */
+ src_file = fopen(src_file_name, "rb");
+ if (src_file == NULL)
+ return 0;
+
+ /* Get the source file length in bytes. */
+ src_file_size = get_file_length(src_file);
+
+ /* Point to the end of the destination file, and to the start */
+ /* of the source file. */
+ fseek(dst_file, offset, origin);
+ fseek(src_file, 0, SEEK_SET);
+
+ /* Loop over all destination file and write it to the source file.*/
+ for (index = 0; index < src_file_size; index++) {
+ /* Read byte from source file. */
+ result = (int)(fread(&local_val, 1, 1, src_file));
+
+ /* If byte reading pass than write it to the destination, */
+ /* else exit from the reading loop. */
+ if (result)
+ /* Read pass, so write it to destination file.*/
+ result = fwrite(&local_val, 1, 1, dst_file);
+ else
+ /* Read failed, return with the copied bytes number. */
+ break;
+ }
+
+ /* Close the files. */
+ fclose(dst_file);
+ fclose(src_file);
+
+ /* Copy ended, return with the number of bytes that were copied. */
+ return index;
+
+}
+
+/*
+ *--------------------------------------------------------------------------
+ * Function: my_printf()
+ * Parameters: as in printf + error level
+ * Return: none
+ * Description: No Words...
+ *--------------------------------------------------------------------------
+ */
+void my_printf(int error_level, char *fmt, ...)
+{
+ char buffer[256];
+ va_list argptr;
+ va_start(argptr, fmt);
+ vsprintf(buffer, fmt, argptr);
+ va_end(argptr);
+
+ if ((g_verbose == NO_VERBOSE) && (error_level == TINF))
+ return;
+
+ if ((error_level == TDBG) && (g_verbose != SUPER_VERBOSE))
+ return;
+
+ printf("%s", buffer);
+}
+
+/*
+ *--------------------------------------------------------------------------
+ * Function: write_to_file
+ * Parameters: TBD
+ * Return: TBD
+ * Description: Writes to ELF or BIN files - whateves is open
+ *--------------------------------------------------------------------------
+ */
+int write_to_file(unsigned int write_value,
+ unsigned int offset,
+ unsigned char num_of_bytes,
+ char *print_string)
+{
+
+ int result = 0;
+ int index;
+ unsigned int localValue4;
+ unsigned short localValue2;
+ unsigned char localValue1;
+
+ fseek(g_hfd_pointer, 0L, SEEK_SET);
+ fseek(g_hfd_pointer, offset, SEEK_SET);
+
+ switch (num_of_bytes) {
+ case(1):
+ localValue1 = (unsigned char)write_value;
+ result = (int)(fwrite(&localValue1, 1,
+ 1, g_hfd_pointer));
+ break;
+ case(2):
+ localValue2 = (unsigned short)write_value;
+ result = (int)(fwrite(&localValue2,
+ 2,
+ 1,
+ g_hfd_pointer));
+ break;
+ case(4):
+ localValue4 = write_value;
+ result = (int)(fwrite(&localValue4,
+ 4,
+ 1,
+ g_hfd_pointer));
+ break;
+ default:
+ /* Pad the same value N times. */
+ localValue1 = (unsigned char)write_value;
+ for (index = 0; index < num_of_bytes; index++)
+ result = (int)(fwrite(&localValue1,
+ 1,
+ 1,
+ g_hfd_pointer));
+ break;
+ }
+
+ my_printf(TINF, "\nIn write_to_file - %s", print_string);
+
+ if (result) {
+ my_printf(TINF,
+ " - Offset %2d - value 0x%x",
+ offset, write_value);
+ } else {
+ my_printf(TERR,
+ "\n\nCouldn't write %x to file at %x\n\n",
+ write_value, offset);
+ return FALSE;
+ }
+
+ return TRUE;
+
+}
+
+/*
+ *--------------------------------------------------------------------------
+ * Function: read_from_file
+ * Parameters: TBD
+ * Return : TBD
+ * Description : Reads from open BIN file
+ *--------------------------------------------------------------------------
+ */
+int read_from_file(unsigned int offset,
+ unsigned char size_to_read,
+ unsigned int *read_value,
+ char *print_string)
+{
+ int result;
+ unsigned int localValue4;
+ unsigned short localValue2;
+ unsigned char localValue1;
+
+ fseek(input_file_pointer, 0L, SEEK_SET);
+ fseek(input_file_pointer, offset, SEEK_SET);
+
+ switch (size_to_read) {
+ case(1):
+ result = (int)(fread(&localValue1,
+ 1,
+ 1,
+ input_file_pointer));
+ *read_value = localValue1;
+ break;
+ case(2):
+ result = (int)(fread(&localValue2,
+ 2,
+ 1,
+ input_file_pointer));
+ *read_value = localValue2;
+ break;
+ case(4):
+ result = (int)(fread(&localValue4,
+ 4,
+ 1,
+ input_file_pointer));
+ *read_value = localValue4;
+ break;
+ default:
+ my_printf(TERR, "\nIn read_from_file - %s", print_string);
+ my_printf(TERR, "\n\nInvalid call to read_from_file\n\n");
+ return FALSE;
+ break;
+ }
+
+ my_printf(TINF, "\nIn read_from_file - %s", print_string);
+
+ if (result) {
+ my_printf(TINF,
+ " - Offset %d - value %x",
+ offset, *read_value);
+ } else {
+ my_printf(TERR,
+ "\n\nCouldn't read from file at %x\n\n",
+ offset);
+ return FALSE;
+ }
+
+ return TRUE;
+}
+
+/*
+ *--------------------------------------------------------------------------
+ * Function: init_calculation
+ * Parameters: unsigned int check_sum_crc (I\O)
+ * Return:
+ * Description: Initialize the variable according to the selected
+ * calculation
+ *--------------------------------------------------------------------------
+ */
+void init_calculation(unsigned int *check_sum_crc)
+{
+ switch (g_calc_type) {
+ case CALC_TYPE_NONE:
+ case CALC_TYPE_CHECKSUM:
+ *check_sum_crc = 0;
+ break;
+ case CALC_TYPE_CRC:
+ *check_sum_crc = initialize_crc_32();
+ break;
+ }
+}
+
+/*
+ *--------------------------------------------------------------------------
+ * Function: finalize_calculation
+ * Parameters: unsigned int check_sum_crc (I\O)
+ * Return:
+ * Description: Finalize the variable according to the selected calculation
+ *--------------------------------------------------------------------------
+ */
+void finalize_calculation(unsigned int *check_sum_crc)
+{
+ switch (g_calc_type) {
+ case CALC_TYPE_NONE:
+ case CALC_TYPE_CHECKSUM:
+ /* Do nothing */
+ break;
+ case CALC_TYPE_CRC:
+ *check_sum_crc = finalize_crc_32(*check_sum_crc);
+ break;
+ }
+}
+
+/*--------------------------------------------------------------------------
+ * Function: update_calculation
+ * Parameters: unsigned int check_sum_crc (I\O)
+ * unsigned int byte_to_add (I)
+ * Return:
+ * Description: Calculate a new checksum\crc with the new byte_to_add
+ * given the previous checksum\crc
+ *--------------------------------------------------------------------------
+ */
+void update_calculation(unsigned int *check_sum_crc,
+ unsigned char byte_to_add)
+{
+ switch (g_calc_type) {
+ case CALC_TYPE_NONE:
+ /* Do nothing */
+ break;
+ case CALC_TYPE_CHECKSUM:
+ *check_sum_crc += byte_to_add;
+ break;
+ case CALC_TYPE_CRC:
+ *check_sum_crc = update_crc_32(*check_sum_crc, byte_to_add);
+ break;
+ }
+}
+
+/*
+ *--------------------------------------------------------------------------
+ * Function: str_cmp_no_case
+ * Parameters: s1, s2: Strings to compare.
+ * Return: function returns an integer less than, equal to, or
+ * greater than zero if s1 (or the first n bytes thereof) is
+ * found, respectively, to be less than, to match, or be
+ * greater than s2.
+ * Description: Compare two string without case sensitive.
+ *--------------------------------------------------------------------------
+ */
+int str_cmp_no_case(const char *s1, const char *s2)
+{
+ return strcasecmp(s1, s2);
+}
+
+/*
+ *--------------------------------------------------------------------------
+ * Function: get_file_lengt
+ * Parameters: stream - Pointer to a FILE objec
+ * Return: File length in bytes
+ * Description: Gets the file length in bytes.
+ *--------------------------------------------------------------------------
+ */
+int get_file_length(FILE *stream)
+{
+ int curent_position;
+ int file_len;
+
+ /* Store current position. */
+ curent_position = ftell(stream);
+
+ /* End position of the file is its length. */
+ fseek(stream, 0, SEEK_END); /* seek to end of file */
+ file_len = ftell(stream);
+
+ /* Restore the original position. */
+ fseek(stream, curent_position, SEEK_SET);
+
+ /* return file length. */
+ return file_len;
+}
+
+/*
+ ***************************************************************************
+ * "bt" mode Handler
+ ***************************************************************************
+ */
+
+/*
+ ***************************************************************************
+ * Function: main_bin
+ * Parameters: TBD
+ * Return: True for success
+ * Description:
+ * TBD
+ ***************************************************************************
+ */
+int main_bin(struct tbinparams binary_params)
+{
+ char dir_name[NAME_SIZE];
+ char *file_name_ptr = NULL;
+ char *tmp_str_ptr;
+ int dir_name_len;
+ unsigned int bin_file_size_bytes;
+ unsigned int bin_fw_offset = 0;
+ unsigned int tmp_param;
+ FILE *output_file_pointer;
+
+ /* If input file was not declared, then print error message. */
+ if (strlen(input_file_name) == 0) {
+ my_printf(TERR, "\n\nDefine input file, using -i flag\n\n");
+ return FALSE;
+ }
+
+ /* Open input file */
+ input_file_pointer = fopen(input_file_name, "r+b");
+ if (input_file_pointer == NULL) {
+ my_printf(TERR, "\n\nCannot open %s\n\n", input_file_name);
+ return FALSE;
+ }
+
+ /*
+ * Check Binary file size, this file contain the image itself,
+ * without any header.
+ */
+ bin_file_size_bytes = get_file_length(input_file_pointer);
+ if (bin_file_size_bytes == 0) {
+ my_printf(TINF,
+ "\nBIN Input file name %s is empty (size is %d)\n",
+ input_file_name, bin_file_size_bytes);
+ return FALSE;
+ }
+
+ /*
+ * If the binary file contains also place for the header, then the FW
+ * size is the length of the file minus the header length
+ */
+ if ((binary_params.bin_params & BIN_FW_HDR_OFFSET) != 0)
+ bin_fw_offset = binary_params.fw_hdr_offset + HEADER_SIZE;
+
+ my_printf(TINF, "\nBIN file: %s, size: %d (0x%x) bytes\n",
+ input_file_name,
+ bin_file_size_bytes,
+ bin_file_size_bytes);
+
+ /* Check validity of FW header offset. */
+ if (((int)binary_params.fw_hdr_offset < 0) ||
+ (binary_params.fw_hdr_offset > bin_file_size_bytes)) {
+ my_printf(TERR,
+ "\nFW header offset 0x%08x (%d) should be in the"
+ " range of 0 and file size (%d).\n",
+ binary_params.fw_hdr_offset,
+ binary_params.fw_hdr_offset,
+ bin_file_size_bytes);
+ return FALSE;
+ }
+
+ /* Get the input directory and input file name. */
+ file_name_ptr = input_file_name;
+ for (tmp_str_ptr = input_file_name; tmp_str_ptr != NULL;) {
+ tmp_str_ptr = strstr(tmp_str_ptr, DIR_DELIMITER_STR);
+ if (tmp_str_ptr != NULL) {
+ file_name_ptr = tmp_str_ptr + strlen(DIR_DELIMITER_STR);
+ tmp_str_ptr = file_name_ptr;
+ }
+ }
+
+ dir_name_len = strlen(input_file_name) - strlen(file_name_ptr);
+ strncpy(dir_name, input_file_name, dir_name_len);
+ dir_name[dir_name_len] = '\0';
+
+ /* Create the header file in the same directory as the input file. */
+ sprintf(g_hdr_input_name, "%shdr_%s", dir_name, file_name_ptr);
+ g_hfd_pointer = fopen(g_hdr_input_name, "w+b");
+ if (g_hfd_pointer == NULL) {
+ my_printf(TERR, "\n\nCannot open %s\n\n", g_hdr_input_name);
+ return FALSE;
+ }
+
+ if (strlen(output_file_name) == 0)
+ sprintf(output_file_name, "%sout_%s", dir_name, file_name_ptr);
+
+ my_printf(TINF, "Output file name: %s\n", output_file_name);
+
+ /*
+ *********************************************************************
+ * Set the ANCHOR & Extended-ANCHOR
+ *********************************************************************
+ */
+ /* Write the ancore. */
+ if (!write_to_file(FW_HDR_ANCHOR,
+ HDR_ANCHOR_OFFSET,
+ 4,
+ "HDR - FW Header ANCHOR "))
+ return FALSE;
+
+ /* Write the extended anchor. */
+ if (binary_params.bin_params & BIN_FW_HDR_CRC_DISABLE) {
+
+ /* Write the ancore and the extended anchor. */
+ if (!write_to_file(FW_HDR_EXT_ANCHOR_DISABLE,
+ HDR_EXTENDED_ANCHOR_OFFSET, 2,
+ "HDR - Header EXTENDED ANCHOR "))
+ return FALSE;
+ } else {
+ /* Write the anchor and the extended anchor. */
+ if (!write_to_file(FW_HDR_EXT_ANCHOR_ENABLE,
+ HDR_EXTENDED_ANCHOR_OFFSET, 2,
+ "HDR - Header EXTENDED ANCHOR "))
+ return FALSE;
+ }
+
+ /* Write the SPI flash MAX clock. */
+ switch (binary_params.spi_max_clk) {
+ case SPI_MAX_CLOCK_20_MHZ_VAL:
+ tmp_param = SPI_MAX_CLOCK_20_MHZ;
+ break;
+ case SPI_MAX_CLOCK_25_MHZ_VAL:
+ tmp_param = SPI_MAX_CLOCK_25_MHZ;
+ break;
+ case SPI_MAX_CLOCK_33_MHZ_VAL:
+ tmp_param = SPI_MAX_CLOCK_33_MHZ;
+ break;
+ case SPI_MAX_CLOCK_40_MHZ_VAL:
+ tmp_param = SPI_MAX_CLOCK_40_MHZ;
+ break;
+ case SPI_MAX_CLOCK_50_MHZ_VAL:
+ tmp_param = SPI_MAX_CLOCK_50_MHZ;
+ break;
+ default:
+ my_printf(TERR, "\n\nInvalid SPI Flash MAX clock (%d MHz) ",
+ binary_params.spi_max_clk);
+ my_printf(TERR, "- it should be 20, 25, 33, 40 or 50 MHz");
+ return FALSE;
+ break;
+ }
+
+ if (!write_to_file(tmp_param, HDR_SPI_MAX_CLK_OFFSET, 1,
+ "HDR - SPI flash MAX Clock "))
+ return FALSE;
+
+ /* Write the SPI flash Read Mode. */
+ if (!write_to_file(binary_params.spi_read_mode,
+ HDR_SPI_READ_MODE_OFFSET, 1,
+ "HDR - SPI flash Read Mode "))
+ return FALSE;
+
+ /* Write the error detection configuration. */
+ if (binary_params.bin_params & BIN_FW_CRC_DISABLE) {
+ if (!write_to_file(FW_CRC_DISABLE,
+ HDR_ERR_DETECTION_CONF_OFFSET,
+ 1,
+ "HDR - FW CRC Disabled "))
+ return FALSE;
+ } else {
+ /* Write the ancore and the extended anchor. */
+ if (!write_to_file(FW_CRC_ENABLE,
+ HDR_ERR_DETECTION_CONF_OFFSET, 1,
+ "HDR - FW CRC Enabled "))
+ return FALSE;
+ }
+
+ /* FW entry point should be between the FW load address and RAM size */
+ if ((binary_params.fw_load_addr >
+ (g_ram_start_address + g_ram_size)) ||
+ (binary_params.fw_load_addr < g_ram_start_address)) {
+ my_printf(TERR,
+ "\nFW load address (0x%08x) should be between "
+ "start (0x%08x) and end (0x%08x) of RAM ).",
+ binary_params.fw_load_addr,
+ g_ram_start_address,
+ (g_ram_start_address + g_ram_size));
+ return FALSE;
+ }
+
+ /* Write the FW load start address */
+ if (!write_to_file(binary_params.fw_load_addr,
+ HDR_FW_LOAD_START_ADDR_OFFSET, 4,
+ "HDR - FW load start address "))
+ return FALSE;
+
+ /*
+ * Write the FW length. (MUST BE SET BEFORE fw_err_detec_e_addr)
+ */
+ if ((binary_params.bin_params & BIN_FW_LENGTH) == 0x00000000) {
+ /*
+ * In case the FW length was not set, then the FW length is the
+ * size of the binary file minus the offset of the start of the
+ * FW.
+ */
+ binary_params.fw_len = bin_file_size_bytes-bin_fw_offset;
+ }
+
+ if ((int)binary_params.fw_len < 0) {
+ my_printf(TERR,
+ "\nFW length %d (0x%08x) should be greater than 0x0.",
+ binary_params.fw_len,
+ binary_params.fw_len);
+ return FALSE;
+ }
+
+ if (((int)binary_params.fw_len >
+ (bin_file_size_bytes - bin_fw_offset)) ||
+ ((int)binary_params.fw_len > g_ram_size)) {
+ my_printf(TERR,
+ "\nFW length %d (0x%08x) should be within the",
+ binary_params.fw_len, binary_params.fw_len);
+ my_printf(TERR,
+ " input-file (related to the FW offset)");
+ my_printf(TERR,
+ "\n (0x%08x) and within the RAM (RAM size: 0x%08x).",
+ (bin_file_size_bytes - bin_fw_offset), g_ram_size);
+ return FALSE;
+ }
+
+ if ((binary_params.bin_params & BIN_FW_USER_ARM_RESET) != 0x00000000) {
+ read_from_file((bin_fw_offset + ARM_FW_ENTRY_POINT_OFFSET),
+ 4,
+ &binary_params.fw_ep,
+ "read FW entry point for FW image ");
+
+ if ((binary_params.fw_ep <
+ binary_params.fw_load_addr) ||
+ (binary_params.fw_ep >
+ (binary_params.fw_load_addr +
+ binary_params.fw_len))) {
+ my_printf(TERR,
+ "\nFW entry point (0x%08x) should be between",
+ binary_params.fw_ep);
+ my_printf(TERR,
+ " the FW load address (0x%08x) ",
+ binary_params.fw_load_addr);
+ my_printf(TERR,
+ "and FW length (0x%08x).\n",
+ (binary_params.fw_load_addr +
+ binary_params.fw_len));
+ return FALSE;
+ }
+ }
+
+ /* FW entry point should be between the FW load address and RAM size */
+ if ((binary_params.fw_ep <
+ binary_params.fw_load_addr) ||
+ (binary_params.fw_ep >
+ (binary_params.fw_load_addr +
+ binary_params.fw_len))) {
+ if (((binary_params.bin_params & BIN_FW_ENTRY_POINT) ==
+ 0x00000000) &&
+ ((binary_params.bin_params &
+ BIN_FW_LOAD_START_ADDR) != 0x00000000)) {
+ binary_params.fw_ep =
+ binary_params.fw_load_addr;
+ } else {
+ my_printf(TERR,
+ "\nFW entry point (0x%08x) should be ",
+ binary_params.fw_ep);
+ my_printf(TERR,
+ "\between the FW load address (0x%08x)",
+ binary_params.fw_load_addr);
+ my_printf(TERR,
+ " and FW length (0x%08x).\n",
+ (binary_params.fw_load_addr +
+ binary_params.fw_len));
+ return FALSE;
+ }
+ }
+
+ /* Write the FW entry point */
+ if (!write_to_file(binary_params.fw_ep,
+ HDR_FW_ENTRY_POINT_OFFSET,
+ 4,
+ "HDR - FW Entry point "))
+ return FALSE;
+
+ /* Calculate the CRC end address. */
+ if ((binary_params.bin_params & BIN_FW_CKS_SIZE) == 0x00000000) {
+ /*
+ * In case the size was not set, then CRC end address is
+ * the size of the binary file.
+ */
+ binary_params.fw_err_detec_e_addr =
+ binary_params.fw_len - 1;
+ } else {
+ /* CRC end address should be less than FW length. */
+ if (binary_params.fw_err_detec_e_addr >
+ (binary_params.fw_len - 1)) {
+ my_printf(TERR,
+ "\nCRC end address (0x%08x) should be less ",
+ binary_params.fw_err_detec_e_addr);
+ my_printf(TERR,
+ "than the FW length %d (0x%08x)",
+ (binary_params.fw_len - 1),
+ (binary_params.fw_len - 1));
+ return FALSE;
+ }
+ }
+
+ /* Check CRC start and end addresses. */
+ if (binary_params.fw_err_detec_s_addr >
+ binary_params.fw_err_detec_e_addr) {
+ my_printf(TERR,
+ "\nCRC start address (0x%08x) should be less or ",
+ binary_params.fw_err_detec_s_addr);
+ my_printf(TERR,
+ "equal to CRC end address (0x%08x)\nPlease check ",
+ binary_params.fw_err_detec_e_addr);
+ my_printf(TERR,
+ "CRC start address and CRC size arguments.");
+ return FALSE;
+ }
+
+ /* CRC start addr should be between the FW load address and RAM size */
+ if (binary_params.fw_err_detec_s_addr >
+ binary_params.fw_len) {
+ my_printf(TERR, "\nCRC start address (0x%08x) should ",
+ binary_params.fw_err_detec_s_addr);
+ my_printf(TERR, "be FW length (0x%08x).",
+ binary_params.fw_len);
+ return FALSE;
+ }
+
+ /* Write the CRC start address */
+ if (!write_to_file(binary_params.fw_err_detec_s_addr,
+ HDR_FW_ERR_DETECT_START_ADDR_OFFSET,
+ 4,
+ "HDR - FW CRC Start "))
+ return FALSE;
+
+ /* CRC end addr should be between the CRC start address and RAM size */
+ if ((binary_params.fw_err_detec_e_addr <
+ binary_params.fw_err_detec_s_addr) ||
+ (binary_params.fw_err_detec_e_addr >
+ binary_params.fw_len)) {
+ my_printf(TERR,
+ "\nCRC end address (0x%08x) should be between the ",
+ binary_params.fw_err_detec_e_addr);
+ my_printf(TERR,
+ "CRC start address (0x%08x) and FW length (0x%08x).",
+ binary_params.fw_err_detec_s_addr,
+ binary_params.fw_len);
+ return FALSE;
+ }
+
+ /* Write the CRC end address */
+ if (!write_to_file(binary_params.fw_err_detec_e_addr,
+ HDR_FW_ERR_DETECT_END_ADDR_OFFSET,
+ 4,
+ "HDR - FW CRC End "))
+ return FALSE;
+
+ /* Let the FW length to be aligned to 16 */
+ tmp_param = binary_params.fw_len % 16;
+ if (tmp_param)
+ binary_params.fw_len += (16 - tmp_param);
+
+ /* FW load address + FW length should be less than the RAM size. */
+ if ((binary_params.fw_load_addr +
+ binary_params.fw_len) >
+ (g_ram_start_address + g_ram_size)) {
+ my_printf(TERR,
+ "\nFW load address + FW length should (0x%08x) be ",
+ (binary_params.fw_load_addr + binary_params.fw_len));
+ my_printf(TERR,
+ "less than the RAM size (0x%08x).",
+ (g_ram_start_address + g_ram_size));
+ return FALSE;
+ }
+
+ /* Write the FW length */
+ if (!write_to_file(binary_params.fw_len,
+ HDR_FW_LENGTH_OFFSET,
+ 4,
+ "HDR - FW Length "))
+ return FALSE;
+
+ /* Write the SPI flash MAX clock. */
+ switch (binary_params.flash_size) {
+ case FLASH_SIZE_1_MBYTES_VAL:
+ tmp_param = FLASH_SIZE_1_MBYTES;
+ break;
+ case FLASH_SIZE_2_MBYTES_VAL:
+ tmp_param = FLASH_SIZE_2_MBYTES;
+ break;
+ case FLASH_SIZE_4_MBYTES_VAL:
+ tmp_param = FLASH_SIZE_4_MBYTES;
+ break;
+ case FLASH_SIZE_8_MBYTES_VAL:
+ tmp_param = FLASH_SIZE_8_MBYTES;
+ break;
+ case FLASH_SIZE_16_MBYTES_VAL:
+ tmp_param = FLASH_SIZE_16_MBYTES;
+ break;
+ default:
+ my_printf(TERR, "\n\nInvalid Flash size (%d MBytes) -",
+ binary_params.flash_size);
+ my_printf(TERR, " it should be 1, 2, 4, 8 or 16 MBytes\n");
+ return FALSE;
+ break;
+ }
+ if (!write_to_file(tmp_param,
+ HDR_FLASH_SIZE_OFFSET,
+ 1,
+ "HDR - Flash size "))
+
+ return FALSE;
+
+ /* Write the reserved bytes. */
+ if (!write_to_file(PAD_VALUE, HDR_RESERVED, 26,
+ "HDR - Reserved (26 bytes) "))
+ return FALSE;
+
+
+ /* Refresh the FW header bin file in order to calculate CRC */
+ if (g_hfd_pointer) {
+ fclose(g_hfd_pointer);
+ g_hfd_pointer = fopen(g_hdr_input_name, "r+b");
+ if (g_hfd_pointer == NULL) {
+ my_printf(TERR,
+ "\n\nCannot open %s\n\n",
+ input_file_name);
+ return FALSE;
+ }
+ }
+
+ /* Calculate the FW header CRC */
+ if ((binary_params.bin_params & BIN_FW_HDR_CRC_DISABLE) == 0) {
+ /* Calculate ... */
+ g_calc_type = CALC_TYPE_CRC;
+ if (!calc_header_crc_bin(&binary_params.hdr_crc))
+ return FALSE;
+
+ g_calc_type = CALC_TYPE_NONE;
+ } else
+ binary_params.hdr_crc = 0;
+
+ /* Write FW header CRC to header file */
+ if (!write_to_file(binary_params.hdr_crc,
+ HDR_FW_HEADER_SIG_OFFSET,
+ 4,
+ "HDR - Header CRC "))
+ return FALSE;
+
+ /* Calculate the FW CRC */
+ if ((binary_params.bin_params & BIN_FW_CRC_DISABLE) == 0) {
+ /* Calculate ... */
+ g_calc_type = CALC_TYPE_CRC;
+ if (!calc_firmware_csum_bin(&binary_params.fw_crc,
+ (bin_fw_offset +
+ binary_params.fw_err_detec_s_addr),
+ (binary_params.fw_err_detec_e_addr -
+ binary_params.fw_err_detec_s_addr+1)))
+ return FALSE;
+
+ g_calc_type = CALC_TYPE_NONE;
+ } else
+ binary_params.fw_crc = 0;
+
+ /* Write the FW CRC into file header file */
+ if (!write_to_file(binary_params.fw_crc,
+ HDR_FW_IMAGE_SIG_OFFSET,
+ 4,
+ "HDR - FW CRC "))
+ return FALSE;
+
+ /* Close if needed... */
+ if (input_file_pointer) {
+ fclose(input_file_pointer);
+ input_file_pointer = NULL;
+ }
+
+ if (g_hfd_pointer) {
+ fclose(g_hfd_pointer);
+ g_hfd_pointer = NULL;
+ }
+
+ /* Create empty output file. */
+ output_file_pointer = fopen(output_file_name, "wb");
+ if (output_file_pointer)
+ fclose(output_file_pointer);
+
+ if ((binary_params.bin_params & BIN_FW_HDR_OFFSET) != 0) {
+ copy_file_to_file(output_file_name,
+ input_file_name,
+ 0,
+ SEEK_SET);
+ copy_file_to_file(output_file_name,
+ g_hdr_input_name,
+ binary_params.fw_hdr_offset,
+ SEEK_SET);
+ } else {
+ copy_file_to_file(output_file_name,
+ g_hdr_input_name,
+ 0,
+ SEEK_END);
+ copy_file_to_file(output_file_name,
+ input_file_name,
+ 0,
+ SEEK_END);
+ }
+
+ my_printf(TINF, "\n\n");
+
+ return TRUE;
+}
+
+/*******************************************************************
+ * Function: calc_header_crc_bin
+ * Parameters: unsigned short header checksum (O)
+ * unsigned int header offset from first byte in
+ * the binary (I)
+ * Return:
+ * Description: Go thru bin file and calculate checksum
+ *******************************************************************
+ */
+int calc_header_crc_bin(unsigned int *p_cksum)
+{
+ int i;
+ unsigned int calc_header_checksum_crc = 0;
+ unsigned char g_header_array[HEADER_SIZE];
+ int line_print_size = 32;
+
+ init_calculation(&calc_header_checksum_crc);
+
+ /* Go thru the BIN File and calculate the Checksum */
+ fseek(g_hfd_pointer, 0x00000000, SEEK_SET);
+ if (fread(g_header_array,
+ 1,
+ HEADER_SIZE,
+ g_hfd_pointer) == 0)
+ return 0;
+
+ for (i = 0; i < (HEADER_SIZE - HEADER_CRC_FIELDS_SIZE); i++) {
+
+ /*
+ * I had once the Verbose check inside the my_printf, but
+ * it made ECST run sloooowwwwwly....
+ */
+ if (g_verbose == SUPER_VERBOSE) {
+ if (i%line_print_size == 0)
+ my_printf(TDBG,
+ "\n[%.4x]: ",
+ g_header_array + i);
+
+ my_printf(TDBG, "%.2x ", g_header_array[i]);
+ }
+
+ update_calculation(&calc_header_checksum_crc,
+ g_header_array[i]);
+
+ if (g_verbose == SUPER_VERBOSE) {
+ if ((i + 1) % line_print_size == 0)
+ my_printf(TDBG,
+ "FW Header ChecksumCRC = %.8x",
+ calc_header_checksum_crc);
+
+ }
+ }
+
+ finalize_calculation(&calc_header_checksum_crc);
+ *p_cksum = calc_header_checksum_crc;
+
+ return TRUE;
+}
+
+/*
+ *******************************************************************
+ * Function: calc_firmware_csum_bin
+ * Parameters: unsigned int fwStart (I)
+ * unsigned int firmware size in words (I)
+ * unsigned int - firmware checksum (O)
+ * Return:
+ * Description: TBD
+ *******************************************************************
+ */
+int calc_firmware_csum_bin(unsigned int *p_cksum,
+ unsigned int fw_offset,
+ unsigned int fw_length)
+{
+
+ unsigned int i;
+ unsigned int calc_read_bytes;
+ unsigned int calc_num_of_bytes_to_read;
+ unsigned int calc_curr_position;
+ unsigned int calc_fw_checksum_crc = 0;
+ unsigned char g_fw_array[BUFF_SIZE];
+ int line_print_size = 32;
+
+
+ calc_num_of_bytes_to_read = fw_length;
+ calc_curr_position = fw_offset;
+
+ if (g_verbose == REGULAR_VERBOSE) {
+ my_printf(TINF,
+ "\nFW Error Detect Start Dddress: 0x%08x",
+ calc_curr_position);
+ my_printf(TINF,
+ "\nFW Error Detect End Dddress: 0x%08x",
+ calc_curr_position + calc_num_of_bytes_to_read - 1);
+ my_printf(TINF,
+ "\nFW Error Detect Size: %d (0x%X)",
+ calc_num_of_bytes_to_read,
+ calc_num_of_bytes_to_read);
+ }
+
+ init_calculation(&calc_fw_checksum_crc);
+
+ while (calc_num_of_bytes_to_read > 0) {
+ if (calc_num_of_bytes_to_read > BUFF_SIZE)
+ calc_read_bytes = BUFF_SIZE;
+ else
+ calc_read_bytes = calc_num_of_bytes_to_read;
+
+ fseek(input_file_pointer, 0L, SEEK_SET);
+ fseek(input_file_pointer, calc_curr_position, SEEK_SET);
+ if (fread(g_fw_array,
+ 1,
+ calc_read_bytes,
+ input_file_pointer) == 0)
+ return 0;
+
+ for (i = 0; i < calc_read_bytes; i++) {
+ /*
+ * I had once the Verbose check inside the my_printf,
+ * but it made ECST run sloooowwwwwly....
+ */
+ if (g_verbose == SUPER_VERBOSE) {
+ if (i%line_print_size == 0)
+ my_printf(TDBG,
+ "\n[%.4x]: ",
+ calc_curr_position + i);
+
+ my_printf(TDBG, "%.2x ", g_fw_array[i]);
+ }
+
+ update_calculation(&calc_fw_checksum_crc,
+ g_fw_array[i]);
+
+ if (g_verbose == SUPER_VERBOSE) {
+ if ((i + 1) % line_print_size == 0)
+ my_printf(TDBG,
+ "FW Checksum= %.8x",
+ calc_fw_checksum_crc);
+ }
+ }
+ calc_num_of_bytes_to_read -= calc_read_bytes;
+ calc_curr_position += calc_read_bytes;
+ } /* end of while(calc_num_of_bytes_to_read > 0) */
+
+ finalize_calculation(&calc_fw_checksum_crc);
+ *p_cksum = calc_fw_checksum_crc;
+
+ return TRUE;
+}
+
+/*
+ ***************************************************************************
+ * "bh" mode Handler
+ ***************************************************************************
+ */
+
+/*
+ *******************************************************************
+ * Function: main_hdr
+ * Parameters: TBD
+ * Return: True for success
+ * Description:
+ *******************************************************************
+ */
+int main_hdr(void)
+{
+ int result = 0;
+ char tmp_file_name[NAME_SIZE];
+ unsigned int tmp_long_val;
+ unsigned int bin_file_size_bytes;
+
+ if (is_ptr_merge) {
+ if (strlen(input_file_name) == 0) {
+ my_printf(TERR, "\n\nNo input BIN file selected for");
+ my_printf(TERR, " BootLoader header file.\n\n");
+ return FALSE;
+ }
+
+ if (strlen(output_file_name) == 0)
+ strncpy(tmp_file_name,
+ input_file_name,
+ sizeof(tmp_file_name));
+ else {
+ copy_file_to_file(output_file_name,
+ input_file_name,
+ 0,
+ SEEK_END);
+ strncpy(tmp_file_name,
+ output_file_name,
+ sizeof(tmp_file_name));
+ }
+
+ /* Open Header file */
+ g_hdr_pointer = fopen(tmp_file_name, "r+b");
+ if (g_hdr_pointer == NULL) {
+ my_printf(TERR,
+ "\n\nCannot open %s file.\n\n",
+ tmp_file_name);
+ return FALSE;
+ }
+
+ bin_file_size_bytes = get_file_length(g_hdr_pointer);
+
+ /* Offset should be less than file size. */
+ if (fw_offset > bin_file_size_bytes) {
+ my_printf(TERR,
+ "\n\nFW offset 0x%08x should be less than ",
+ fw_offset);
+ my_printf(TERR,
+ "file size 0x%x (%d).\n\n",
+ bin_file_size_bytes, bin_file_size_bytes);
+ return FALSE;
+ }
+
+ /* FW table should be less than file size. */
+ if (ptr_fw_addr > bin_file_size_bytes) {
+ my_printf(TERR, "\n\nFW table 0x%08x should be less ",
+ ptr_fw_addr);
+ my_printf(TERR, "than file size 0x%x (%d).\n\n",
+ bin_file_size_bytes, bin_file_size_bytes);
+ return FALSE;
+ }
+
+ fseek(g_hdr_pointer, 0L, SEEK_SET);
+ fseek(g_hdr_pointer, fw_offset, SEEK_SET);
+
+ tmp_long_val = HDR_PTR_SIGNATURE;
+ result = (int)(fwrite(&tmp_long_val,
+ 4,
+ 1,
+ g_hdr_pointer));
+ result |= (int)(fwrite(&ptr_fw_addr,
+ 4,
+ 1,
+ g_hdr_pointer));
+
+ if (result) {
+ my_printf(TINF,
+ "\nBootLoader Header file: %s\n",
+ tmp_file_name);
+ my_printf(TINF,
+ " Offset: 0x%08X, Signature: 0x%08X,",
+ fw_offset, HDR_PTR_SIGNATURE);
+ my_printf(TINF,
+ " Pointer: 0x%08X\n",
+ ptr_fw_addr);
+ } else {
+ my_printf(TERR,
+ "\n\nCouldn't write signature (%x) and ",
+ tmp_long_val);
+ my_printf(TERR,
+ "pointer to BootLoader header file (%s)\n\n",
+ ptr_fw_addr, tmp_file_name);
+ return FALSE;
+ }
+
+ } else {
+
+ if (strlen(output_file_name) == 0) {
+ my_printf(TERR, "\n\nNo output file selected ");
+ my_printf(TERR, "for BootLoader header file.\n\n");
+ return FALSE;
+ }
+
+ /* Open Output file */
+ g_hdr_pointer = fopen(output_file_name, "w+b");
+ if (g_hdr_pointer == NULL) {
+ my_printf(TERR,
+ "\n\nCannot open %s file.\n\n",
+ output_file_name);
+ return FALSE;
+ }
+
+ fseek(g_hdr_pointer, 0L, SEEK_SET);
+
+ tmp_long_val = HDR_PTR_SIGNATURE;
+ result = (int)(fwrite(&tmp_long_val,
+ 4,
+ 1,
+ g_hdr_pointer));
+ result |= (int)(fwrite(&ptr_fw_addr,
+ 4,
+ 1,
+ g_hdr_pointer));
+
+ if (result) {
+ my_printf(TINF,
+ "\nBootLoader Header file: %s\n",
+ output_file_name);
+ my_printf(TINF,
+ " Signature: 0x%08X, Pointer: 0x%08X\n",
+ HDR_PTR_SIGNATURE,
+ ptr_fw_addr);
+ } else {
+ my_printf(TERR,
+ "\n\nCouldn't write signature (%x) and ",
+ tmp_long_val);
+ my_printf(TERR,
+ "pointer to BootLoader header file (%s)\n\n",
+ output_file_name);
+ return FALSE;
+ }
+
+ }
+
+ /* Close if needed... */
+ if (g_hdr_pointer) {
+ fclose(g_hdr_pointer);
+ g_hdr_pointer = NULL;
+ }
+
+ return TRUE;
+}
+
+/*
+ ***************************************************************************
+ * "api" mode Handler
+ ***************************************************************************
+ */
+
+/*
+ *******************************************************************
+ * Function: main_api
+ * Parameters: TBD
+ * Return: True for success
+ * Description:
+ * TBD
+ *******************************************************************
+ */
+int main_api(void)
+{
+
+ char dir_name[NAME_SIZE];
+ char *file_name_ptr = NULL;
+ char *tmp_str_ptr;
+ int dir_name_len;
+ char tmp_file_name[NAME_SIZE];
+ int result = 0;
+ unsigned int crc_checksum;
+
+ api_file_size_bytes = 0;
+
+ /* If API input file was not declared, then print error message. */
+ if (strlen(input_file_name) == 0) {
+ my_printf(TERR,
+ "\n\nNeed to define API input file, using -i flag\n\n");
+ return FALSE;
+
+ }
+
+ if (strlen(output_file_name) == 0) {
+ /* Get the input directory and input file name. */
+ file_name_ptr = input_file_name;
+ for (tmp_str_ptr = input_file_name; tmp_str_ptr != NULL;) {
+ tmp_str_ptr = strstr(tmp_str_ptr, DIR_DELIMITER_STR);
+ if (tmp_str_ptr != NULL) {
+ file_name_ptr =
+ tmp_str_ptr + strlen(DIR_DELIMITER_STR);
+ tmp_str_ptr = file_name_ptr;
+ }
+
+ }
+
+ dir_name_len = strlen(input_file_name) - strlen(file_name_ptr);
+ strncpy(dir_name, input_file_name, dir_name_len);
+ dir_name[dir_name_len] = '\0';
+
+ sprintf(tmp_file_name, "%sapi_%s", dir_name, file_name_ptr);
+
+ } else
+ strncpy(tmp_file_name, output_file_name, sizeof(tmp_file_name));
+
+ /* Make sure that new empty file is created. */
+ api_file_pointer = fopen(tmp_file_name, "w");
+ if (api_file_pointer == NULL) {
+ my_printf(TERR, "\n\nCannot open %s\n\n", tmp_file_name);
+ return FALSE;
+ }
+ fclose(api_file_pointer);
+
+ copy_file_to_file(tmp_file_name, input_file_name, 0, SEEK_END);
+
+ /* Open API input file */
+ api_file_pointer = fopen(tmp_file_name, "r+b");
+ if (api_file_pointer == NULL) {
+ my_printf(TERR, "\n\nCannot open %s\n\n", tmp_file_name);
+ return FALSE;
+ }
+
+ /*
+ * Check Binary file size, this file contain the image itself,
+ * without any header.
+ */
+ api_file_size_bytes = get_file_length(api_file_pointer);
+ my_printf(TINF,
+ "\nAPI file: %s, size: %d bytes (0x%x)\n",
+ tmp_file_name,
+ api_file_size_bytes,
+ api_file_size_bytes);
+
+
+ crc_checksum = calc_api_csum_bin();
+
+ fseek(api_file_pointer, 0L, SEEK_SET);
+ fseek(api_file_pointer, api_file_size_bytes, SEEK_SET);
+
+ result = (int)(fwrite(&crc_checksum,
+ 4,
+ 1,
+ api_file_pointer));
+
+ if (result)
+ my_printf(TINF,
+ "\nIn API BIN file - Offset 0x%08X - value 0x%08X",
+ api_file_size_bytes,
+ crc_checksum);
+ else {
+ my_printf(TERR,
+ "\n\nCouldn't write %x to API BIN file at %08x\n\n",
+ crc_checksum, api_file_size_bytes);
+ return FALSE;
+ }
+
+ /* Close if needed... */
+ if (api_file_pointer) {
+ fclose(api_file_pointer);
+ api_file_pointer = NULL;
+ }
+
+ return TRUE;
+}
+
+
+
+/*
+ *******************************************************************
+ * Function: calc_api_csum_bin
+ * Parameters:
+ *
+ * Return: Return the CRC \ checksum, or "0" in case of fail.
+ * Description: TBD
+ *******************************************************************
+*/
+unsigned int calc_api_csum_bin(void)
+{
+
+ unsigned int i;
+ unsigned int calc_read_bytes;
+ unsigned int calc_num_of_bytes_to_read;
+ unsigned int calc_curr_position;
+ unsigned int calc_fw_checksum_crc = 0;
+ unsigned char g_fw_array[BUFF_SIZE];
+ int line_print_size = 32;
+
+
+ calc_num_of_bytes_to_read = api_file_size_bytes;
+ calc_curr_position = 0;
+
+ if (g_verbose == SUPER_VERBOSE) {
+ my_printf(TDBG,
+ "\nAPI CRC \\ Checksum First Byte Address: 0x%08x",
+ calc_curr_position);
+ my_printf(TDBG,
+ "\nAPI CRC \\ Checksum Size: %d (0x%X)",
+ calc_num_of_bytes_to_read,
+ calc_num_of_bytes_to_read);
+ }
+
+ init_calculation(&calc_fw_checksum_crc);
+
+ while (calc_num_of_bytes_to_read > 0) {
+ if (calc_num_of_bytes_to_read > BUFF_SIZE)
+ calc_read_bytes = BUFF_SIZE;
+ else
+ calc_read_bytes = calc_num_of_bytes_to_read;
+
+ fseek(api_file_pointer, 0L, SEEK_SET);
+ fseek(api_file_pointer, calc_curr_position, SEEK_SET);
+ if (fread(g_fw_array,
+ 1,
+ calc_read_bytes,
+ api_file_pointer) == 0)
+ return 0;
+
+ for (i = 0; i < calc_read_bytes; i++) {
+ /*
+ * I had once the Verbose check inside the my_printf,
+ * but it made ecst run sloooowwwwwly....
+ */
+ if (g_verbose == SUPER_VERBOSE) {
+ if (i%line_print_size == 0)
+ my_printf(TDBG,
+ "\n[%.4x]: ",
+ calc_curr_position + i);
+
+ my_printf(TDBG, "%.2x ", g_fw_array[i]);
+ }
+
+ update_calculation(&calc_fw_checksum_crc,
+ g_fw_array[i]);
+
+ if (g_verbose == SUPER_VERBOSE) {
+ if ((i + 1) % line_print_size == 0)
+ my_printf(TDBG,
+ "FW Checksum= %.8x",
+ calc_fw_checksum_crc);
+ }
+ }
+ calc_num_of_bytes_to_read -= calc_read_bytes;
+ calc_curr_position += calc_read_bytes;
+ } /* end of while(calc_num_of_bytes_to_read > 0) */
+
+ finalize_calculation(&calc_fw_checksum_crc);
+
+ return calc_fw_checksum_crc;
+
+}
+
+
+/*
+ **************************************************************************
+ * CRC Handler
+ **************************************************************************
+*/
+
+/*
+ *******************************************************************
+ *
+ * #define P_xxxx
+ *
+ * The CRC's are computed using polynomials. The coefficients
+ * for the algorithms are defined by the following constants.
+ *
+ *******************************************************************
+ */
+
+#define P_32 0xEDB88320L
+
+/*
+ *******************************************************************
+ *
+ * static int crc_tab...init
+ * static unsigned ... crc_tab...[]
+ *
+ * The algorithms use tables with pre-calculated values. This
+ * speeds up the calculation dramatically. The first time the
+ * CRC function is called, the table for that specific calcu-
+ * lation is set up. The ...init variables are used to deter-
+ * mine if the initialization has taken place. The calculated
+ * values are stored in the crc_tab... arrays.
+ *
+ * The variables are declared static. This makes them invisible
+ * for other modules of the program.
+ *
+ *******************************************************************
+ */
+static int crc_tab32_init = FALSE;
+static unsigned int crc_tab32[256];
+
+/*
+ ********************************************************************
+ *
+ * static void init_crc...tab();
+ *
+ * Three local functions are used to initialize the tables
+ * with values for the algorithm.
+ *
+ *******************************************************************
+ */
+
+static void init_crc32_tab(void);
+
+/*
+ *******************************************************************
+ *
+ * unsigned int initialize_crc_32( void );
+ *
+ * The function update_crc_32 calculates a new CRC-32 value
+ * based on the previous value of the CRC and the next byte
+ * of the data to be checked.
+ *
+ *******************************************************************
+ */
+
+unsigned int initialize_crc_32(void)
+{
+ return 0xffffffffL;
+} /* initialize_crc_32 */
+
+
+/*
+ *******************************************************************
+ *
+ * unsigned int update_crc_32( unsigned int crc, char c );
+ *
+ * The function update_crc_32 calculates a new CRC-32 value
+ * based on the previous value of the CRC and the next byte
+ * of the data to be checked.
+ *
+ *******************************************************************
+ */
+
+unsigned int update_crc_32(unsigned int crc, char c)
+{
+
+ unsigned int tmp, long_c;
+
+ long_c = 0x000000ffL & (unsigned int)c;
+
+ if (!crc_tab32_init)
+ init_crc32_tab();
+
+ tmp = crc ^ long_c;
+ crc = (crc >> 8) ^ crc_tab32[tmp & 0xff];
+
+ return crc;
+
+} /* update_crc_32 */
+
+
+
+/*
+ *******************************************************************
+ *
+ * static void init_crc32_tab( void );
+ *
+ * The function init_crc32_tab() is used to fill the array
+ * for calculation of the CRC-32 with values.
+ *
+ *******************************************************************
+ */
+static void init_crc32_tab(void)
+{
+
+ int i, j;
+ unsigned int crc;
+
+ for (i = 0; i < 256; i++) {
+
+ crc = (unsigned int)i;
+
+ for (j = 0; j < 8; j++) {
+
+ if (crc & 0x00000001L)
+ crc = (crc >> 1) ^ P_32;
+ else
+ crc = crc >> 1;
+ }
+
+ crc_tab32[i] = crc;
+ }
+
+ crc_tab32_init = TRUE;
+
+} /* init_crc32_tab */
+
+/*
+ *******************************************************************
+ *
+ * unsigned int finalize_crc_32( unsigned int crc );
+ *
+ * The function finalize_crc_32 finalizes a CRC-32 calculation
+ * by performing a bit convolution (bit 0 is bit 31, etc').
+ *
+ *******************************************************************
+ */
+
+unsigned int finalize_crc_32(unsigned int crc)
+{
+
+ int i;
+ unsigned int result = 0;
+
+ for (i = 0; i < NUM_OF_BYTES; i++)
+ SET_VAR_BIT(result, NUM_OF_BYTES - (i+1), READ_VAR_BIT(crc, i));
+
+ return result;
+
+} /* finalize_crc_32 */
+
diff --git a/util/ecst.h b/util/ecst.h
new file mode 100755
index 0000000000..d61f95be3b
--- /dev/null
+++ b/util/ecst.h
@@ -0,0 +1,258 @@
+/*
+ * Copyright (c) 2015 The Chromium OS Authors. All rights reserved.
+ * Use of this source code is governed by a BSD-style license that can be
+ * found in the LICENSE file.
+ */
+
+#ifndef ECST_H
+#define ECST_H
+
+/*---------------------------------------------------------------------------
+ Includes
+ --------------------------------------------------------------------------*/
+
+#include <stdlib.h>
+#include <string.h>
+#include <stdio.h>
+#include <curses.h>
+
+
+/*---------------------------------------------------------------------------
+ Defines
+ --------------------------------------------------------------------------*/
+
+/* For the beauty */
+#define TRUE 1
+#define FALSE 0
+
+/* CHANGEME when the version is updated */
+#define T_VER 1
+#define T_REV_MAJOR 0
+#define T_REV_MINOR 1
+
+/* Header starts by default at 0x20000 */
+#define FIRMWARE_OFFSET_FROM_HEADER 0x40
+
+#define ARM_FW_ENTRY_POINT_OFFSET 0x04
+
+/* Some useful offsets inside the header */
+#define HDR_ANCHOR_OFFSET 0
+#define HDR_EXTENDED_ANCHOR_OFFSET 4
+#define HDR_SPI_MAX_CLK_OFFSET 6
+#define HDR_SPI_READ_MODE_OFFSET 7
+#define HDR_ERR_DETECTION_CONF_OFFSET 8
+#define HDR_FW_LOAD_START_ADDR_OFFSET 9
+#define HDR_FW_ENTRY_POINT_OFFSET 13
+#define HDR_FW_ERR_DETECT_START_ADDR_OFFSET 17
+#define HDR_FW_ERR_DETECT_END_ADDR_OFFSET 21
+#define HDR_FW_LENGTH_OFFSET 25
+#define HDR_FLASH_SIZE_OFFSET 29
+#define HDR_RESERVED 30
+#define HDR_FW_HEADER_SIG_OFFSET 56
+#define HDR_FW_IMAGE_SIG_OFFSET 60
+
+
+#define FIRMW_CKSM_OFFSET 0x3C
+
+/* Header field known values */
+#define FW_HDR_ANCHOR 0x2A3B4D5E
+#define FW_HDR_EXT_ANCHOR_ENABLE 0xAB1E
+#define FW_HDR_EXT_ANCHOR_DISABLE 0x54E1
+#define FW_CRC_DISABLE 0x00
+#define FW_CRC_ENABLE 0x02
+#define HEADER_CRC_FIELDS_SIZE 8
+
+#define HDR_PTR_SIGNATURE 0x55AA650E
+
+#define CKSMCRC_INV_BIT_OFFSET 0x1
+
+/* Some common Sizes */
+#define STR_SIZE 200
+#define ARG_SIZE 100
+#define NAME_SIZE 160
+#define BUFF_SIZE 0x400
+#define HEADER_SIZE 64
+#define TMP_STR_SIZE 20
+#define PAD_VALUE 0x00
+
+
+#define MAX_ARGS 100
+
+/* Text Colors */
+#define TDBG 0x02 /* Dark Green */
+#define TPAS 0x0A /* light green */
+#define TINF 0x0B /* light turquise */
+#define TERR 0x0C /* light red */
+#define TUSG 0x0E /* light yellow */
+
+/* Indicates bin Command line parameters */
+#define BIN_FW_HDR_CRC_DISABLE 0x0001
+#define BIN_FW_CRC_DISABLE 0x0002
+#define BIN_FW_START 0x0004
+#define BIN_FW_SIZE 0x0008
+#define BIN_CK_FIRMWARE 0x0010
+#define BIN_FW_CKS_START 0x0020
+#define BIN_FW_CKS_SIZE 0x0040
+#define BIN_FW_CHANGE_SIG 0x0080
+#define BIN_FW_SPI_MAX_CLK 0x0100
+#define BIN_FW_LOAD_START_ADDR 0x0200
+#define BIN_FW_ENTRY_POINT 0x0400
+#define BIN_FW_LENGTH 0x0800
+#define BIN_FW_HDR_OFFSET 0x1000
+#define BIN_FW_USER_ARM_RESET 0x2000
+
+#define ECRP_OFFSET 0x01
+#define ECRP_INPUT_FILE 0x02
+#define ECRP_OUTPUT_FILE 0x04
+
+#define DIR_DELIMITER_STR "/"
+
+#define SPI_MAX_CLOCK_20_MHZ_VAL 20
+#define SPI_MAX_CLOCK_25_MHZ_VAL 25
+#define SPI_MAX_CLOCK_33_MHZ_VAL 33
+#define SPI_MAX_CLOCK_40_MHZ_VAL 40
+#define SPI_MAX_CLOCK_50_MHZ_VAL 50
+
+#define SPI_MAX_CLOCK_20_MHZ 0x00
+#define SPI_MAX_CLOCK_25_MHZ 0x01
+#define SPI_MAX_CLOCK_33_MHZ 0x02
+#define SPI_MAX_CLOCK_40_MHZ 0x03
+#define SPI_MAX_CLOCK_50_MHZ 0x04
+
+
+#define SPI_NORMAL_MODE_VAL "normal"
+#define SPI_SINGLE_MODE_VAL "fast"
+#define SPI_DUAL_MODE_VAL "dual"
+#define SPI_QUAD_MODE_VAL "quad"
+
+#define SPI_NORMAL_MODE 0x00
+#define SPI_SINGLE_MODE 0x01
+#define SPI_DUAL_MODE 0x03
+#define SPI_QUAD_MODE 0x04
+
+#define FLASH_SIZE_1_MBYTES_VAL 1
+#define FLASH_SIZE_2_MBYTES_VAL 2
+#define FLASH_SIZE_4_MBYTES_VAL 4
+#define FLASH_SIZE_8_MBYTES_VAL 8
+#define FLASH_SIZE_16_MBYTES_VAL 16
+
+#define FLASH_SIZE_1_MBYTES 0x01
+#define FLASH_SIZE_2_MBYTES 0x03
+#define FLASH_SIZE_4_MBYTES 0x07
+#define FLASH_SIZE_8_MBYTES 0x0F
+#define FLASH_SIZE_16_MBYTES 0x1F
+
+/* Header fields deafult values. */
+#define SPI_MAX_CLOCK_DEAFULT SPI_MAX_CLOCK_20_MHZ_VAL
+#define SPI_READ_MODE_DEAFULT SPI_NORMAL_MODE
+#define FLASH_SIZE_DEAFULT FLASH_SIZE_16_MBYTES_VAL
+#define FW_CRC_START_ADDR 0x00000000
+
+#define ADDR_16_BYTES_ALIGNED_MASK 0x0000000F
+#define ADDR_4_BYTES_ALIGNED_MASK 0x00000003
+
+#define MAX_FLASH_SIZE 0x03ffffff
+
+/* Chips: convert from name to index. */
+#define NPCX5M5G 0
+#define NPCX5M6G 1
+
+#define NPCX5M5G_RAM_ADDR 0x100A8000
+#define NPCX5M5G_RAM_SIZE 0x20000
+#define NPCX5M6G_RAM_ADDR 0x10088000
+#define NPCX5M6G_RAM_SIZE 0x40000
+
+/*---------------------------------------------------------------------------
+ Typedefs
+ --------------------------------------------------------------------------*/
+
+/* Parameters for Binary manipulation */
+struct tbinparams {
+ unsigned int anchor;
+ unsigned short ext_anchor;
+ unsigned char spi_max_clk;
+ unsigned char spi_read_mode;
+ unsigned char err_detec_cnf;
+ unsigned int fw_load_addr;
+ unsigned int fw_ep;
+ unsigned int fw_err_detec_s_addr;
+ unsigned int fw_err_detec_e_addr;
+ unsigned int fw_len;
+ unsigned int flash_size;
+ unsigned int hdr_crc;
+ unsigned int fw_crc;
+ unsigned int fw_hdr_offset;
+ unsigned int bin_params;
+} bin_params_struct;
+
+enum verbose_level {
+ NO_VERBOSE = 0,
+ REGULAR_VERBOSE,
+ SUPER_VERBOSE
+};
+
+enum calc_type {
+ CALC_TYPE_NONE = 0,
+ CALC_TYPE_CHECKSUM ,
+ CALC_TYPE_CRC
+};
+
+struct chip_info {
+ unsigned int ram_addr;
+ unsigned int ram_size;
+} chip_info_struct;
+
+/*------------------------------------------------------------------------*/
+/* CRC Variable bit operation macros */
+/*------------------------------------------------------------------------*/
+#define NUM_OF_BYTES 32
+#define READ_VAR_BIT(var, nb) (((var) >> (nb)) & 0x1)
+#define SET_VAR_BIT(var, nb, val) ((var) |= ((val)<<(nb)))
+
+/*---------------------------------------------------------------------------
+ Functions Declaration
+ --------------------------------------------------------------------------*/
+
+/* main manipulation */
+int main_bin(struct tbinparams binary_parameters);
+int main_api(void);
+int main_hdr(void);
+
+/* General Checksum\CRC calculation */
+void init_calculation(unsigned int *check_sum_crc);
+void finalize_calculation(unsigned int *check_sum_crc);
+void update_calculation_information(unsigned char crc_con_dat);
+
+
+/* Checksum calculation etc. (BIN Specific) */
+int calc_header_crc_bin(unsigned int *pointer_header_checksum);
+int calc_firmware_csum_bin(unsigned int *p_cksum,
+ unsigned int fw_offset,
+ unsigned int fw_length);
+
+/* Checksum calculation etc. (ERP Specific) */
+int calc_erp_csum_bin(unsigned short *region_pointer_header_checksum,
+ unsigned int region_pointer_ofs);
+
+/* No words - General */
+void exit_with_usage(void);
+int copy_file_to_file(char *dst_file_name,
+ char *src_file_name,
+ int offset,
+ int origin);
+int write_to_file(unsigned int write_value,
+ unsigned int offset,
+ unsigned char num_of_bytes,
+ char *print_string);
+int read_from_file(unsigned int offset,
+ unsigned char size_to_read,
+ unsigned int *read_value,
+ char *print_string);
+
+/* Nice Particular Printf - General */
+void my_printf(int error_level, char *fmt, ...);
+
+int str_cmp_no_case(const char *s1, const char *s2);
+int get_file_length(FILE *stream);
+
+#endif /* ECST_H */
diff --git a/util/openocd/npcx.cfg b/util/openocd/npcx.cfg
index d42580a907..73b1957f3c 100644
--- a/util/openocd/npcx.cfg
+++ b/util/openocd/npcx.cfg
@@ -46,9 +46,7 @@ target create $_TARGETNAME cortex_m -endian $_ENDIAN -chain-position \
adapter_khz 100
adapter_nsrst_delay 100
-if {[using_jtag]} {
- jtag_ntrst_delay 100
-}
+jtag_ntrst_delay 100
# use srst to perform a system reset
cortex_m reset_config srst
@@ -58,6 +56,6 @@ reset_config trst_and_srst
$_TARGETNAME configure -event reset-start {
echo "NPCX5M5G Reset..."
- adapter_khz 1000
halt
+ adapter_khz 1000
}
diff --git a/util/openocd/npcx_cmds.tcl b/util/openocd/npcx_cmds.tcl
index a32afccf03..51db7f635a 100644
--- a/util/openocd/npcx_cmds.tcl
+++ b/util/openocd/npcx_cmds.tcl
@@ -10,6 +10,9 @@ source [find mem_helper.tcl]
proc flash_npcx {image_path image_offset image_size spifw_image} {
set UPLOAD_FLAG 0x200C4000;
+ echo "*** NPCX Reset and halt CPU first ***"
+ reset halt
+
# Clear whole 96KB Code RAM
mwb 0x100A8000 0xFF 0x18000
# Upload binary image to Code RAM
@@ -34,7 +37,7 @@ proc flash_npcx {image_path image_offset image_size spifw_image} {
resume
# Wait for any pending flash operations to complete
- while {[expr [mrw $UPLOAD_FLAG] & 0x01] == 0} { sleep 1 }
+ while {[expr [mrw $UPLOAD_FLAG] & 0x01] == 0} { sleep 1000 }
if {[expr [mrw $UPLOAD_FLAG] & 0x02] == 0} {
echo "*** Program Fail ***"
@@ -58,7 +61,6 @@ proc flash_npcx_ro {image_dir image_offset} {
# Halt CPU first
halt
- adapter_khz 1000
# diable MPU for Data RAM
mww $MPU_RNR 0x1
@@ -81,8 +83,8 @@ proc flash_npcx_all {image_dir image_offset} {
set flash_size 0x800000
# images path
- set ro_image_path $image_dir/ec.RO.flat
- set rw_image_path $image_dir/ec.RW.bin
+ set ro_image_path $image_dir/RO/ec.RO.flat
+ set rw_image_path $image_dir/RW/ec.RW.bin
set spifw_image $image_dir/chip/npcx/spiflashfw/ec_npcxflash.bin
# images offset
@@ -91,8 +93,6 @@ proc flash_npcx_all {image_dir image_offset} {
# Halt CPU first
halt
- adapter_khz 1000
-
# diable MPU for Data RAM
mww $MPU_RNR 0x1
mww $MPU_RASR 0x0
@@ -109,7 +109,7 @@ proc flash_npcx_all {image_dir image_offset} {
}
-proc halt_npcx_cpu { } {
- echo "*** Halt CPU first ***"
- halt
+proc reset_halt_cpu { } {
+ echo "*** NPCX Reset and halt CPU first ***"
+ reset halt
}