summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorVadim Bendebury <vbendeb@chromium.org>2018-08-08 16:35:29 -0700
committerchrome-bot <chrome-bot@chromium.org>2018-08-16 00:30:05 -0700
commitbaacee39d493a578b40227385d423a8a54629eba (patch)
tree7df357510218fb61b7d3cc477cad111923dc93a6
parent5f57eca28f604829c29ebf318d9675d6c6654724 (diff)
downloadchrome-ec-baacee39d493a578b40227385d423a8a54629eba.tar.gz
cr50: speed up bit bang EC programming
The original bit bang programming implementation attempted to provide a fully functional alternative UART interface for the case when EC programming is required, so that proper UART parity can be ensured. Come to think of it, this is not really necessary: - EC programming over UART does not require full duplex. - when EC is being programmed, the AP is held in reset, there is no need to support AP console or TPM at that time, as a result interrupts could be disabled for somewhat longer intervals. This patch introduces the following modifications: - remove uartn interface redirections - when bitbang mode is enabled regular EC console is not available. - instead of waiting for fixed amount of cycles on every bit, wait for the deadline calculated when character transmission started on tx side or when the original start bit was detected on rx side and recalculated after each clock. - when finishing receiving a character do not exit ISR right away, spin for a duration of a character polling the rx line, in case the EC keeps transmitting. The rx buffer is allocated on the ISR stack and is limited to 20 bytes, which would probably cause an overrun if this interface were used for reading flash contents from the EC. - connect USB EC console flow directly to the bit bang driver when bit bang mode is enabled and disable interrupts from the EC UART. - do not use the GPIO wrappers for bit bang interrupt processing - it takes too long. - when starting a bit bang session set the clock timer value to zero, this allows not to worry about wraparound, which will happen in almost 3 minutes, programming session should not take this long. - for the duration of 'bit bang enabled' state servo detection interrupt is disabled, it gets re-enabled after bit bang mode is disabled and servo_detect() gets to run on 1s hook. - it is not enough to check the DIOB5 pinmux state to tell if EC UART is connected or not, as this pin could be connected in bit bang mode as well; always report EC TX UART as disconnected when bit bang mode is enabled. - for the duration of bit bang programming session suppress 'aggregate' GPIO interrupts, triggered per port when GPIO interrupt is asserted. Additional speed up could be achieved if gpio driver wrappers were replaced with direct register accesses, but even as presented this patch allows to reliably program the STM32 on Scarlet at 57600 baud, which is 6 times faster than the current state. BRANCH=cr50, cr50-mp BUG=b:62539385 TEST=with some flash_ec modifications which make sure that bit bang mode is enabled properly (fixing timing of setting boot0 and resetting the EC), Scarlet device EC can be reprogrammed at 57600 baud 100 times in a row with and without logic analyzer connected to the EC UART pins. Change-Id: I2e3520f158943323cb015fa18650a7e177f03cc3 Signed-off-by: Vadim Bendebury <vbendeb@chromium.org> Reviewed-on: https://chromium-review.googlesource.com/1171221 Reviewed-by: Randall Spangler <rspangler@chromium.org>
-rw-r--r--board/cr50/board.c29
-rw-r--r--board/cr50/ec_state.c3
-rw-r--r--board/cr50/gpio.inc4
-rw-r--r--board/cr50/rdd.c18
-rw-r--r--chip/g/uart_bitbang.c287
-rw-r--r--chip/g/uart_bitbang.h52
-rw-r--r--chip/g/uartn.c66
-rw-r--r--chip/g/usart.c17
8 files changed, 194 insertions, 282 deletions
diff --git a/board/cr50/board.c b/board/cr50/board.c
index 67ed39ab38..8958309fea 100644
--- a/board/cr50/board.c
+++ b/board/cr50/board.c
@@ -93,6 +93,7 @@ struct uart_bitbang_properties bitbang_config = {
.uart = UART_EC,
.tx_gpio = GPIO_DETECT_SERVO, /* This is TX to EC console. */
.rx_gpio = GPIO_EC_TX_CR50_RX,
+ .rx_irq = GC_IRQNUM_GPIO1_GPIO4INT, /* Must match gpoi.inc */
/*
* The rx/tx_pinmux_regval values MUST agree with the pin config for
* both the TX and RX GPIOs in gpio.inc. Don't change one without
@@ -104,19 +105,7 @@ struct uart_bitbang_properties bitbang_config = {
.rx_pinmux_regval = GC_PINMUX_GPIO1_GPIO4_SEL,
};
-void ec_tx_cr50_rx(enum gpio_signal signal)
-{
- uart_bitbang_receive_char();
- /*
- * Let the USART module know that there's new bits to consume.
- *
- * When programming the EC in bitbang mode the rest of the system is
- * shut down, there not much else to do, so this could be processed
- * directly on interrupt context the same way it is done with EC
- * console output.
- */
- send_data_to_usb(&ec_uart);
-}
+DECLARE_IRQ(GC_IRQNUM_GPIO1_GPIO4INT, uart_bitbang_irq, 0);
const char *device_state_names[] = {
"init",
@@ -715,6 +704,13 @@ static void board_init(void)
init_wp_state();
/*
+ * Need to do this at run time as compile time constant initialization
+ * to a variable value (even to a const known at compile time) is not
+ * supported.
+ */
+ bitbang_config.uart_in = ec_uart.producer.queue;
+
+ /*
* Note that the AP, EC, and servo state machines do not have explicit
* init_xxx_state() functions, because they don't need to configure
* registers prior to starting their state machines. Their state
@@ -951,11 +947,18 @@ DECLARE_SAFE_CONSOLE_COMMAND(sysrst, command_sys_rst,
void assert_ec_rst(void)
{
+ /* Prevent bit bang interrupt storm. */
+ if (uart_bitbang_is_enabled())
+ task_disable_irq(bitbang_config.rx_irq);
+
GWRITE(RBOX, ASSERT_EC_RST, 1);
}
void deassert_ec_rst(void)
{
GWRITE(RBOX, ASSERT_EC_RST, 0);
+
+ if (uart_bitbang_is_enabled())
+ task_enable_irq(bitbang_config.rx_irq);
}
int is_ec_rst_asserted(void)
diff --git a/board/cr50/ec_state.c b/board/cr50/ec_state.c
index ddea279909..28a075a1dd 100644
--- a/board/cr50/ec_state.c
+++ b/board/cr50/ec_state.c
@@ -107,6 +107,9 @@ static void ec_detect(void)
/* Disable interrupts if we had them on for debouncing */
gpio_disable_interrupt(GPIO_DETECT_EC);
+ if (uart_bitbang_is_enabled())
+ return;
+
/* If we detect the EC, make sure it's on */
if (gpio_get_level(GPIO_DETECT_EC)) {
set_ec_on();
diff --git a/board/cr50/gpio.inc b/board/cr50/gpio.inc
index 532fc67ff3..2943573b18 100644
--- a/board/cr50/gpio.inc
+++ b/board/cr50/gpio.inc
@@ -65,7 +65,9 @@ GPIO_INT(DETECT_EC, PIN(1, 2), GPIO_INT_HIGH, ec_detect_asserted)
*/
GPIO_INT(DETECT_SERVO, PIN(1, 3), GPIO_INT_HIGH | GPIO_PULL_DOWN,
servo_detect_asserted)
-GPIO_INT(EC_TX_CR50_RX, PIN(1, 4), GPIO_INT_FALLING, ec_tx_cr50_rx)
+
+/* This is used for EC flash bit bang programming. */
+GPIO(EC_TX_CR50_RX, PIN(1, 4), GPIO_INPUT)
/* Pull this low to interrupt the AP */
GPIO(INT_AP_L, PIN(0, 0), GPIO_OUT_HIGH)
diff --git a/board/cr50/rdd.c b/board/cr50/rdd.c
index bb4b225626..8128d1b24c 100644
--- a/board/cr50/rdd.c
+++ b/board/cr50/rdd.c
@@ -58,7 +58,12 @@ int uart_tx_is_connected(int uart)
{
if (uart == UART_AP)
return GREAD(PINMUX, DIOA7_SEL);
- return GREAD(PINMUX, DIOB5_SEL);
+
+ /*
+ * Enabling bit bang programming mode disconnected the EC UART from
+ * the external pin, but muxed DIOB5 to a different GPIO bit.
+ */
+ return !uart_bitbang_is_enabled() && GREAD(PINMUX, DIOB5_SEL);
}
/**
@@ -224,8 +229,7 @@ static void ccd_state_change_hook(void)
flags_want |= CCD_ENABLE_UART_EC;
#ifdef CONFIG_UART_BITBANG
- /* EC must be all the way on for bit-banging the EC UART */
- if (ec_is_on() && uart_bitbang_is_wanted())
+ if (uart_bitbang_is_wanted())
flags_want |= CCD_ENABLE_UART_EC_BITBANG;
#endif
@@ -322,8 +326,14 @@ static void ccd_state_change_hook(void)
if (delta & CCD_ENABLE_UART_EC_TX)
uartn_tx_connect(UART_EC);
#ifdef CONFIG_UART_BITBANG
- if (delta & CCD_ENABLE_UART_EC_BITBANG)
+ if (delta & CCD_ENABLE_UART_EC_BITBANG) {
+ /*
+ * Servo detect interrupt will be re-enabled by the
+ * servo_detect() poll once bit bang mode is disabled.
+ */
+ gpio_disable_interrupt(GPIO_DETECT_SERVO);
uart_bitbang_enable();
+ }
#endif
if (delta & CCD_ENABLE_I2C)
usb_i2c_board_enable();
diff --git a/chip/g/uart_bitbang.c b/chip/g/uart_bitbang.c
index 610514cb47..f2d22ef9f2 100644
--- a/chip/g/uart_bitbang.c
+++ b/chip/g/uart_bitbang.c
@@ -25,9 +25,6 @@
|| (rate == 19200) || (rate == 38400) || (rate == 57600) || \
(rate == 115200))
-#define RX_BUF_SIZE 8
-#define BUF_NEXT(idx) ((idx+1) % RX_BUF_SIZE)
-
#define TIMEUS_CLK_FREQ 24 /* units: MHz */
/* Flag indicating whether bit banging is enabled or not. */
@@ -35,11 +32,7 @@ static uint8_t bitbang_enabled;
/* Flag indicating bit banging is desired. Allows async enable/disable. */
static uint8_t bitbang_wanted;
-static int rx_buf[RX_BUF_SIZE];
-
/* Current bitbang context */
-static int tx_pin;
-static int rx_pin;
static uint32_t bit_period_ticks;
static uint8_t set_parity;
@@ -90,27 +83,35 @@ int uart_bitbang_config(int baud_rate, int parity)
CPRINTF("Err: invalid parity '%d'. (0:N, 1:O, 2:E)\n", parity);
return EC_ERROR_INVAL;
};
- bitbang_config.htp.parity = parity;
+ bitbang_config.parity = parity;
return EC_SUCCESS;
}
int uart_bitbang_enable(void)
{
- /* We only want to bit bang 1 UART at a time */
if (bitbang_enabled)
- return EC_ERROR_BUSY;
+ return EC_SUCCESS;
/* UART TX must be disconnected first */
if (uart_tx_is_connected(bitbang_config.uart))
return EC_ERROR_BUSY;
+ /* Set this early to avoid interfering with CCD state machine. */
+ bitbang_enabled = 1;
+
+ /*
+ * Disable aggregate interrupts from GPIOs, otherwise
+ * _gpio0_interrupt() gets invoked along with the pin specific
+ * interrupts.
+ */
+ task_disable_irq(GC_IRQNUM_GPIO0_GPIOCOMBINT);
+ task_disable_irq(GC_IRQNUM_GPIO1_GPIOCOMBINT);
+
/* Select the GPIOs instead of the UART block */
- REG32(bitbang_config.tx_pinmux_reg) =
- bitbang_config.tx_pinmux_regval;
+ REG32(bitbang_config.tx_pinmux_reg) = bitbang_config.tx_pinmux_regval;
gpio_set_flags(bitbang_config.tx_gpio, GPIO_OUT_HIGH);
- REG32(bitbang_config.rx_pinmux_reg) =
- bitbang_config.rx_pinmux_regval;
+ REG32(bitbang_config.rx_pinmux_reg) = bitbang_config.rx_pinmux_regval;
gpio_set_flags(bitbang_config.rx_gpio, GPIO_INPUT);
/*
@@ -120,26 +121,20 @@ int uart_bitbang_enable(void)
pmu_clock_en(PERIPH_TIMEUS);
GR_TIMEUS_EN(0) = 0;
GR_TIMEUS_MAXVAL(0) = 0xFFFFFFFF;
+ GR_TIMEUS_CUR_MAJOR(0) = 0; /* Prevent timer counter overflows. */
GR_TIMEUS_EN(0) = 1;
/* Save context information. */
- tx_pin = bitbang_config.tx_gpio;
- rx_pin = bitbang_config.rx_gpio;
- bit_period_ticks = TIMEUS_CLK_FREQ *
- ((1 * SECOND) / bitbang_config.baud_rate);
- set_parity = bitbang_config.htp.parity;
-
- /* Register the function pointers. */
- uartn_funcs[bitbang_config.uart]._rx_available =
- _uart_bitbang_rx_available;
- uartn_funcs[bitbang_config.uart]._write_char =
- _uart_bitbang_write_char;
- uartn_funcs[bitbang_config.uart]._read_char =
- _uart_bitbang_read_char;
+ bit_period_ticks = ((uint64_t)TIMEUS_CLK_FREQ * SECOND) /
+ bitbang_config.baud_rate;
+ set_parity = bitbang_config.parity;
- bitbang_enabled = 1;
+ uartn_disable_interrupt(bitbang_config.uart);
+ task_enable_irq(bitbang_config.rx_irq);
gpio_enable_interrupt(bitbang_config.rx_gpio);
+
CPRINTS("Bit bang enabled");
+
return EC_SUCCESS;
}
@@ -148,223 +143,212 @@ int uart_bitbang_disable(void)
if (!uart_bitbang_is_enabled())
return EC_SUCCESS;
- /*
- * This is safe because if the UART was not specified in the config, we
- * would have already returned.
- */
- bitbang_enabled = 0;
gpio_reset(bitbang_config.tx_gpio);
gpio_reset(bitbang_config.rx_gpio);
- /* Unregister the function pointers. */
- uartn_funcs[bitbang_config.uart]._rx_available = _uartn_rx_available;
- uartn_funcs[bitbang_config.uart]._write_char = _uartn_write_char;
- uartn_funcs[bitbang_config.uart]._read_char = _uartn_read_char;
-
/* Gate the microsecond timer since we're done with it. */
pmu_clock_dis(PERIPH_TIMEUS);
/* Don't need to watch RX */
gpio_disable_interrupt(bitbang_config.rx_gpio);
+ task_disable_irq(bitbang_config.rx_irq);
+ uartn_enable_interrupt(bitbang_config.uart);
+
+ /* Restore aggregate GPIO interrupts. */
+ task_enable_irq(GC_IRQNUM_GPIO0_GPIOCOMBINT);
+ task_enable_irq(GC_IRQNUM_GPIO1_GPIOCOMBINT);
+
+ bitbang_enabled = 0;
+
CPRINTS("Bit bang disabled");
return EC_SUCCESS;
}
-static void wait_ticks(uint32_t ticks)
+/*
+ * Function waiting for completion of the current tick should be re-entrant -
+ * it is not likely to happen, but is possible that the RX interrupt gets
+ * asserted while the last period of the TX is still counting, because the
+ * last TX period is counting with interrupts enabled.
+ */
+static void wait_ticks(uint32_t *next_tick)
{
- uint32_t t0 = GR_TIMEUS_CUR_MAJOR(0);
+ uint32_t nt = *next_tick;
- while ((GR_TIMEUS_CUR_MAJOR(0) - t0) < ticks)
+ while (GR_TIMEUS_CUR_MAJOR(0) < nt)
;
+
+ *next_tick += bit_period_ticks;
+}
+
+static uint32_t get_next_tick(uint32_t delta)
+{
+ return GR_TIMEUS_CUR_MAJOR(0) + delta;
}
-void uart_bitbang_write_char(char c)
+static void uart_bitbang_write_char(char c)
{
int val;
int ones;
int i;
-
- if (!uart_bitbang_is_enabled())
- return;
+ uint32_t next_tick;
interrupt_disable();
+ next_tick = get_next_tick(bit_period_ticks);
+
/* Start bit. */
- gpio_set_level(tx_pin, 0);
- wait_ticks(bit_period_ticks);
+ gpio_set_level(bitbang_config.tx_gpio, 0);
+ wait_ticks(&next_tick);
/* 8 data bits. */
ones = 0;
for (i = 0; i < 8; i++) {
val = (c & (1 << i));
+ gpio_set_level(bitbang_config.tx_gpio, val);
+
/* Count 1's in order to handle parity bit. */
if (val)
ones++;
- gpio_set_level(tx_pin, val);
- wait_ticks(bit_period_ticks);
+ wait_ticks(&next_tick);
}
/* Optional parity. */
- switch (set_parity) {
- case 1: /* odd parity */
- if (ones & 0x1)
- gpio_set_level(tx_pin, 0);
- else
- gpio_set_level(tx_pin, 1);
- wait_ticks(bit_period_ticks);
- break;
-
- case 2: /* even parity */
- if (ones & 0x1)
- gpio_set_level(tx_pin, 1);
- else
- gpio_set_level(tx_pin, 0);
- wait_ticks(bit_period_ticks);
- break;
-
- case 0: /* no parity */
- default:
- break;
+ if (set_parity) {
+ gpio_set_level(bitbang_config.tx_gpio,
+ (set_parity == 1) ^ (ones & 1));
+ wait_ticks(&next_tick);
};
/* 1 stop bit. */
- gpio_set_level(tx_pin, 1);
- wait_ticks(bit_period_ticks);
+ gpio_set_level(bitbang_config.tx_gpio, 1);
+
+ /*
+ * Re-enable interrupts early: this could be the last byte and the
+ * response could come very soon, we don't want to waste time enabling
+ * interrupts AFTER stop bit is completed.
+ */
interrupt_enable();
+ wait_ticks(&next_tick);
+}
+
+void uart_bitbang_drain_tx_queue(struct queue const *q)
+{
+ uint8_t c;
+
+ while (queue_count(q)) {
+ QUEUE_REMOVE_UNITS(q, &c, 1);
+ uart_bitbang_write_char(c);
+ }
}
-int uart_bitbang_receive_char(void)
+static int uart_bitbang_receive_char(uint8_t *rxed_char, uint32_t *next_tick)
{
uint8_t rx_char;
int i;
- int rv;
int ones;
int parity_bit;
int stop_bit;
- uint8_t head;
- uint8_t tail;
- /* Disable interrupts so that we aren't interrupted. */
- interrupt_disable();
#if BITBANG_DEBUG
rx_buff_rx_char_cnt++;
#endif /* BITBANG_DEBUG */
- rv = EC_SUCCESS;
rx_char = 0;
+ ones = 0;
/* Wait 1 bit period for the start bit. */
- wait_ticks(bit_period_ticks);
+ wait_ticks(next_tick);
- /* 8 data bits. */
- ones = 0;
for (i = 0; i < 8; i++) {
- if (gpio_get_level(rx_pin)) {
+ if (gpio_get_level(bitbang_config.rx_gpio)) {
ones++;
rx_char |= (1 << i);
}
- wait_ticks(bit_period_ticks);
+ wait_ticks(next_tick);
}
/* optional parity or stop bit. */
- parity_bit = gpio_get_level(rx_pin);
+ parity_bit = gpio_get_level(bitbang_config.rx_gpio);
+
if (set_parity) {
- wait_ticks(bit_period_ticks);
- stop_bit = gpio_get_level(rx_pin);
+ wait_ticks(next_tick);
+ stop_bit = gpio_get_level(bitbang_config.rx_gpio);
+
+ if ((set_parity == 1) != ((ones + parity_bit) & 1)) {
+#if BITBANG_DEBUG
+ parity_err_cnt++;
+ parity_err_discard[parity_discard_idx] = rx_char;
+ parity_discard_idx = (parity_discard_idx + 1) %
+ DISCARD_LOG;
+#endif /* BITBANG_DEBUG */
+ return EC_ERROR_CRC;
+ }
} else {
/* If there's no parity, that _was_ the stop bit. */
stop_bit = parity_bit;
}
- /* Check the parity if necessary. */
- switch (set_parity) {
- case 2: /* even parity */
- if (ones & 0x1)
- rv = parity_bit ? EC_SUCCESS : EC_ERROR_CRC;
- else
- rv = parity_bit ? EC_ERROR_CRC : EC_SUCCESS;
- break;
-
- case 1: /* odd parity */
- if (ones & 0x1)
- rv = parity_bit ? EC_ERROR_CRC : EC_SUCCESS;
- else
- rv = parity_bit ? EC_SUCCESS : EC_ERROR_CRC;
- break;
-
- case 0:
- default:
- break;
- }
-
-#if BITBANG_DEBUG
- if (rv != EC_SUCCESS) {
- parity_err_cnt++;
- parity_err_discard[parity_discard_idx] = rx_char;
- parity_discard_idx = (parity_discard_idx + 1) % DISCARD_LOG;
- }
-#endif /* BITBANG_DEBUG */
/* Check that the stop bit is valid. */
if (stop_bit != 1) {
- rv = EC_ERROR_CRC;
#if BITBANG_DEBUG
stop_bit_err_cnt++;
stop_bit_discard[stop_bit_discard_idx] = rx_char;
stop_bit_discard_idx = (stop_bit_discard_idx + 1) % DISCARD_LOG;
#endif /* BITBANG_DEBUG */
- }
-
- if (rv != EC_SUCCESS) {
- interrupt_enable();
- return rv;
+ return EC_ERROR_CRC;
}
/* Place the received char in the RX buffer. */
- head = bitbang_config.htp.head;
- tail = bitbang_config.htp.tail;
- if (BUF_NEXT(tail) != head) {
- rx_buf[tail] = rx_char;
- bitbang_config.htp.tail = BUF_NEXT(tail);
#if BITBANG_DEBUG
- rx_buff_inserted_cnt++;
+ rx_buff_inserted_cnt++;
#endif /* BITBANG_DEBUG */
- }
- interrupt_enable();
+ *rxed_char = rx_char;
+
return EC_SUCCESS;
}
-int uart_bitbang_read_char(void)
+void uart_bitbang_irq(void)
{
- int c;
- uint8_t head;
-
- head = bitbang_config.htp.head;
- c = rx_buf[head];
+ uint8_t rx_buffer[20];
+ size_t i = 0;
+ uint32_t next_tick;
+
+ /* Empirically chosen IRQ latency compensation. */
+ next_tick = get_next_tick(bit_period_ticks - 40);
+ do {
+ uint32_t max_time;
+ int rv;
+new_char:
+ rv = uart_bitbang_receive_char(rx_buffer + i, &next_tick);
+ gpio_clear_pending_interrupt(bitbang_config.rx_gpio);
+
+ if (rv != EC_SUCCESS)
+ break;
- if (head != bitbang_config.htp.tail)
- bitbang_config.htp.head = BUF_NEXT(head);
+ if (++i == sizeof(rx_buffer))
+ break;
+ /*
+ * For the duration of one byte wait for another byte from the
+ * EC.
+ */
+ max_time = GR_TIMEUS_CUR_MAJOR(0) + bit_period_ticks * 10;
+ while (GR_TIMEUS_CUR_MAJOR(0) < max_time) {
+ if (!gpio_get_level(bitbang_config.rx_gpio)) {
+ next_tick = get_next_tick(bit_period_ticks);
+ goto new_char;
+ }
+ }
-#if BITBANG_DEBUG
- read_char_cnt++;
-#endif /* BITBANG_DEBUG */
- return c;
-}
+ } while (0);
-int uart_bitbang_is_char_available(void)
-{
- return bitbang_config.htp.head != bitbang_config.htp.tail;
+ QUEUE_ADD_UNITS(bitbang_config.uart_in, rx_buffer, i);
}
#if BITBANG_DEBUG
static int write_test_pattern(int pattern_idx)
{
- if (!uart_bitbang_is_enabled()) {
- ccprintf("bit banging mode not enabled for UART%d\n", uart);
- return EC_ERROR_INVAL;
- }
-
switch (pattern_idx) {
case 0:
uart_bitbang_write_char(uart, 'a');
@@ -442,7 +426,7 @@ static int command_bitbang(int argc, char **argv)
} else {
ccprintf("baud rate - parity\n");
ccprintf(" %6d ", bitbang_config.baud_rate);
- switch (bitbang_config.htp.parity) {
+ switch (bitbang_config.parity) {
case 1:
ccprintf("odd\n");
break;
@@ -497,9 +481,6 @@ static int command_bitbang_dump_stats(int argc, char **argv)
for (i = 0; i < RX_BUF_SIZE; i++)
ccprintf(" %02x ", rx_buf[i] & 0xFF);
ccprintf("]\n");
- ccprintf("head: %d\ntail: %d\n",
- bitbang_config.htp.head,
- bitbang_config.htp.tail);
ccprintf("Discards\nparity: ");
ccprintf("[");
for (i = 0; i < DISCARD_LOG; i++)
diff --git a/chip/g/uart_bitbang.h b/chip/g/uart_bitbang.h
index 8ebf5635a0..75084da165 100644
--- a/chip/g/uart_bitbang.h
+++ b/chip/g/uart_bitbang.h
@@ -10,25 +10,7 @@
#include "common.h"
#include "gpio.h"
-
-/* These are functions that we'll have to replace. */
-struct uartn_function_ptrs {
- int (*_rx_available)(int uart);
- void (*_write_char)(int uart, char c);
- int (*_read_char)(int uart);
-};
-
-/*
- * And these are the function definitions. The functions live in
- * chip/g/uartn.c.
- */
-extern int _uartn_rx_available(int uart);
-extern void _uartn_write_char(int uart, char c);
-extern int _uartn_read_char(int uart);
-extern int _uart_bitbang_rx_available(int uart);
-extern void _uart_bitbang_write_char(int uart, char c);
-extern int _uart_bitbang_read_char(int uart);
-extern struct uartn_function_ptrs uartn_funcs[];
+#include "queue.h"
struct uart_bitbang_properties {
enum gpio_signal tx_gpio;
@@ -37,13 +19,11 @@ struct uart_bitbang_properties {
uint32_t tx_pinmux_regval;
uint32_t rx_pinmux_reg;
uint32_t rx_pinmux_regval;
- int baud_rate;
+ struct queue const *uart_in;
+ uint32_t baud_rate;
+ uint16_t rx_irq;
uint8_t uart;
- struct {
- unsigned int head : 3;
- unsigned int tail : 3;
- unsigned int parity : 2;
- } htp __packed;
+ uint8_t parity;
};
/* In order to bitbang a UART, a board must define a bitbang_config. */
@@ -84,32 +64,14 @@ int uart_bitbang_is_enabled(void);
int uart_bitbang_is_wanted(void);
/**
- * TX a character on a UART configured for bit banging mode.
- *
- * @param c: Character to send out.
- */
-void uart_bitbang_write_char(char c);
-
-/**
* Sample the RX line on a UART configured for bit banging mode.
*
* This is called when a falling edge is seen on the RX line and will attempt to
* receive a character. Incoming data with framing errors or parity errors will
* be discarded.
- *
- * @returns EC_SUCCESS if a character was successfully received, EC_ERROR_CRC if
- * there was a framing or parity issue.
*/
-int uart_bitbang_receive_char(void);
+void uart_bitbang_irq(void);
-/**
- * Returns 1 if there are characters available for consumption, otherwise 0.
- */
-int uart_bitbang_is_char_available(void);
-
-/**
- * Retrieve a character from the bit bang RX buffer.
- */
-int uart_bitbang_read_char(void);
+void uart_bitbang_drain_tx_queue(struct queue const *q);
#endif /* __CROS_EC_CHIP_G_UART_BITBANG_H */
diff --git a/chip/g/uartn.c b/chip/g/uartn.c
index 0c9b5882dd..8f14f3c54e 100644
--- a/chip/g/uartn.c
+++ b/chip/g/uartn.c
@@ -10,7 +10,6 @@
#include "system.h"
#include "task.h"
#include "uart.h"
-#include "uart_bitbang.h"
#include "util.h"
#define USE_UART_INTERRUPTS (!(defined(CONFIG_CUSTOMIZED_RO) && \
@@ -26,26 +25,6 @@ static struct uartn_interrupts interrupt[] = {
{GC_IRQNUM_UART2_TXINT, GC_IRQNUM_UART2_RXINT},
};
-struct uartn_function_ptrs uartn_funcs[3] = {
- {
- _uartn_rx_available,
- _uartn_write_char,
- _uartn_read_char,
- },
-
- {
- _uartn_rx_available,
- _uartn_write_char,
- _uartn_read_char,
- },
-
- {
- _uartn_rx_available,
- _uartn_write_char,
- _uartn_read_char,
- },
-};
-
void uartn_tx_start(int uart)
{
if (!uart_init_done())
@@ -113,18 +92,13 @@ int uartn_tx_ready(int uart)
return !(GR_UART_STATE(uart) & GC_UART_STATE_TX_MASK);
}
-int _uartn_rx_available(int uart)
+int uartn_rx_available(int uart)
{
/* True if the RX buffer is not completely empty. */
return !(GR_UART_STATE(uart) & GC_UART_STATE_RXEMPTY_MASK);
}
-int uartn_rx_available(int uart)
-{
- return uartn_funcs[uart]._rx_available(uart);
-}
-
-void _uartn_write_char(int uart, char c)
+void uartn_write_char(int uart, char c)
{
/* Wait for space in transmit FIFO. */
while (!uartn_tx_ready(uart))
@@ -133,44 +107,10 @@ void _uartn_write_char(int uart, char c)
GR_UART_WDATA(uart) = c;
}
-void uartn_write_char(int uart, char c)
-{
- uartn_funcs[uart]._write_char(uart, c);
-}
-
-int _uartn_read_char(int uart)
-{
- return GR_UART_RDATA(uart);
-}
-
int uartn_read_char(int uart)
{
- return uartn_funcs[uart]._read_char(uart);
-}
-
-#ifdef CONFIG_UART_BITBANG
-int _uart_bitbang_rx_available(int uart)
-{
- if (uart_bitbang_is_enabled())
- return uart_bitbang_is_char_available();
-
- return 0;
-}
-
-void _uart_bitbang_write_char(int uart, char c)
-{
- if (uart_bitbang_is_enabled())
- uart_bitbang_write_char(c);
-}
-
-int _uart_bitbang_read_char(int uart)
-{
- if (uart_bitbang_is_enabled())
- return uart_bitbang_read_char();
-
- return 0;
+ return GR_UART_RDATA(uart);
}
-#endif /* defined(CONFIG_UART_BITBANG) */
void uartn_disable_interrupt(int uart)
{
diff --git a/chip/g/usart.c b/chip/g/usart.c
index 6580ca9eb0..3e5ba3a88a 100644
--- a/chip/g/usart.c
+++ b/chip/g/usart.c
@@ -5,12 +5,15 @@
#include "queue.h"
#include "queue_policies.h"
-#include "uartn.h"
-#include "usart.h"
-#include "usb-stream.h"
#ifdef CONFIG_STREAM_SIGNATURE
#include "signing.h"
#endif
+#ifdef CONFIG_UART_BITBANG
+#include "uart_bitbang.h"
+#endif
+#include "uartn.h"
+#include "usart.h"
+#include "usb-stream.h"
#define USE_UART_INTERRUPTS (!(defined(CONFIG_CUSTOMIZED_RO) && \
defined(SECTION_IS_RO)))
@@ -173,6 +176,14 @@ static void uart_written(struct consumer const *consumer, size_t count)
struct usart_config const *config =
DOWNCAST(consumer, struct usart_config, consumer);
+#ifdef CONFIG_UART_BITBANG
+ if (uart_bitbang_is_enabled() &&
+ (config->uart == bitbang_config.uart)) {
+ uart_bitbang_drain_tx_queue(consumer->queue);
+ return;
+ }
+#endif
+
if (uartn_tx_ready(config->uart), queue_count(consumer->queue))
uartn_tx_start(config->uart);
}