2009-06-18 00:34:19

by Brian Swetland

[permalink] [raw]
Subject: Revised patch series for minimal HTC Dream support

This incorporates feedback from lkml/lakml, and I think is in
pretty good shape now.

msm_serial.c
- Ryan Mallon
- remove some likely/unlikely not in hot-path code, for clarity
- UART_TO_MSM() -> to_msm_uart()
- clean up static structure declarations
- Pavel Machek
- SUPPORT_SYSRQ needed for console break handling
- remove hrtimer.h, other unused headers
- Kconfig cleanup
- Alan Cox
- set_termios should propogate used settings
- Linus Walleij
- use resource_size() when appropriate
- dev_err instead of printk(KERN_ERR...
- remove some chatty printks
- use __exit, __exit_p()

board-dream.c
- Stefan Schmidt
- remove smc resources
- remove unused headers

ll debug support
- Pavel Machek
- remove extraneous 1002 label


2009-06-18 00:34:33

by Brian Swetland

[permalink] [raw]
Subject: [PATCH 1/3] [ARM] msm_serial: serial driver for MSM7K onboard serial peripheral.

From: Robert Love <[email protected]>

Provides support for the "lowspeed" UARTs on the MSM7k and QSD8k
family of SoCs from Qualcomm. Serial console support included.

Signed-off-by: Robert Love <[email protected]>
Signed-off-by: Brian Swetland <[email protected]>
Acked-by: Pavel Machek <[email protected]>
---
drivers/serial/Kconfig | 10 +
drivers/serial/Makefile | 1 +
drivers/serial/msm_serial.c | 762 +++++++++++++++++++++++++++++++++++++++++++
drivers/serial/msm_serial.h | 117 +++++++
include/linux/serial_core.h | 3 +
5 files changed, 893 insertions(+), 0 deletions(-)
create mode 100644 drivers/serial/msm_serial.c
create mode 100644 drivers/serial/msm_serial.h

diff --git a/drivers/serial/Kconfig b/drivers/serial/Kconfig
index 1132c5c..1e3cc15 100644
--- a/drivers/serial/Kconfig
+++ b/drivers/serial/Kconfig
@@ -1320,6 +1320,16 @@ config SERIAL_SGI_IOC3
If you have an SGI Altix with an IOC3 serial card,
say Y or M. Otherwise, say N.

+config SERIAL_MSM
+ bool "MSM on-chip serial port support"
+ depends on ARM && ARCH_MSM
+ select SERIAL_CORE
+
+config SERIAL_MSM_CONSOLE
+ bool "MSM serial console support"
+ depends on SERIAL_MSM
+ select SERIAL_CORE_CONSOLE
+
config SERIAL_NETX
tristate "NetX serial port support"
depends on ARM && ARCH_NETX
diff --git a/drivers/serial/Makefile b/drivers/serial/Makefile
index 45a8658..d5a2998 100644
--- a/drivers/serial/Makefile
+++ b/drivers/serial/Makefile
@@ -71,6 +71,7 @@ obj-$(CONFIG_SERIAL_SGI_IOC4) += ioc4_serial.o
obj-$(CONFIG_SERIAL_SGI_IOC3) += ioc3_serial.o
obj-$(CONFIG_SERIAL_ATMEL) += atmel_serial.o
obj-$(CONFIG_SERIAL_UARTLITE) += uartlite.o
+obj-$(CONFIG_SERIAL_MSM) += msm_serial.o
obj-$(CONFIG_SERIAL_NETX) += netx-serial.o
obj-$(CONFIG_SERIAL_OF_PLATFORM) += of_serial.o
obj-$(CONFIG_SERIAL_OF_PLATFORM_NWPSERIAL) += nwpserial.o
diff --git a/drivers/serial/msm_serial.c b/drivers/serial/msm_serial.c
new file mode 100644
index 0000000..b0569d9
--- /dev/null
+++ b/drivers/serial/msm_serial.c
@@ -0,0 +1,762 @@
+/*
+ * drivers/serial/msm_serial.c - driver for msm7k serial device and console
+ *
+ * Copyright (C) 2007 Google, Inc.
+ * Author: Robert Love <[email protected]>
+ *
+ * This software is licensed under the terms of the GNU General Public
+ * License version 2, as published by the Free Software Foundation, and
+ * may be copied, distributed, and modified under those terms.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ */
+
+#if defined(CONFIG_SERIAL_MSM_CONSOLE) && defined(CONFIG_MAGIC_SYSRQ)
+# define SUPPORT_SYSRQ
+#endif
+
+#include <linux/module.h>
+#include <linux/io.h>
+#include <linux/irq.h>
+#include <linux/init.h>
+#include <linux/console.h>
+#include <linux/tty.h>
+#include <linux/tty_flip.h>
+#include <linux/serial_core.h>
+#include <linux/serial.h>
+#include <linux/clk.h>
+#include <linux/platform_device.h>
+
+#include "msm_serial.h"
+
+struct msm_port {
+ struct uart_port uart;
+ char name[16];
+ struct clk *clk;
+ unsigned int imr;
+};
+
+#define to_msm_uart(uart_port) ((struct msm_port *) uart_port)
+
+static inline void msm_write(struct uart_port *port, unsigned int val,
+ unsigned int off)
+{
+ __raw_writel(val, port->membase + off);
+}
+
+static inline unsigned int msm_read(struct uart_port *port, unsigned int off)
+{
+ return __raw_readl(port->membase + off);
+}
+
+static void msm_stop_tx(struct uart_port *port)
+{
+ struct msm_port *msm_port = to_msm_uart(port);
+
+ msm_port->imr &= ~UART_IMR_TXLEV;
+ msm_write(port, msm_port->imr, UART_IMR);
+}
+
+static void msm_start_tx(struct uart_port *port)
+{
+ struct msm_port *msm_port = to_msm_uart(port);
+
+ msm_port->imr |= UART_IMR_TXLEV;
+ msm_write(port, msm_port->imr, UART_IMR);
+}
+
+static void msm_stop_rx(struct uart_port *port)
+{
+ struct msm_port *msm_port = to_msm_uart(port);
+
+ msm_port->imr &= ~(UART_IMR_RXLEV | UART_IMR_RXSTALE);
+ msm_write(port, msm_port->imr, UART_IMR);
+}
+
+static void msm_enable_ms(struct uart_port *port)
+{
+ struct msm_port *msm_port = to_msm_uart(port);
+
+ msm_port->imr |= UART_IMR_DELTA_CTS;
+ msm_write(port, msm_port->imr, UART_IMR);
+}
+
+static void handle_rx(struct uart_port *port)
+{
+ struct tty_struct *tty = port->info->port.tty;
+ unsigned int sr;
+
+ /*
+ * Handle overrun. My understanding of the hardware is that overrun
+ * is not tied to the RX buffer, so we handle the case out of band.
+ */
+ if ((msm_read(port, UART_SR) & UART_SR_OVERRUN)) {
+ port->icount.overrun++;
+ tty_insert_flip_char(tty, 0, TTY_OVERRUN);
+ msm_write(port, UART_CR_CMD_RESET_ERR, UART_CR);
+ }
+
+ /* and now the main RX loop */
+ while ((sr = msm_read(port, UART_SR)) & UART_SR_RX_READY) {
+ unsigned int c;
+ char flag = TTY_NORMAL;
+
+ c = msm_read(port, UART_RF);
+
+ if (sr & UART_SR_RX_BREAK) {
+ port->icount.brk++;
+ if (uart_handle_break(port))
+ continue;
+ } else if (sr & UART_SR_PAR_FRAME_ERR) {
+ port->icount.frame++;
+ } else {
+ port->icount.rx++;
+ }
+
+ /* Mask conditions we're ignorning. */
+ sr &= port->read_status_mask;
+
+ if (sr & UART_SR_RX_BREAK) {
+ flag = TTY_BREAK;
+ } else if (sr & UART_SR_PAR_FRAME_ERR) {
+ flag = TTY_FRAME;
+ }
+
+ if (!uart_handle_sysrq_char(port, c))
+ tty_insert_flip_char(tty, c, flag);
+ }
+
+ tty_flip_buffer_push(tty);
+}
+
+static void handle_tx(struct uart_port *port)
+{
+ struct circ_buf *xmit = &port->info->xmit;
+ struct msm_port *msm_port = to_msm_uart(port);
+ int sent_tx;
+
+ if (port->x_char) {
+ msm_write(port, port->x_char, UART_TF);
+ port->icount.tx++;
+ port->x_char = 0;
+ }
+
+ while (msm_read(port, UART_SR) & UART_SR_TX_READY) {
+ if (uart_circ_empty(xmit)) {
+ /* disable tx interrupts */
+ msm_port->imr &= ~UART_IMR_TXLEV;
+ msm_write(port, msm_port->imr, UART_IMR);
+ break;
+ }
+
+ msm_write(port, xmit->buf[xmit->tail], UART_TF);
+
+ xmit->tail = (xmit->tail + 1) & (UART_XMIT_SIZE - 1);
+ port->icount.tx++;
+ sent_tx = 1;
+ }
+
+ if (uart_circ_chars_pending(xmit) < WAKEUP_CHARS)
+ uart_write_wakeup(port);
+}
+
+static void handle_delta_cts(struct uart_port *port)
+{
+ msm_write(port, UART_CR_CMD_RESET_CTS, UART_CR);
+ port->icount.cts++;
+ wake_up_interruptible(&port->info->delta_msr_wait);
+}
+
+static irqreturn_t msm_irq(int irq, void *dev_id)
+{
+ struct uart_port *port = dev_id;
+ struct msm_port *msm_port = to_msm_uart(port);
+ unsigned int misr;
+
+ spin_lock(&port->lock);
+ misr = msm_read(port, UART_MISR);
+ msm_write(port, 0, UART_IMR); /* disable interrupt */
+
+ if (misr & (UART_IMR_RXLEV | UART_IMR_RXSTALE))
+ handle_rx(port);
+ if (misr & UART_IMR_TXLEV)
+ handle_tx(port);
+ if (misr & UART_IMR_DELTA_CTS)
+ handle_delta_cts(port);
+
+ msm_write(port, msm_port->imr, UART_IMR); /* restore interrupt */
+ spin_unlock(&port->lock);
+
+ return IRQ_HANDLED;
+}
+
+static unsigned int msm_tx_empty(struct uart_port *port)
+{
+ return (msm_read(port, UART_SR) & UART_SR_TX_EMPTY) ? TIOCSER_TEMT : 0;
+}
+
+static unsigned int msm_get_mctrl(struct uart_port *port)
+{
+ return TIOCM_CAR | TIOCM_CTS | TIOCM_DSR | TIOCM_RTS;
+}
+
+static void msm_set_mctrl(struct uart_port *port, unsigned int mctrl)
+{
+ unsigned int mr;
+
+ mr = msm_read(port, UART_MR1);
+
+ if (!(mctrl & TIOCM_RTS)) {
+ mr &= ~UART_MR1_RX_RDY_CTL;
+ msm_write(port, mr, UART_MR1);
+ msm_write(port, UART_CR_CMD_RESET_RFR, UART_CR);
+ } else {
+ mr |= UART_MR1_RX_RDY_CTL;
+ msm_write(port, mr, UART_MR1);
+ }
+}
+
+static void msm_break_ctl(struct uart_port *port, int break_ctl)
+{
+ if (break_ctl)
+ msm_write(port, UART_CR_CMD_START_BREAK, UART_CR);
+ else
+ msm_write(port, UART_CR_CMD_STOP_BREAK, UART_CR);
+}
+
+static int msm_set_baud_rate(struct uart_port *port, unsigned int baud)
+{
+ unsigned int baud_code, rxstale, watermark;
+
+ switch (baud) {
+ case 300:
+ baud_code = UART_CSR_300;
+ rxstale = 1;
+ break;
+ case 600:
+ baud_code = UART_CSR_600;
+ rxstale = 1;
+ break;
+ case 1200:
+ baud_code = UART_CSR_1200;
+ rxstale = 1;
+ break;
+ case 2400:
+ baud_code = UART_CSR_2400;
+ rxstale = 1;
+ break;
+ case 4800:
+ baud_code = UART_CSR_4800;
+ rxstale = 1;
+ break;
+ case 9600:
+ baud_code = UART_CSR_9600;
+ rxstale = 2;
+ break;
+ case 14400:
+ baud_code = UART_CSR_14400;
+ rxstale = 3;
+ break;
+ case 19200:
+ baud_code = UART_CSR_19200;
+ rxstale = 4;
+ break;
+ case 28800:
+ baud_code = UART_CSR_28800;
+ rxstale = 6;
+ break;
+ case 38400:
+ baud_code = UART_CSR_38400;
+ rxstale = 8;
+ break;
+ case 57600:
+ baud_code = UART_CSR_57600;
+ rxstale = 16;
+ break;
+ case 115200:
+ default:
+ baud_code = UART_CSR_115200;
+ baud = 115200;
+ rxstale = 31;
+ break;
+ }
+
+ msm_write(port, baud_code, UART_CSR);
+
+ /* RX stale watermark */
+ watermark = UART_IPR_STALE_LSB & rxstale;
+ watermark |= UART_IPR_RXSTALE_LAST;
+ watermark |= UART_IPR_STALE_TIMEOUT_MSB & (rxstale << 2);
+ msm_write(port, watermark, UART_IPR);
+
+ /* set RX watermark */
+ watermark = (port->fifosize * 3) / 4;
+ msm_write(port, watermark, UART_RFWR);
+
+ /* set TX watermark */
+ msm_write(port, 10, UART_TFWR);
+
+ return baud;
+}
+
+static void msm_reset(struct uart_port *port)
+{
+ /* reset everything */
+ msm_write(port, UART_CR_CMD_RESET_RX, UART_CR);
+ msm_write(port, UART_CR_CMD_RESET_TX, UART_CR);
+ msm_write(port, UART_CR_CMD_RESET_ERR, UART_CR);
+ msm_write(port, UART_CR_CMD_RESET_BREAK_INT, UART_CR);
+ msm_write(port, UART_CR_CMD_RESET_CTS, UART_CR);
+ msm_write(port, UART_CR_CMD_SET_RFR, UART_CR);
+}
+
+static void msm_init_clock(struct uart_port *port)
+{
+ struct msm_port *msm_port = to_msm_uart(port);
+
+ clk_enable(msm_port->clk);
+
+ msm_write(port, 0xC0, UART_MREG);
+ msm_write(port, 0xB2, UART_NREG);
+ msm_write(port, 0x7D, UART_DREG);
+ msm_write(port, 0x1C, UART_MNDREG);
+}
+
+static int msm_startup(struct uart_port *port)
+{
+ struct msm_port *msm_port = to_msm_uart(port);
+ unsigned int data, rfr_level;
+ int ret;
+
+ snprintf(msm_port->name, sizeof(msm_port->name),
+ "msm_serial%d", port->line);
+
+ ret = request_irq(port->irq, msm_irq, IRQF_TRIGGER_HIGH,
+ msm_port->name, port);
+ if (ret)
+ return ret;
+
+ msm_init_clock(port);
+
+ if (port->fifosize > 12)
+ rfr_level = port->fifosize - 12;
+ else
+ rfr_level = port->fifosize;
+
+ /* set automatic RFR level */
+ data = msm_read(port, UART_MR1);
+ data &= ~UART_MR1_AUTO_RFR_LEVEL1;
+ data &= ~UART_MR1_AUTO_RFR_LEVEL0;
+ data |= UART_MR1_AUTO_RFR_LEVEL1 & (rfr_level << 2);
+ data |= UART_MR1_AUTO_RFR_LEVEL0 & rfr_level;
+ msm_write(port, data, UART_MR1);
+
+ /* make sure that RXSTALE count is non-zero */
+ data = msm_read(port, UART_IPR);
+ if (!data) {
+ data |= UART_IPR_RXSTALE_LAST;
+ data |= UART_IPR_STALE_LSB;
+ msm_write(port, data, UART_IPR);
+ }
+
+ msm_reset(port);
+
+ msm_write(port, 0x05, UART_CR); /* enable TX & RX */
+
+ /* turn on RX and CTS interrupts */
+ msm_port->imr = UART_IMR_RXLEV | UART_IMR_RXSTALE |
+ UART_IMR_CURRENT_CTS;
+ msm_write(port, msm_port->imr, UART_IMR);
+
+ return 0;
+}
+
+static void msm_shutdown(struct uart_port *port)
+{
+ struct msm_port *msm_port = to_msm_uart(port);
+
+ msm_port->imr = 0;
+ msm_write(port, 0, UART_IMR); /* disable interrupts */
+
+ clk_disable(msm_port->clk);
+
+ free_irq(port->irq, port);
+}
+
+static void msm_set_termios(struct uart_port *port, struct ktermios *termios,
+ struct ktermios *old)
+{
+ unsigned long flags;
+ unsigned int baud, mr;
+
+ spin_lock_irqsave(&port->lock, flags);
+
+ /* calculate and set baud rate */
+ baud = uart_get_baud_rate(port, termios, old, 300, 115200);
+ baud = msm_set_baud_rate(port, baud);
+ if (tty_termios_baud_rate(termios))
+ tty_termios_encode_baud_rate(termios, baud, baud);
+
+ /* calculate parity */
+ mr = msm_read(port, UART_MR2);
+ mr &= ~UART_MR2_PARITY_MODE;
+ if (termios->c_cflag & PARENB) {
+ if (termios->c_cflag & PARODD)
+ mr |= UART_MR2_PARITY_MODE_ODD;
+ else if (termios->c_cflag & CMSPAR)
+ mr |= UART_MR2_PARITY_MODE_SPACE;
+ else
+ mr |= UART_MR2_PARITY_MODE_EVEN;
+ }
+
+ /* calculate bits per char */
+ mr &= ~UART_MR2_BITS_PER_CHAR;
+ switch (termios->c_cflag & CSIZE) {
+ case CS5:
+ mr |= UART_MR2_BITS_PER_CHAR_5;
+ break;
+ case CS6:
+ mr |= UART_MR2_BITS_PER_CHAR_6;
+ break;
+ case CS7:
+ mr |= UART_MR2_BITS_PER_CHAR_7;
+ break;
+ case CS8:
+ default:
+ mr |= UART_MR2_BITS_PER_CHAR_8;
+ break;
+ }
+
+ /* calculate stop bits */
+ mr &= ~(UART_MR2_STOP_BIT_LEN_ONE | UART_MR2_STOP_BIT_LEN_TWO);
+ if (termios->c_cflag & CSTOPB)
+ mr |= UART_MR2_STOP_BIT_LEN_TWO;
+ else
+ mr |= UART_MR2_STOP_BIT_LEN_ONE;
+
+ /* set parity, bits per char, and stop bit */
+ msm_write(port, mr, UART_MR2);
+
+ /* calculate and set hardware flow control */
+ mr = msm_read(port, UART_MR1);
+ mr &= ~(UART_MR1_CTS_CTL | UART_MR1_RX_RDY_CTL);
+ if (termios->c_cflag & CRTSCTS) {
+ mr |= UART_MR1_CTS_CTL;
+ mr |= UART_MR1_RX_RDY_CTL;
+ }
+ msm_write(port, mr, UART_MR1);
+
+ /* Configure status bits to ignore based on termio flags. */
+ port->read_status_mask = 0;
+ if (termios->c_iflag & INPCK)
+ port->read_status_mask |= UART_SR_PAR_FRAME_ERR;
+ if (termios->c_iflag & (BRKINT | PARMRK))
+ port->read_status_mask |= UART_SR_RX_BREAK;
+
+ uart_update_timeout(port, termios->c_cflag, baud);
+
+ spin_unlock_irqrestore(&port->lock, flags);
+}
+
+static const char *msm_type(struct uart_port *port)
+{
+ return "MSM";
+}
+
+static void msm_release_port(struct uart_port *port)
+{
+ struct platform_device *pdev = to_platform_device(port->dev);
+ struct resource *resource;
+
+ resource = platform_get_resource(pdev, IORESOURCE_MEM, 0);
+ if (!resource)
+ return;
+
+ release_mem_region(port->mapbase, resource_size(resource));
+ iounmap(port->membase);
+ port->membase = NULL;
+}
+
+static int msm_request_port(struct uart_port *port)
+{
+ struct platform_device *pdev = to_platform_device(port->dev);
+ struct resource *resource;
+ resource_size_t size;
+
+ resource = platform_get_resource(pdev, IORESOURCE_MEM, 0);
+ if (!resource)
+ return -ENXIO;
+ size = resource_size(resource);
+
+ if (!request_mem_region(port->mapbase, size, "msm_serial"))
+ return -EBUSY;
+
+ port->membase = ioremap(port->mapbase, size);
+ if (!port->membase) {
+ release_mem_region(port->mapbase, size);
+ return -EBUSY;
+ }
+
+ return 0;
+}
+
+static void msm_config_port(struct uart_port *port, int flags)
+{
+ if (flags & UART_CONFIG_TYPE) {
+ port->type = PORT_MSM;
+ msm_request_port(port);
+ }
+}
+
+static int msm_verify_port(struct uart_port *port, struct serial_struct *ser)
+{
+ if (ser->type != PORT_UNKNOWN && ser->type != PORT_MSM)
+ return -EINVAL;
+ if (port->irq != ser->irq)
+ return -EINVAL;
+ return 0;
+}
+
+static void msm_power(struct uart_port *port, unsigned int state,
+ unsigned int oldstate)
+{
+ struct msm_port *msm_port = to_msm_uart(port);
+
+ switch (state) {
+ case 0:
+ clk_enable(msm_port->clk);
+ break;
+ case 3:
+ clk_disable(msm_port->clk);
+ break;
+ default:
+ dev_err(port->dev, "Unknown PM state %d\n", state);
+ }
+}
+
+static struct uart_ops msm_uart_pops = {
+ .tx_empty = msm_tx_empty,
+ .set_mctrl = msm_set_mctrl,
+ .get_mctrl = msm_get_mctrl,
+ .stop_tx = msm_stop_tx,
+ .start_tx = msm_start_tx,
+ .stop_rx = msm_stop_rx,
+ .enable_ms = msm_enable_ms,
+ .break_ctl = msm_break_ctl,
+ .startup = msm_startup,
+ .shutdown = msm_shutdown,
+ .set_termios = msm_set_termios,
+ .type = msm_type,
+ .release_port = msm_release_port,
+ .request_port = msm_request_port,
+ .config_port = msm_config_port,
+ .verify_port = msm_verify_port,
+ .pm = msm_power,
+};
+
+static struct msm_port msm_uart_ports[] = {
+ {
+ .uart = {
+ .iotype = UPIO_MEM,
+ .ops = &msm_uart_pops,
+ .flags = UPF_BOOT_AUTOCONF,
+ .fifosize = 512,
+ .line = 0,
+ },
+ },
+ {
+ .uart = {
+ .iotype = UPIO_MEM,
+ .ops = &msm_uart_pops,
+ .flags = UPF_BOOT_AUTOCONF,
+ .fifosize = 512,
+ .line = 1,
+ },
+ },
+ {
+ .uart = {
+ .iotype = UPIO_MEM,
+ .ops = &msm_uart_pops,
+ .flags = UPF_BOOT_AUTOCONF,
+ .fifosize = 64,
+ .line = 2,
+ },
+ },
+};
+
+#define UART_NR ARRAY_SIZE(msm_uart_ports)
+
+static inline struct uart_port *get_port_from_line(unsigned int line)
+{
+ return &msm_uart_ports[line].uart;
+}
+
+#ifdef CONFIG_SERIAL_MSM_CONSOLE
+
+static void msm_console_putchar(struct uart_port *port, int c)
+{
+ while (!(msm_read(port, UART_SR) & UART_SR_TX_READY))
+ ;
+ msm_write(port, c, UART_TF);
+}
+
+static void msm_console_write(struct console *co, const char *s,
+ unsigned int count)
+{
+ struct uart_port *port;
+ struct msm_port *msm_port;
+
+ BUG_ON(co->index < 0 || co->index >= UART_NR);
+
+ port = get_port_from_line(co->index);
+ msm_port = to_msm_uart(port);
+
+ spin_lock(&port->lock);
+ uart_console_write(port, s, count, msm_console_putchar);
+ spin_unlock(&port->lock);
+}
+
+static int __init msm_console_setup(struct console *co, char *options)
+{
+ struct uart_port *port;
+ int baud, flow, bits, parity;
+
+ if (co->index >= UART_NR || co->index < 0)
+ return -ENXIO;
+
+ port = get_port_from_line(co->index);
+
+ if (!port->membase)
+ return -ENXIO;
+
+ port->cons = co;
+
+ msm_init_clock(port);
+
+ if (options)
+ uart_parse_options(options, &baud, &parity, &bits, &flow);
+
+ bits = 8;
+ parity = 'n';
+ flow = 'n';
+ msm_write(port, UART_MR2_BITS_PER_CHAR_8 | UART_MR2_STOP_BIT_LEN_ONE,
+ UART_MR2); /* 8N1 */
+
+ if (baud < 300 || baud > 115200)
+ baud = 115200;
+ msm_set_baud_rate(port, baud);
+
+ msm_reset(port);
+
+ return uart_set_options(port, co, baud, parity, bits, flow);
+}
+
+static struct uart_driver msm_uart_driver;
+
+static struct console msm_console = {
+ .name = "ttyMSM",
+ .write = msm_console_write,
+ .device = uart_console_device,
+ .setup = msm_console_setup,
+ .flags = CON_PRINTBUFFER,
+ .index = -1,
+ .data = &msm_uart_driver,
+};
+
+#define MSM_CONSOLE (&msm_console)
+
+#else
+#define MSM_CONSOLE NULL
+#endif
+
+static struct uart_driver msm_uart_driver = {
+ .owner = THIS_MODULE,
+ .driver_name = "msm_serial",
+ .dev_name = "ttyMSM",
+ .nr = UART_NR,
+ .cons = MSM_CONSOLE,
+};
+
+static int __init msm_serial_probe(struct platform_device *pdev)
+{
+ struct msm_port *msm_port;
+ struct resource *resource;
+ struct uart_port *port;
+
+ if (pdev->id < 0 || pdev->id >= UART_NR)
+ return -ENXIO;
+
+ port = get_port_from_line(pdev->id);
+ port->dev = &pdev->dev;
+ msm_port = to_msm_uart(port);
+
+ msm_port->clk = clk_get(&pdev->dev, "uart_clk");
+ if (IS_ERR(msm_port->clk))
+ return PTR_ERR(msm_port->clk);
+ port->uartclk = clk_get_rate(msm_port->clk);
+
+ resource = platform_get_resource(pdev, IORESOURCE_MEM, 0);
+ if (!resource)
+ return -ENXIO;
+ port->mapbase = resource->start;
+
+ port->irq = platform_get_irq(pdev, 0);
+ if (port->irq < 0)
+ return -ENXIO;
+
+ platform_set_drvdata(pdev, port);
+
+ return uart_add_one_port(&msm_uart_driver, port);
+}
+
+static int __exit msm_serial_remove(struct platform_device *pdev)
+{
+ struct msm_port *msm_port = platform_get_drvdata(pdev);
+
+ clk_put(msm_port->clk);
+
+ return 0;
+}
+
+static struct platform_driver msm_platform_driver = {
+ .probe = msm_serial_probe,
+ .remove = __exit_p(msm_serial_remove),
+ .driver = {
+ .name = "msm_serial",
+ .owner = THIS_MODULE,
+ },
+};
+
+static int __init msm_serial_init(void)
+{
+ int ret;
+
+ ret = uart_register_driver(&msm_uart_driver);
+ if (ret)
+ return ret;
+
+ ret = platform_driver_probe(&msm_platform_driver, msm_serial_probe);
+ if (ret)
+ uart_unregister_driver(&msm_uart_driver);
+
+ return ret;
+}
+
+static void __exit msm_serial_exit(void)
+{
+#ifdef CONFIG_SERIAL_MSM_CONSOLE
+ unregister_console(&msm_console);
+#endif
+ platform_driver_unregister(&msm_platform_driver);
+ uart_unregister_driver(&msm_uart_driver);
+}
+
+module_init(msm_serial_init);
+module_exit(msm_serial_exit);
+
+MODULE_AUTHOR("Robert Love <[email protected]>");
+MODULE_DESCRIPTION("Driver for msm7x serial device");
+MODULE_LICENSE("GPL");
diff --git a/drivers/serial/msm_serial.h b/drivers/serial/msm_serial.h
new file mode 100644
index 0000000..689f1fa
--- /dev/null
+++ b/drivers/serial/msm_serial.h
@@ -0,0 +1,117 @@
+/*
+ * drivers/serial/msm_serial.h
+ *
+ * Copyright (C) 2007 Google, Inc.
+ * Author: Robert Love <[email protected]>
+ *
+ * This software is licensed under the terms of the GNU General Public
+ * License version 2, as published by the Free Software Foundation, and
+ * may be copied, distributed, and modified under those terms.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ */
+
+#ifndef __DRIVERS_SERIAL_MSM_SERIAL_H
+#define __DRIVERS_SERIAL_MSM_SERIAL_H
+
+#define UART_MR1 0x0000
+
+#define UART_MR1_AUTO_RFR_LEVEL0 0x3F
+#define UART_MR1_AUTO_RFR_LEVEL1 0x3FF00
+#define UART_MR1_RX_RDY_CTL (1 << 7)
+#define UART_MR1_CTS_CTL (1 << 6)
+
+#define UART_MR2 0x0004
+#define UART_MR2_ERROR_MODE (1 << 6)
+#define UART_MR2_BITS_PER_CHAR 0x30
+#define UART_MR2_BITS_PER_CHAR_5 (0x0 << 4)
+#define UART_MR2_BITS_PER_CHAR_6 (0x1 << 4)
+#define UART_MR2_BITS_PER_CHAR_7 (0x2 << 4)
+#define UART_MR2_BITS_PER_CHAR_8 (0x3 << 4)
+#define UART_MR2_STOP_BIT_LEN_ONE (0x1 << 2)
+#define UART_MR2_STOP_BIT_LEN_TWO (0x3 << 2)
+#define UART_MR2_PARITY_MODE_NONE 0x0
+#define UART_MR2_PARITY_MODE_ODD 0x1
+#define UART_MR2_PARITY_MODE_EVEN 0x2
+#define UART_MR2_PARITY_MODE_SPACE 0x3
+#define UART_MR2_PARITY_MODE 0x3
+
+#define UART_CSR 0x0008
+#define UART_CSR_115200 0xFF
+#define UART_CSR_57600 0xEE
+#define UART_CSR_38400 0xDD
+#define UART_CSR_28800 0xCC
+#define UART_CSR_19200 0xBB
+#define UART_CSR_14400 0xAA
+#define UART_CSR_9600 0x99
+#define UART_CSR_4800 0x77
+#define UART_CSR_2400 0x55
+#define UART_CSR_1200 0x44
+#define UART_CSR_600 0x33
+#define UART_CSR_300 0x22
+
+#define UART_TF 0x000C
+
+#define UART_CR 0x0010
+#define UART_CR_CMD_NULL (0 << 4)
+#define UART_CR_CMD_RESET_RX (1 << 4)
+#define UART_CR_CMD_RESET_TX (2 << 4)
+#define UART_CR_CMD_RESET_ERR (3 << 4)
+#define UART_CR_CMD_RESET_BREAK_INT (4 << 4)
+#define UART_CR_CMD_START_BREAK (5 << 4)
+#define UART_CR_CMD_STOP_BREAK (6 << 4)
+#define UART_CR_CMD_RESET_CTS (7 << 4)
+#define UART_CR_CMD_PACKET_MODE (9 << 4)
+#define UART_CR_CMD_MODE_RESET (12 << 4)
+#define UART_CR_CMD_SET_RFR (13 << 4)
+#define UART_CR_CMD_RESET_RFR (14 << 4)
+#define UART_CR_TX_DISABLE (1 << 3)
+#define UART_CR_TX_ENABLE (1 << 3)
+#define UART_CR_RX_DISABLE (1 << 3)
+#define UART_CR_RX_ENABLE (1 << 3)
+
+#define UART_IMR 0x0014
+#define UART_IMR_TXLEV (1 << 0)
+#define UART_IMR_RXSTALE (1 << 3)
+#define UART_IMR_RXLEV (1 << 4)
+#define UART_IMR_DELTA_CTS (1 << 5)
+#define UART_IMR_CURRENT_CTS (1 << 6)
+
+#define UART_IPR_RXSTALE_LAST 0x20
+#define UART_IPR_STALE_LSB 0x1F
+#define UART_IPR_STALE_TIMEOUT_MSB 0x3FF80
+
+#define UART_IPR 0x0018
+#define UART_TFWR 0x001C
+#define UART_RFWR 0x0020
+#define UART_HCR 0x0024
+
+#define UART_MREG 0x0028
+#define UART_NREG 0x002C
+#define UART_DREG 0x0030
+#define UART_MNDREG 0x0034
+#define UART_IRDA 0x0038
+#define UART_MISR_MODE 0x0040
+#define UART_MISR_RESET 0x0044
+#define UART_MISR_EXPORT 0x0048
+#define UART_MISR_VAL 0x004C
+#define UART_TEST_CTRL 0x0050
+
+#define UART_SR 0x0008
+#define UART_SR_HUNT_CHAR (1 << 7)
+#define UART_SR_RX_BREAK (1 << 6)
+#define UART_SR_PAR_FRAME_ERR (1 << 5)
+#define UART_SR_OVERRUN (1 << 4)
+#define UART_SR_TX_EMPTY (1 << 3)
+#define UART_SR_TX_READY (1 << 2)
+#define UART_SR_RX_FULL (1 << 1)
+#define UART_SR_RX_READY (1 << 0)
+
+#define UART_RF 0x000C
+#define UART_MISR 0x0010
+#define UART_ISR 0x0014
+
+#endif /* __DRIVERS_SERIAL_MSM_SERIAL_H */
diff --git a/include/linux/serial_core.h b/include/linux/serial_core.h
index 6fd80c4..23d2fb0 100644
--- a/include/linux/serial_core.h
+++ b/include/linux/serial_core.h
@@ -171,6 +171,9 @@
/* Timberdale UART */
#define PORT_TIMBUART 87

+/* Qualcomm MSM SoCs */
+#define PORT_MSM 88
+
#ifdef __KERNEL__

#include <linux/compiler.h>
--
1.6.2.4

2009-06-18 00:34:45

by Brian Swetland

[permalink] [raw]
Subject: [PATCH 2/3] [ARM] msm: make debugging UART (for DEBUG_LL) configurable

Provides options to select one of the three "lowspeed" UARTs
on MSM7k SoCs for DEBUG_LL output from the zImage decompressor
and kernel.

Signed-off-by: Brian Swetland <[email protected]>
---
arch/arm/mach-msm/Kconfig | 24 ++++++++++++++++++++++++
arch/arm/mach-msm/include/mach/debug-macro.S | 24 +++++++++++++++++-------
arch/arm/mach-msm/include/mach/msm_iomap.h | 12 ++++++++++++
arch/arm/mach-msm/include/mach/uncompress.h | 7 +++++++
arch/arm/mach-msm/io.c | 3 +++
5 files changed, 63 insertions(+), 7 deletions(-)

diff --git a/arch/arm/mach-msm/Kconfig b/arch/arm/mach-msm/Kconfig
index d140abc..35f2a90 100644
--- a/arch/arm/mach-msm/Kconfig
+++ b/arch/arm/mach-msm/Kconfig
@@ -3,6 +3,30 @@ if ARCH_MSM
comment "MSM Board Type"
depends on ARCH_MSM

+config MSM_DEBUG_UART
+ int
+ default 1 if MSM_DEBUG_UART1
+ default 2 if MSM_DEBUG_UART2
+ default 3 if MSM_DEBUG_UART3
+
+choice
+ prompt "Debug UART"
+
+ default MSM_DEBUG_UART_NONE
+
+ config MSM_DEBUG_UART_NONE
+ bool "None"
+
+ config MSM_DEBUG_UART1
+ bool "UART1"
+
+ config MSM_DEBUG_UART2
+ bool "UART2"
+
+ config MSM_DEBUG_UART3
+ bool "UART3"
+endchoice
+
config MACH_HALIBUT
depends on ARCH_MSM
default y
diff --git a/arch/arm/mach-msm/include/mach/debug-macro.S b/arch/arm/mach-msm/include/mach/debug-macro.S
index 1db3c97..d48747e 100644
--- a/arch/arm/mach-msm/include/mach/debug-macro.S
+++ b/arch/arm/mach-msm/include/mach/debug-macro.S
@@ -14,15 +14,18 @@
*
*/

+
+
#include <mach/hardware.h>
#include <mach/msm_iomap.h>

+#ifdef CONFIG_MSM_DEBUG_UART
.macro addruart,rx
@ see if the MMU is enabled and select appropriate base address
mrc p15, 0, \rx, c1, c0
tst \rx, #1
- ldreq \rx, =MSM_UART1_PHYS
- movne \rx, #0
+ ldreq \rx, =MSM_DEBUG_UART_PHYS
+ ldrne \rx, =MSM_DEBUG_UART_BASE
.endm

.macro senduart,rd,rx
@@ -32,13 +35,20 @@

.macro waituart,rd,rx
@ wait for TX_READY
- teq \rx, #0
- bne 2f
-1: ldr \rd, [\rx, #0x08]
+1001: ldr \rd, [\rx, #0x08]
tst \rd, #0x04
- beq 1b
-2:
+ beq 1001b
+ .endm
+#else
+ .macro addruart,rx
+ .endm
+
+ .macro senduart,rd,rx
+ .endm
+
+ .macro waituart,rd,rx
.endm
+#endif

.macro busyuart,rd,rx
.endm
diff --git a/arch/arm/mach-msm/include/mach/msm_iomap.h b/arch/arm/mach-msm/include/mach/msm_iomap.h
index 2f7b4c8..9dae1a9 100644
--- a/arch/arm/mach-msm/include/mach/msm_iomap.h
+++ b/arch/arm/mach-msm/include/mach/msm_iomap.h
@@ -84,6 +84,18 @@
#define MSM_UART3_PHYS 0xA9C00000
#define MSM_UART3_SIZE SZ_4K

+#ifdef CONFIG_MSM_DEBUG_UART
+#define MSM_DEBUG_UART_BASE 0xE1000000
+#if CONFIG_MSM_DEBUG_UART == 1
+#define MSM_DEBUG_UART_PHYS MSM_UART1_PHYS
+#elif CONFIG_MSM_DEBUG_UART == 2
+#define MSM_DEBUG_UART_PHYS MSM_UART2_PHYS
+#elif CONFIG_MSM_DEBUG_UART == 3
+#define MSM_DEBUG_UART_PHYS MSM_UART3_PHYS
+#endif
+#define MSM_DEBUG_UART_SIZE SZ_4K
+#endif
+
#define MSM_SDC1_PHYS 0xA0400000
#define MSM_SDC1_SIZE SZ_4K

diff --git a/arch/arm/mach-msm/include/mach/uncompress.h b/arch/arm/mach-msm/include/mach/uncompress.h
index 026e895..d94292c 100644
--- a/arch/arm/mach-msm/include/mach/uncompress.h
+++ b/arch/arm/mach-msm/include/mach/uncompress.h
@@ -16,9 +16,16 @@
#ifndef __ASM_ARCH_MSM_UNCOMPRESS_H

#include "hardware.h"
+#include "linux/io.h"
+#include "mach/msm_iomap.h"

static void putc(int c)
{
+#if defined(MSM_DEBUG_UART_PHYS)
+ unsigned base = MSM_DEBUG_UART_PHYS;
+ while (!(readl(base + 0x08) & 0x04)) ;
+ writel(c, base + 0x0c);
+#endif
}

static inline void flush(void)
diff --git a/arch/arm/mach-msm/io.c b/arch/arm/mach-msm/io.c
index 6e7692f..1c5e7da 100644
--- a/arch/arm/mach-msm/io.c
+++ b/arch/arm/mach-msm/io.c
@@ -42,6 +42,9 @@ static struct map_desc msm_io_desc[] __initdata = {
MSM_DEVICE(GPIO1),
MSM_DEVICE(GPIO2),
MSM_DEVICE(CLK_CTL),
+#ifdef CONFIG_MSM_DEBUG_UART
+ MSM_DEVICE(DEBUG_UART),
+#endif
{
.virtual = (unsigned long) MSM_SHARED_RAM_BASE,
.pfn = __phys_to_pfn(MSM_SHARED_RAM_PHYS),
--
1.6.2.4

2009-06-18 00:34:56

by Brian Swetland

[permalink] [raw]
Subject: [PATCH 3/3] [ARM] msm: add minimal board file for HTC Dream device

This is just enough to get the device booting and serial console
working. Sufficient for debugging further MSM7k/Dream Support.
This will support HTC Dream / T-Mobile G1 / Android ADP1 (which
are all the same hardware, known as "trout" to the ARM machine
database).

Signed-off-by: Brian Swetland <[email protected]>
---
arch/arm/mach-msm/Kconfig | 6 +++
arch/arm/mach-msm/Makefile | 1 +
arch/arm/mach-msm/board-dream.c | 84 +++++++++++++++++++++++++++++++++++++++
arch/arm/mach-msm/board-dream.h | 5 ++
4 files changed, 96 insertions(+), 0 deletions(-)
create mode 100644 arch/arm/mach-msm/board-dream.c
create mode 100644 arch/arm/mach-msm/board-dream.h

diff --git a/arch/arm/mach-msm/Kconfig b/arch/arm/mach-msm/Kconfig
index 35f2a90..f780086 100644
--- a/arch/arm/mach-msm/Kconfig
+++ b/arch/arm/mach-msm/Kconfig
@@ -34,4 +34,10 @@ config MACH_HALIBUT
help
Support for the Qualcomm SURF7201A eval board.

+config MACH_TROUT
+ default y
+ bool "HTC Dream (aka trout)"
+ help
+ Support for the HTC Dream, T-Mobile G1, Android ADP1 devices.
+
endif
diff --git a/arch/arm/mach-msm/Makefile b/arch/arm/mach-msm/Makefile
index 1aa4700..91e6f5c 100644
--- a/arch/arm/mach-msm/Makefile
+++ b/arch/arm/mach-msm/Makefile
@@ -6,3 +6,4 @@ obj-y += clock.o clock-7x01a.o

obj-$(CONFIG_MACH_HALIBUT) += board-halibut.o

+obj-$(CONFIG_MACH_TROUT) += board-dream.o
diff --git a/arch/arm/mach-msm/board-dream.c b/arch/arm/mach-msm/board-dream.c
new file mode 100644
index 0000000..6eae7e3
--- /dev/null
+++ b/arch/arm/mach-msm/board-dream.c
@@ -0,0 +1,84 @@
+/* linux/arch/arm/mach-msm/board-dream.c
+ *
+ * Copyright (C) 2009 Google, Inc.
+ * Author: Brian Swetland <[email protected]>
+ *
+ * This software is licensed under the terms of the GNU General Public
+ * License version 2, as published by the Free Software Foundation, and
+ * may be copied, distributed, and modified under those terms.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ */
+
+#include <linux/kernel.h>
+#include <linux/init.h>
+#include <linux/platform_device.h>
+
+#include <asm/mach-types.h>
+#include <asm/mach/arch.h>
+#include <asm/mach/map.h>
+
+#include <mach/board.h>
+#include <mach/hardware.h>
+#include <mach/msm_iomap.h>
+
+#include "devices.h"
+#include "board-dream.h"
+
+static struct platform_device *devices[] __initdata = {
+ &msm_device_uart3,
+ &msm_device_smd,
+ &msm_device_nand,
+ &msm_device_hsusb,
+ &msm_device_i2c,
+};
+
+extern struct sys_timer msm_timer;
+
+static void __init trout_init_irq(void)
+{
+ msm_init_irq();
+}
+
+static void __init trout_init(void)
+{
+ platform_add_devices(devices, ARRAY_SIZE(devices));
+}
+
+static struct map_desc trout_io_desc[] __initdata = {
+ {
+ .virtual = TROUT_CPLD_BASE,
+ .pfn = __phys_to_pfn(TROUT_CPLD_START),
+ .length = TROUT_CPLD_SIZE,
+ .type = MT_DEVICE_NONSHARED
+ }
+};
+
+static void __init trout_map_io(void)
+{
+ msm_map_common_io();
+ iotable_init(trout_io_desc, ARRAY_SIZE(trout_io_desc));
+
+#ifdef CONFIG_MSM_DEBUG_UART3
+ /* route UART3 to the "H2W" extended usb connector */
+ writeb(0x80, TROUT_CPLD_BASE + 0x00);
+#endif
+
+ msm_clock_init();
+}
+
+MACHINE_START(TROUT, "HTC Dream")
+#ifdef CONFIG_MSM_DEBUG_UART
+ .phys_io = MSM_DEBUG_UART_PHYS,
+ .io_pg_offst = ((MSM_DEBUG_UART_BASE) >> 18) & 0xfffc,
+#endif
+ .boot_params = 0x10000100,
+ .map_io = trout_map_io,
+ .init_irq = trout_init_irq,
+ .init_machine = trout_init,
+ .timer = &msm_timer,
+MACHINE_END
diff --git a/arch/arm/mach-msm/board-dream.h b/arch/arm/mach-msm/board-dream.h
new file mode 100644
index 0000000..4f345a5
--- /dev/null
+++ b/arch/arm/mach-msm/board-dream.h
@@ -0,0 +1,5 @@
+
+#define TROUT_CPLD_BASE 0xE8100000
+#define TROUT_CPLD_START 0x98000000
+#define TROUT_CPLD_SIZE SZ_4K
+
--
1.6.2.4

2009-06-18 02:03:23

by Geunsik Lim

[permalink] [raw]
Subject: Re: [PATCH 3/3] [ARM] msm: add minimal board file for HTC Dream device

On Thu, Jun 18, 2009 at 9:31 AM, Brian Swetland<[email protected]> wrote:
> This is just enough to get the device booting and serial console
> working.  Sufficient for debugging further MSM7k/Dream Support.
> This will support HTC Dream / T-Mobile G1 / Android ADP1 (which
> are all the same hardware, known as "trout" to the ARM machine
> database).
Hi Brian,
I have one silly question.
I still not understand "trout" meaning with your description.

> +config MACH_TROUT
> +       default y
> +       bool "HTC Dream (aka trout)"
> +       help
> +         Support for the HTC Dream, T-Mobile G1, Android ADP1 devices.
> +
"trout" word just means HTC Dream Model. Is it right?
Thks,

--
Regards,
GeunSik Lim ( Samsung Electronics )
Blog : http://blog.naver.com/invain/
e-Mail: [email protected]
[email protected] , [email protected]

2009-06-18 02:44:23

by Brian Swetland

[permalink] [raw]
Subject: Re: [PATCH 3/3] [ARM] msm: add minimal board file for HTC Dream device

On Wed, Jun 17, 2009 at 6:56 PM, GeunSik Lim<[email protected]> wrote:
> On Thu, Jun 18, 2009 at 9:31 AM, Brian Swetland<[email protected]> wrote:
>> This is just enough to get the device booting and serial console
>> working.  Sufficient for debugging further MSM7k/Dream Support.
>> This will support HTC Dream / T-Mobile G1 / Android ADP1 (which
>> are all the same hardware, known as "trout" to the ARM machine
>> database).
> Hi Brian,
> I have one silly question.
> I still not understand "trout" meaning with your description.
>
>> +config MACH_TROUT
>> +       default y
>> +       bool "HTC Dream (aka trout)"
>> +       help
>> +         Support for the HTC Dream, T-Mobile G1, Android ADP1 devices.
>> +
> "trout" word just means HTC Dream Model. Is it right?

Yes -- this is the ARM linux kernel machine ID for this hardware:
http://www.arm.linux.org.uk/developer/machines/list.php?id=1440

Brian

2009-06-18 09:19:27

by Alan

[permalink] [raw]
Subject: Re: [PATCH 1/3] [ARM] msm_serial: serial driver for MSM7K onboard serial peripheral.

On Wed, 17 Jun 2009 17:31:13 -0700
Brian Swetland <[email protected]> wrote:

> From: Robert Love <[email protected]>
>
> Provides support for the "lowspeed" UARTs on the MSM7k and QSD8k
> family of SoCs from Qualcomm. Serial console support included.
>
> Signed-off-by: Robert Love <[email protected]>
> Signed-off-by: Brian Swetland <[email protected]>
> Acked-by: Pavel Machek <[email protected]>

If you fold other peoples patches into something please preserve the
authorship data and preferably keep the two patches separated as it
otherwise causes merge problems if stuff (eg the serial patches) goes via
two trees at once.

At the moment the ttydev tree has
-> your original -> my (intel's I guess) fixes ->

and if the updated one also went in via the arm tree git can't always
figure out what is going on.

If its only going by one path and you know that then just adding an
additional note on the authorship of updates is fine but this being
serial/tty and ARM is likely to hit both trees.

Alan

2009-06-18 10:26:34

by Pavel Machek

[permalink] [raw]
Subject: Re: [PATCH 2/3] [ARM] msm: make debugging UART (for DEBUG_LL) configurable

On Wed 2009-06-17 17:31:14, Brian Swetland wrote:
> Provides options to select one of the three "lowspeed" UARTs
> on MSM7k SoCs for DEBUG_LL output from the zImage decompressor
> and kernel.
>
> Signed-off-by: Brian Swetland <[email protected]>

Acked-by: Pavel Machek <[email protected]>

--
(english) http://www.livejournal.com/~pavelmachek
(cesky, pictures) http://atrey.karlin.mff.cuni.cz/~pavel/picture/horses/blog.html

2009-06-18 10:26:58

by Pavel Machek

[permalink] [raw]
Subject: Re: [PATCH 3/3] [ARM] msm: add minimal board file for HTC Dream device

On Wed 2009-06-17 17:31:15, Brian Swetland wrote:
> This is just enough to get the device booting and serial console
> working. Sufficient for debugging further MSM7k/Dream Support.
> This will support HTC Dream / T-Mobile G1 / Android ADP1 (which
> are all the same hardware, known as "trout" to the ARM machine
> database).
>
> Signed-off-by: Brian Swetland <[email protected]>

Acked-by: Pavel Machek <[email protected]>

--
(english) http://www.livejournal.com/~pavelmachek
(cesky, pictures) http://atrey.karlin.mff.cuni.cz/~pavel/picture/horses/blog.html

2009-06-18 14:01:57

by Geunsik Lim

[permalink] [raw]
Subject: Re: [PATCH 3/3] [ARM] msm: add minimal board file for HTC Dream device

On Thu, Jun 18, 2009 at 11:44 AM, Brian Swetland<[email protected]> wrote:
> On Wed, Jun 17, 2009 at 6:56 PM, GeunSik Lim<[email protected]> wrote:
>> On Thu, Jun 18, 2009 at 9:31 AM, Brian Swetland<[email protected]> wrote:
>>> This is just enough to get the device booting and serial console
>>> working.  Sufficient for debugging further MSM7k/Dream Support.
>>> This will support HTC Dream / T-Mobile G1 / Android ADP1 (which
>>> are all the same hardware, known as "trout" to the ARM machine
>>> database).
>> Hi Brian,
>> I have one silly question.
>> I still not understand "trout" meaning with your description.
>>
>>> +config MACH_TROUT
>>> +       default y
>>> +       bool "HTC Dream (aka trout)"
>>> +       help
>>> +         Support for the HTC Dream, T-Mobile G1, Android ADP1 devices.
>>> +
>> "trout" word just means HTC Dream Model. Is it right?
>
> Yes -- this is the ARM linux kernel machine ID for this hardware:
> http://www.arm.linux.org.uk/developer/machines/list.php?id=1440
>
> Brian
>
Looks good to me.
Reviewed-by: GeunSik Lim <[email protected]>


--
Regards,
GeunSik Lim ( Samsung Electronics )
Blog : http://blog.naver.com/invain/
e-Mail: [email protected]
[email protected] , [email protected]

2009-06-18 19:29:53

by Brian Swetland

[permalink] [raw]
Subject: Re: [PATCH 1/3] [ARM] msm_serial: serial driver for MSM7K onboard serial peripheral.

On Thu, Jun 18, 2009 at 2:20 AM, Alan Cox<[email protected]> wrote:
> On Wed, 17 Jun 2009 17:31:13 -0700
> Brian Swetland <[email protected]> wrote:
>
>> From: Robert Love <[email protected]>
>>
>> Provides support for the "lowspeed" UARTs on the MSM7k and QSD8k
>> family of SoCs from Qualcomm.  Serial console support included.
>>
>> Signed-off-by: Robert Love <[email protected]>
>> Signed-off-by: Brian Swetland <[email protected]>
>> Acked-by: Pavel Machek <[email protected]>
>
> If you fold other peoples patches into something please preserve the
> authorship data and preferably keep the two patches separated as it
> otherwise causes merge problems if stuff (eg the serial patches) goes via
> two trees at once.

Ah, sorry about that -- I can resend the revised patch that your patch
applies against (but without your changes merged in). Previously, for
the ARM stuff I got the impression that a single patch folding small
changes in was preferred, but I may have misunderstood the workflow.

> At the moment the ttydev tree has
>        -> your original -> my (intel's I guess) fixes ->
>
> and if the updated one also went in via the arm tree git can't always
> figure out what is going on.
>
> If its only going by one path and you know that then just adding an
> additional note on the authorship of updates is fine but this being
> serial/tty and ARM is likely to hit both trees.
>
> Alan
>