* [PATCH 00/14] Serial : sc26xx - generalize and support SC2892
@ 2010-02-25 13:34 Martin Fuzzey
2010-02-25 13:34 ` [PATCH V2 01/14] Serial: Enable build of sc26xx driver for embedded platforms Martin Fuzzey
` (13 more replies)
0 siblings, 14 replies; 15+ messages in thread
From: Martin Fuzzey @ 2010-02-25 13:34 UTC (permalink / raw)
To: linux-serial, tsbogend
This patch series generalizes the SC26xx driver to all embedded platforms
(in addition to the current SNI_RM) and adds support for the SC2892 DUART.
This chip is quite similar to the SC2692 but has more baud rates
and bigger FIFOs.
Changes since V1:
Add patch: Use device name ttySC0 as per Documentation/devices.txt
Add Acked-By: Thomas Bogendoerfer <tsbogend@alpha.franken.de>
Rename driver to sc2xxx
^ permalink raw reply [flat|nested] 15+ messages in thread
* [PATCH V2 01/14] Serial: Enable build of sc26xx driver for embedded platforms
2010-02-25 13:34 [PATCH 00/14] Serial : sc26xx - generalize and support SC2892 Martin Fuzzey
@ 2010-02-25 13:34 ` Martin Fuzzey
2010-02-25 13:35 ` [PATCH V2 02/14] Serial: sc26xx fix build errors Martin Fuzzey
` (12 subsequent siblings)
13 siblings, 0 replies; 15+ messages in thread
From: Martin Fuzzey @ 2010-02-25 13:34 UTC (permalink / raw)
To: linux-serial, tsbogend
Acked-By: Thomas Bogendoerfer <tsbogend@alpha.franken.de>
Signed-off-by: Martin Fuzzey <mfuzzey@gmail.com>
---
drivers/serial/Kconfig | 2 +-
1 files changed, 1 insertions(+), 1 deletions(-)
diff --git a/drivers/serial/Kconfig b/drivers/serial/Kconfig
index 9ff47db..10bd461 100644
--- a/drivers/serial/Kconfig
+++ b/drivers/serial/Kconfig
@@ -1395,7 +1395,7 @@ config SERIAL_QE
config SERIAL_SC26XX
tristate "SC2681/SC2692 serial port support"
- depends on SNI_RM
+ depends on SNI_RM || EMBEDDED
select SERIAL_CORE
help
This is a driver for the onboard serial ports of
^ permalink raw reply related [flat|nested] 15+ messages in thread
* [PATCH V2 02/14] Serial: sc26xx fix build errors.
2010-02-25 13:34 [PATCH 00/14] Serial : sc26xx - generalize and support SC2892 Martin Fuzzey
2010-02-25 13:34 ` [PATCH V2 01/14] Serial: Enable build of sc26xx driver for embedded platforms Martin Fuzzey
@ 2010-02-25 13:35 ` Martin Fuzzey
2010-02-25 13:35 ` [PATCH V2 03/14] Serial: sc26xx - use interrupt trigger flags from resources Martin Fuzzey
` (11 subsequent siblings)
13 siblings, 0 replies; 15+ messages in thread
From: Martin Fuzzey @ 2010-02-25 13:35 UTC (permalink / raw)
To: linux-serial, tsbogend
Add missing include.
Use __devexit rather than __exit to allow building in kernel.
Acked-By: Thomas Bogendoerfer <tsbogend@alpha.franken.de>
Signed-off-by: Martin Fuzzey <mfuzzey@gmail.com>
---
drivers/serial/sc26xx.c | 3 ++-
1 files changed, 2 insertions(+), 1 deletions(-)
diff --git a/drivers/serial/sc26xx.c b/drivers/serial/sc26xx.c
index 75038ad..dc09682 100644
--- a/drivers/serial/sc26xx.c
+++ b/drivers/serial/sc26xx.c
@@ -20,6 +20,7 @@
#include <linux/init.h>
#include <linux/platform_device.h>
#include <linux/irq.h>
+#include <linux/io.h>
#if defined(CONFIG_MAGIC_SYSRQ)
#define SUPPORT_SYSRQ
@@ -709,7 +710,7 @@ out_free_port:
}
-static int __exit sc26xx_driver_remove(struct platform_device *dev)
+static int __devexit sc26xx_driver_remove(struct platform_device *dev)
{
struct uart_sc26xx_port *up = dev_get_drvdata(&dev->dev);
^ permalink raw reply related [flat|nested] 15+ messages in thread
* [PATCH V2 03/14] Serial: sc26xx - use interrupt trigger flags from resources.
2010-02-25 13:34 [PATCH 00/14] Serial : sc26xx - generalize and support SC2892 Martin Fuzzey
2010-02-25 13:34 ` [PATCH V2 01/14] Serial: Enable build of sc26xx driver for embedded platforms Martin Fuzzey
2010-02-25 13:35 ` [PATCH V2 02/14] Serial: sc26xx fix build errors Martin Fuzzey
@ 2010-02-25 13:35 ` Martin Fuzzey
2010-02-25 13:35 ` [PATCH V2 04/14] Serial: sc26xx - add accessor function for driver data Martin Fuzzey
` (10 subsequent siblings)
13 siblings, 0 replies; 15+ messages in thread
From: Martin Fuzzey @ 2010-02-25 13:35 UTC (permalink / raw)
To: linux-serial, tsbogend
Allows platform resources to specify interrupt flags.
Acked-By: Thomas Bogendoerfer <tsbogend@alpha.franken.de>
Signed-off-by: Martin Fuzzey <mfuzzey@gmail.com>
---
drivers/serial/sc26xx.c | 11 ++++++++---
1 files changed, 8 insertions(+), 3 deletions(-)
diff --git a/drivers/serial/sc26xx.c b/drivers/serial/sc26xx.c
index dc09682..ca74bf6 100644
--- a/drivers/serial/sc26xx.c
+++ b/drivers/serial/sc26xx.c
@@ -631,7 +631,7 @@ static void __devinit sc26xx_init_masks(struct uart_sc26xx_port *up,
static int __devinit sc26xx_probe(struct platform_device *dev)
{
- struct resource *res;
+ struct resource *res, *irq_res;
struct uart_sc26xx_port *up;
unsigned int *sc26xx_data = dev->dev.platform_data;
int err;
@@ -640,6 +640,10 @@ static int __devinit sc26xx_probe(struct platform_device *dev)
if (!res)
return -ENODEV;
+ irq_res = platform_get_resource(dev, IORESOURCE_IRQ, 0);
+ if (!irq_res)
+ return -ENXIO;
+
up = kzalloc(sizeof *up, GFP_KERNEL);
if (unlikely(!up))
return -ENOMEM;
@@ -652,7 +656,7 @@ static int __devinit sc26xx_probe(struct platform_device *dev)
up->port[0].mapbase = res->start;
up->port[0].membase = ioremap_nocache(up->port[0].mapbase, 0x40);
up->port[0].iotype = UPIO_MEM;
- up->port[0].irq = platform_get_irq(dev, 0);
+ up->port[0].irq = irq_res->start;
up->port[0].dev = &dev->dev;
@@ -688,7 +692,8 @@ static int __devinit sc26xx_probe(struct platform_device *dev)
if (err)
goto out_remove_port0;
- err = request_irq(up->port[0].irq, sc26xx_interrupt, 0, "sc26xx", up);
+ err = request_irq(up->port[0].irq, sc26xx_interrupt,
+ irq_res->flags & IRQF_TRIGGER_MASK, "sc26xx", up);
if (err)
goto out_remove_ports;
^ permalink raw reply related [flat|nested] 15+ messages in thread
* [PATCH V2 04/14] Serial: sc26xx - add accessor function for driver data.
2010-02-25 13:34 [PATCH 00/14] Serial : sc26xx - generalize and support SC2892 Martin Fuzzey
` (2 preceding siblings ...)
2010-02-25 13:35 ` [PATCH V2 03/14] Serial: sc26xx - use interrupt trigger flags from resources Martin Fuzzey
@ 2010-02-25 13:35 ` Martin Fuzzey
2010-02-25 13:35 ` [PATCH V2 05/14] Serial: sc26xx - refactor register access Martin Fuzzey
` (9 subsequent siblings)
13 siblings, 0 replies; 15+ messages in thread
From: Martin Fuzzey @ 2010-02-25 13:35 UTC (permalink / raw)
To: linux-serial, tsbogend
Extract container_of and port -= line to a helper function
to avoid slightly opaque modification of port pointer.
Acked-By: Thomas Bogendoerfer <tsbogend@alpha.franken.de>
Signed-off-by: Martin Fuzzey <mfuzzey@gmail.com>
---
drivers/serial/sc26xx.c | 31 ++++++++++++-------------------
1 files changed, 12 insertions(+), 19 deletions(-)
diff --git a/drivers/serial/sc26xx.c b/drivers/serial/sc26xx.c
index ca74bf6..dc47d4f 100644
--- a/drivers/serial/sc26xx.c
+++ b/drivers/serial/sc26xx.c
@@ -95,6 +95,12 @@ struct uart_sc26xx_port {
#define IMR_RXRDY (1 << 1)
#define IMR_TXRDY (1 << 0)
+static struct uart_sc26xx_port *driver_info(struct uart_port *port)
+{
+ port -= port->line;
+ return container_of(port, struct uart_sc26xx_port, port[0]);
+}
+
/* access port register */
static inline u8 read_sc_port(struct uart_port *p, u8 reg)
{
@@ -111,25 +117,17 @@ static inline void write_sc_port(struct uart_port *p, u8 reg, u8 val)
static void sc26xx_enable_irq(struct uart_port *port, int mask)
{
- struct uart_sc26xx_port *up;
- int line = port->line;
-
- port -= line;
- up = container_of(port, struct uart_sc26xx_port, port[0]);
+ struct uart_sc26xx_port *up = driver_info(port);
- up->imr |= mask << (line * 4);
+ up->imr |= mask << (port->line * 4);
WRITE_SC(port, IMR, up->imr);
}
static void sc26xx_disable_irq(struct uart_port *port, int mask)
{
- struct uart_sc26xx_port *up;
- int line = port->line;
-
- port -= line;
- up = container_of(port, struct uart_sc26xx_port, port[0]);
+ struct uart_sc26xx_port *up = driver_info(port);
- up->imr &= ~(mask << (line * 4));
+ up->imr &= ~(mask << (port->line * 4));
WRITE_SC(port, IMR, up->imr);
}
@@ -257,12 +255,9 @@ static unsigned int sc26xx_tx_empty(struct uart_port *port)
/* port->lock held by caller. */
static void sc26xx_set_mctrl(struct uart_port *port, unsigned int mctrl)
{
- struct uart_sc26xx_port *up;
+ struct uart_sc26xx_port *up = driver_info(port);
int line = port->line;
- port -= line;
- up = container_of(port, struct uart_sc26xx_port, port[0]);
-
if (up->dtr_mask[line]) {
if (mctrl & TIOCM_DTR)
WRITE_SC(port, OPR_SET, up->dtr_mask[line]);
@@ -280,13 +275,11 @@ static void sc26xx_set_mctrl(struct uart_port *port, unsigned int mctrl)
/* port->lock is held by caller and interrupts are disabled. */
static unsigned int sc26xx_get_mctrl(struct uart_port *port)
{
- struct uart_sc26xx_port *up;
+ struct uart_sc26xx_port *up = driver_info(port);
int line = port->line;
unsigned int mctrl = TIOCM_DSR | TIOCM_CTS | TIOCM_CAR;
u8 ipr;
- port -= line;
- up = container_of(port, struct uart_sc26xx_port, port[0]);
ipr = READ_SC(port, IPR) ^ 0xff;
if (up->dsr_mask[line]) {
^ permalink raw reply related [flat|nested] 15+ messages in thread
* [PATCH V2 05/14] Serial: sc26xx - refactor register access
2010-02-25 13:34 [PATCH 00/14] Serial : sc26xx - generalize and support SC2892 Martin Fuzzey
` (3 preceding siblings ...)
2010-02-25 13:35 ` [PATCH V2 04/14] Serial: sc26xx - add accessor function for driver data Martin Fuzzey
@ 2010-02-25 13:35 ` Martin Fuzzey
2010-02-25 13:35 ` [PATCH V2 06/14] Serial: sc26xx simplify timeout calculation Martin Fuzzey
` (8 subsequent siblings)
13 siblings, 0 replies; 15+ messages in thread
From: Martin Fuzzey @ 2010-02-25 13:35 UTC (permalink / raw)
To: linux-serial, tsbogend
Add line number based register accessor functions.
Add command function which implements the inter command
delay required by datasheet.
Acked-By: Thomas Bogendoerfer <tsbogend@alpha.franken.de>
Signed-off-by: Martin Fuzzey <mfuzzey@gmail.com>
---
drivers/serial/sc26xx.c | 44 +++++++++++++++++++++++++++++++++++---------
1 files changed, 35 insertions(+), 9 deletions(-)
diff --git a/drivers/serial/sc26xx.c b/drivers/serial/sc26xx.c
index dc47d4f..1b47443 100644
--- a/drivers/serial/sc26xx.c
+++ b/drivers/serial/sc26xx.c
@@ -102,19 +102,45 @@ static struct uart_sc26xx_port *driver_info(struct uart_port *port)
}
/* access port register */
+static inline u8 read_sc_line(struct uart_port *p, int line, u8 reg)
+{
+ return readb(p->membase + line * 0x20 + reg);
+}
+
static inline u8 read_sc_port(struct uart_port *p, u8 reg)
{
- return readb(p->membase + p->line * 0x20 + reg);
+ return read_sc_line(p, p->line, reg);
+}
+
+static inline void write_sc_line(struct uart_port *p, int line, u8 reg, u8 val)
+{
+ writeb(val, p->membase + line * 0x20 + reg);
}
static inline void write_sc_port(struct uart_port *p, u8 reg, u8 val)
{
- writeb(val, p->membase + p->line * 0x20 + reg);
+ write_sc_line(p, p->line, reg, val);
}
#define READ_SC_PORT(p, r) read_sc_port(p, RD_PORT_##r)
#define WRITE_SC_PORT(p, r, v) write_sc_port(p, WR_PORT_##r, v)
+static void write_cmd_line(struct uart_port *port, int line, u8 cmd)
+{
+ int i;
+
+ write_sc_line(port, line, WR_PORT_CR, cmd);
+
+ /* According to data sheet require 3 NOPs before next command */
+ for (i = 0; i < 3; i++)
+ write_sc_line(port, line, WR_PORT_CR, 0);
+}
+
+static inline void write_cmd_port(struct uart_port *port, u8 cmd)
+{
+ write_cmd_line(port, port->line, cmd);
+}
+
static void sc26xx_enable_irq(struct uart_port *port, int mask)
{
struct uart_sc26xx_port *up = driver_info(port);
@@ -337,9 +363,9 @@ static void sc26xx_enable_ms(struct uart_port *port)
static void sc26xx_break_ctl(struct uart_port *port, int break_state)
{
if (break_state == -1)
- WRITE_SC_PORT(port, CR, CR_STRT_BRK);
+ write_cmd_port(port, CR_STRT_BRK);
else
- WRITE_SC_PORT(port, CR, CR_STOP_BRK);
+ write_cmd_port(port, CR_STOP_BRK);
}
/* port->lock is not held. */
@@ -349,8 +375,8 @@ static int sc26xx_startup(struct uart_port *port)
WRITE_SC(port, OPCR, 0);
/* reset tx and rx */
- WRITE_SC_PORT(port, CR, CR_RES_RX);
- WRITE_SC_PORT(port, CR, CR_RES_TX);
+ write_cmd_port(port, CR_RES_RX);
+ write_cmd_port(port, CR_RES_TX);
/* start rx/tx */
WRITE_SC_PORT(port, CR, CR_ENA_TX | CR_ENA_RX);
@@ -464,7 +490,7 @@ static void sc26xx_set_termios(struct uart_port *port, struct ktermios *termios,
break;
}
- WRITE_SC_PORT(port, CR, CR_RES_MR);
+ write_cmd_port(port, CR_RES_MR);
WRITE_SC_PORT(port, MRx, mr1);
WRITE_SC_PORT(port, MRx, mr2);
@@ -472,8 +498,8 @@ static void sc26xx_set_termios(struct uart_port *port, struct ktermios *termios,
WRITE_SC_PORT(port, CSR, csr);
/* reset tx and rx */
- WRITE_SC_PORT(port, CR, CR_RES_RX);
- WRITE_SC_PORT(port, CR, CR_RES_TX);
+ write_cmd_port(port, CR_RES_RX);
+ write_cmd_port(port, CR_RES_TX);
WRITE_SC_PORT(port, CR, CR_ENA_TX | CR_ENA_RX);
while ((READ_SC_PORT(port, SR) & ((1 << 3) | (1 << 2))) != 0xc)
^ permalink raw reply related [flat|nested] 15+ messages in thread
* [PATCH V2 06/14] Serial: sc26xx simplify timeout calculation
2010-02-25 13:34 [PATCH 00/14] Serial : sc26xx - generalize and support SC2892 Martin Fuzzey
` (4 preceding siblings ...)
2010-02-25 13:35 ` [PATCH V2 05/14] Serial: sc26xx - refactor register access Martin Fuzzey
@ 2010-02-25 13:35 ` Martin Fuzzey
2010-02-25 13:35 ` [PATCH V2 07/14] Serial: sc26xx - simplify port initialisation Martin Fuzzey
` (7 subsequent siblings)
13 siblings, 0 replies; 15+ messages in thread
From: Martin Fuzzey @ 2010-02-25 13:35 UTC (permalink / raw)
To: linux-serial, tsbogend
We already have the baud rate - no need to calculate it again.
Acked-By: Thomas Bogendoerfer <tsbogend@alpha.franken.de>
Signed-off-by: Martin Fuzzey <mfuzzey@gmail.com>
---
drivers/serial/sc26xx.c | 5 +----
1 files changed, 1 insertions(+), 4 deletions(-)
diff --git a/drivers/serial/sc26xx.c b/drivers/serial/sc26xx.c
index 1b47443..316d110 100644
--- a/drivers/serial/sc26xx.c
+++ b/drivers/serial/sc26xx.c
@@ -401,7 +401,6 @@ static void sc26xx_set_termios(struct uart_port *port, struct ktermios *termios,
struct ktermios *old)
{
unsigned int baud = uart_get_baud_rate(port, termios, old, 0, 4000000);
- unsigned int quot = uart_get_divisor(port, baud);
unsigned int iflag, cflag;
unsigned long flags;
u8 mr1, mr2, csr;
@@ -505,9 +504,7 @@ static void sc26xx_set_termios(struct uart_port *port, struct ktermios *termios,
while ((READ_SC_PORT(port, SR) & ((1 << 3) | (1 << 2))) != 0xc)
udelay(2);
- /* XXX */
- uart_update_timeout(port, cflag,
- (port->uartclk / (16 * quot)));
+ uart_update_timeout(port, cflag, baud);
spin_unlock_irqrestore(&port->lock, flags);
}
^ permalink raw reply related [flat|nested] 15+ messages in thread
* [PATCH V2 07/14] Serial: sc26xx - simplify port initialisation.
2010-02-25 13:34 [PATCH 00/14] Serial : sc26xx - generalize and support SC2892 Martin Fuzzey
` (5 preceding siblings ...)
2010-02-25 13:35 ` [PATCH V2 06/14] Serial: sc26xx simplify timeout calculation Martin Fuzzey
@ 2010-02-25 13:35 ` Martin Fuzzey
2010-02-25 13:35 ` [PATCH V2 08/14] Serial: sc26xx - avoid endless loop with IRQs masked Martin Fuzzey
` (6 subsequent siblings)
13 siblings, 0 replies; 15+ messages in thread
From: Martin Fuzzey @ 2010-02-25 13:35 UTC (permalink / raw)
To: linux-serial, tsbogend
Just use a memcpy
Acked-By: Thomas Bogendoerfer <tsbogend@alpha.franken.de>
Signed-off-by: Martin Fuzzey <mfuzzey@gmail.com>
---
drivers/serial/sc26xx.c | 11 +----------
1 files changed, 1 insertions(+), 10 deletions(-)
diff --git a/drivers/serial/sc26xx.c b/drivers/serial/sc26xx.c
index 316d110..69b7ae7 100644
--- a/drivers/serial/sc26xx.c
+++ b/drivers/serial/sc26xx.c
@@ -680,17 +680,8 @@ static int __devinit sc26xx_probe(struct platform_device *dev)
sc26xx_port = &up->port[0];
+ memcpy(&up->port[1], &up->port[0], sizeof(up->port[0]));
up->port[1].line = 1;
- up->port[1].ops = &sc26xx_ops;
- up->port[1].type = PORT_SC26XX;
- up->port[1].uartclk = (29491200 / 16); /* arbitrary */
-
- up->port[1].mapbase = up->port[0].mapbase;
- up->port[1].membase = up->port[0].membase;
- up->port[1].iotype = UPIO_MEM;
- up->port[1].irq = up->port[0].irq;
-
- up->port[1].dev = &dev->dev;
sc26xx_init_masks(up, 1, sc26xx_data[1]);
^ permalink raw reply related [flat|nested] 15+ messages in thread
* [PATCH V2 08/14] Serial: sc26xx - avoid endless loop with IRQs masked.
2010-02-25 13:34 [PATCH 00/14] Serial : sc26xx - generalize and support SC2892 Martin Fuzzey
` (6 preceding siblings ...)
2010-02-25 13:35 ` [PATCH V2 07/14] Serial: sc26xx - simplify port initialisation Martin Fuzzey
@ 2010-02-25 13:35 ` Martin Fuzzey
2010-02-25 13:35 ` [PATCH V2 09/14] Serial: sc26xx - add support for SC2892 chips Martin Fuzzey
` (5 subsequent siblings)
13 siblings, 0 replies; 15+ messages in thread
From: Martin Fuzzey @ 2010-02-25 13:35 UTC (permalink / raw)
To: linux-serial, tsbogend
If hardware is in wierd state it is possible to lock the
system while waiting for the TX flush to complete.
Acked-By: Thomas Bogendoerfer <tsbogend@alpha.franken.de>
Signed-off-by: Martin Fuzzey <mfuzzey@gmail.com>
---
drivers/serial/sc26xx.c | 27 ++++++++++++++++++++++-----
1 files changed, 22 insertions(+), 5 deletions(-)
diff --git a/drivers/serial/sc26xx.c b/drivers/serial/sc26xx.c
index 69b7ae7..bc466ac 100644
--- a/drivers/serial/sc26xx.c
+++ b/drivers/serial/sc26xx.c
@@ -72,6 +72,7 @@ struct uart_sc26xx_port {
#define SR_FRAME (1 << 6)
#define SR_PARITY (1 << 5)
#define SR_OVERRUN (1 << 4)
+#define SR_TXEMT (1 << 3)
#define SR_TXRDY (1 << 2)
#define SR_RXRDY (1 << 0)
@@ -396,6 +397,22 @@ static void sc26xx_shutdown(struct uart_port *port)
WRITE_SC_PORT(port, CR, CR_DIS_TX | CR_DIS_RX);
}
+static int wait_tx_empty(struct uart_port *port)
+{
+ int i;
+ u8 sr;
+ u8 bits = SR_TXEMT | SR_TXRDY;
+
+ for (i = 0; i < 10000; i++) {
+ sr = READ_SC_PORT(port, SR);
+ if ((sr & bits) == bits)
+ return 0;
+ udelay(2);
+ }
+ dev_warn(port->dev, "Timed out waiting for TX Empty sr=%02X\n", sr);
+ return -1;
+}
+
/* port->lock is not held. */
static void sc26xx_set_termios(struct uart_port *port, struct ktermios *termios,
struct ktermios *old)
@@ -407,8 +424,8 @@ static void sc26xx_set_termios(struct uart_port *port, struct ktermios *termios,
spin_lock_irqsave(&port->lock, flags);
- while ((READ_SC_PORT(port, SR) & ((1 << 3) | (1 << 2))) != 0xc)
- udelay(2);
+ if (wait_tx_empty(port))
+ goto out;
WRITE_SC_PORT(port, CR, CR_DIS_TX | CR_DIS_RX);
@@ -501,11 +518,11 @@ static void sc26xx_set_termios(struct uart_port *port, struct ktermios *termios,
write_cmd_port(port, CR_RES_TX);
WRITE_SC_PORT(port, CR, CR_ENA_TX | CR_ENA_RX);
- while ((READ_SC_PORT(port, SR) & ((1 << 3) | (1 << 2))) != 0xc)
- udelay(2);
+ if (wait_tx_empty(port))
+ goto out;
uart_update_timeout(port, cflag, baud);
-
+out:
spin_unlock_irqrestore(&port->lock, flags);
}
^ permalink raw reply related [flat|nested] 15+ messages in thread
* [PATCH V2 09/14] Serial: sc26xx - add support for SC2892 chips
2010-02-25 13:34 [PATCH 00/14] Serial : sc26xx - generalize and support SC2892 Martin Fuzzey
` (7 preceding siblings ...)
2010-02-25 13:35 ` [PATCH V2 08/14] Serial: sc26xx - avoid endless loop with IRQs masked Martin Fuzzey
@ 2010-02-25 13:35 ` Martin Fuzzey
2010-02-25 13:35 ` [PATCH V2 10/14] Serial: sc26xx - introduce a structure for platform data Martin Fuzzey
` (4 subsequent siblings)
13 siblings, 0 replies; 15+ messages in thread
From: Martin Fuzzey @ 2010-02-25 13:35 UTC (permalink / raw)
To: linux-serial, tsbogend
Acked-By: Thomas Bogendoerfer <tsbogend@alpha.franken.de>
Signed-off-by: Martin Fuzzey <mfuzzey@gmail.com>
---
drivers/serial/sc26xx.c | 238 ++++++++++++++++++++++++++++++++++++++---------
1 files changed, 193 insertions(+), 45 deletions(-)
diff --git a/drivers/serial/sc26xx.c b/drivers/serial/sc26xx.c
index bc466ac..053520d 100644
--- a/drivers/serial/sc26xx.c
+++ b/drivers/serial/sc26xx.c
@@ -1,7 +1,8 @@
/*
- * SC268xx.c: Serial driver for Philiphs SC2681/SC2692 devices.
+ * SC26xx.c: Serial driver for Philips SC2681/SC2692/SC2892 devices.
*
* Copyright (C) 2006,2007 Thomas Bogendörfer (tsbogend@alpha.franken.de)
+ * SC2892 support by Martin Fuzzey (mfuzzey@gmail.com)
*/
#include <linux/module.h>
@@ -32,15 +33,29 @@
#define SC26XX_MINOR_START 205
#define SC26XX_NR 2
+struct chip_def {
+ u8 has_mr0;
+ u8 init_mr0;
+ u8 init_mr1;
+ u8 max_baud_mode;
+ u8 default_baud_mode;
+ u8 default_baud_group;
+ const char *name;
+};
+
struct uart_sc26xx_port {
struct uart_port port[2];
- u8 dsr_mask[2];
- u8 cts_mask[2];
- u8 dcd_mask[2];
- u8 ri_mask[2];
- u8 dtr_mask[2];
- u8 rts_mask[2];
- u8 imr;
+ u8 dsr_mask[2];
+ u8 cts_mask[2];
+ u8 dcd_mask[2];
+ u8 ri_mask[2];
+ u8 dtr_mask[2];
+ u8 rts_mask[2];
+ u8 imr;
+ u8 acr;
+ u8 mr0_baud;
+ const unsigned int *baud_rates;
+ const struct chip_def *chip;
};
/* register common to both ports */
@@ -81,6 +96,7 @@ struct uart_sc26xx_port {
#define CR_RES_TX (3 << 4)
#define CR_STRT_BRK (6 << 4)
#define CR_STOP_BRK (7 << 4)
+#define CR_SEL_MR0 (11 << 4)
#define CR_DIS_TX (1 << 3)
#define CR_ENA_TX (1 << 2)
#define CR_DIS_RX (1 << 1)
@@ -96,6 +112,66 @@ struct uart_sc26xx_port {
#define IMR_RXRDY (1 << 1)
#define IMR_TXRDY (1 << 0)
+/* MR0 bits (>= 28L92 only */
+#define MR0_WATCHDOG (1 << 7)
+#define MR0_RXINT2 (1 << 6)
+#define MR0_TXINT(x) ((x) << 4)
+#define MR0_FIFO_SIZE (1 << 3)
+#define MR0_BAUD_MODE ((1 << 2) + (1 << 0))
+
+
+#define NR_BAUD_GROUPS 2
+#define NR_BAUD_MODES 3
+#define NR_BAUDS 13
+#define DEFAULT_BAUD_INDEX 11
+static const unsigned baud_rates[NR_BAUD_MODES][NR_BAUD_GROUPS][NR_BAUDS] = {
+ {
+ /* Normal mode ACR[7] = 0 */
+ {50, 110, 134, 200, 300, 600, 1200, 1050,
+ 2400, 4800, 7200, 9600, 38400},
+
+ /* Normal mode ACR[7] = 1 */
+ {75, 110, 134, 150, 300, 600, 1200, 2000,
+ 2400, 4800, 1800, 9600, 19200},
+ }, {
+ /* Extended mode 1 ACR[7] = 0 */
+ {300, 110, 134, 1200, 1800, 3600, 7200, 1050,
+ 14400, 28800, 7200, 57600, 230400},
+
+ /* Extended mode 1 ACR[7] = 1 */
+ {450, 110, 134, 900, 1800, 3600, 72000, 2000,
+ 14400, 28800, 1800, 57600, 115200},
+ }, {
+ /* Extended mode 2 ACR[7] = 0 */
+ {4800, 880, 1076, 19200, 28800, 57600, 115200, 1050,
+ 57600, 4800, 57600, 9600, 38400},
+
+ /* Extended mode 2 ACR[7] = 1 */
+ {7200, 880, 1076, 14400, 28800, 57600, 115200, 2000,
+ 57600, 4800, 14400, 9600, 19200},
+ }
+};
+
+static struct chip_def chip_26xx = {
+ .name = "SC26XX",
+ .max_baud_mode = 0,
+ .default_baud_mode = 0,
+ .default_baud_group = 1,
+ .has_mr0 = 0,
+ .init_mr1 = 0,
+};
+
+static struct chip_def chip_2892 = {
+ .name = "SC2892",
+ .max_baud_mode = 2,
+ .default_baud_mode = 2,
+ .default_baud_group = 0,
+ .has_mr0 = 1,
+ .init_mr0 = MR0_WATCHDOG | MR0_FIFO_SIZE | MR0_TXINT(1),
+ .init_mr1 = (1 << 6),
+};
+
+
static struct uart_sc26xx_port *driver_info(struct uart_port *port)
{
port -= port->line;
@@ -142,6 +218,19 @@ static inline void write_cmd_port(struct uart_port *port, u8 cmd)
write_cmd_line(port, port->line, cmd);
}
+
+static u8 read_mr0(struct uart_port *port, int line)
+{
+ write_cmd_line(port, line, CR_SEL_MR0);
+ return read_sc_line(port, line, RD_PORT_MRx);
+}
+
+static void write_mr0(struct uart_port *port, int line, u8 val)
+{
+ write_cmd_line(port, line, CR_SEL_MR0);
+ write_sc_line(port, line, WR_PORT_MRx, val);
+}
+
static void sc26xx_enable_irq(struct uart_port *port, int mask)
{
struct uart_sc26xx_port *up = driver_info(port);
@@ -372,6 +461,8 @@ static void sc26xx_break_ctl(struct uart_port *port, int break_state)
/* port->lock is not held. */
static int sc26xx_startup(struct uart_port *port)
{
+ struct uart_sc26xx_port *up = driver_info(port);
+
sc26xx_disable_irq(port, IMR_TXRDY | IMR_RXRDY);
WRITE_SC(port, OPCR, 0);
@@ -379,6 +470,9 @@ static int sc26xx_startup(struct uart_port *port)
write_cmd_port(port, CR_RES_RX);
write_cmd_port(port, CR_RES_TX);
+ if (up->chip->has_mr0)
+ write_mr0(port, port->line, up->chip->init_mr0);
+
/* start rx/tx */
WRITE_SC_PORT(port, CR, CR_ENA_TX | CR_ENA_RX);
@@ -413,10 +507,32 @@ static int wait_tx_empty(struct uart_port *port)
return -1;
}
+static u8 find_csr(struct uart_sc26xx_port *up, unsigned int baud)
+{
+ int i, found = -1;
+
+ for (i = 0; i < NR_BAUDS; i++) {
+ if (up->baud_rates[i] == baud) {
+ found = i;
+ break;
+ }
+ }
+
+ if (found == -1) {
+ found = DEFAULT_BAUD_INDEX;
+ dev_warn(up->port[0].dev,
+ "%d baud not available using %d\n",
+ baud, up->baud_rates[found]);
+ }
+
+ return (u8)found | ((u8)found << 4);
+}
+
/* port->lock is not held. */
static void sc26xx_set_termios(struct uart_port *port, struct ktermios *termios,
struct ktermios *old)
{
+ struct uart_sc26xx_port *up = driver_info(port);
unsigned int baud = uart_get_baud_rate(port, termios, old, 0, 4000000);
unsigned int iflag, cflag;
unsigned long flags;
@@ -469,48 +585,21 @@ static void sc26xx_set_termios(struct uart_port *port, struct ktermios *termios,
} else
mr1 |= (2 << 3);
- switch (baud) {
- case 50:
- csr = 0x00;
- break;
- case 110:
- csr = 0x11;
- break;
- case 134:
- csr = 0x22;
- break;
- case 200:
- csr = 0x33;
- break;
- case 300:
- csr = 0x44;
- break;
- case 600:
- csr = 0x55;
- break;
- case 1200:
- csr = 0x66;
- break;
- case 2400:
- csr = 0x88;
- break;
- case 4800:
- csr = 0x99;
- break;
- default:
- case 9600:
- csr = 0xbb;
- break;
- case 19200:
- csr = 0xcc;
- break;
+ mr1 |= up->chip->init_mr1;
+ csr = find_csr(up, baud);
+
+ if (up->chip->has_mr0) {
+ u8 mr0a = read_mr0(port, 0);
+ mr0a &= ~MR0_BAUD_MODE;
+ mr0a |= up->mr0_baud;
+ write_mr0(port, 0, mr0a);
}
write_cmd_port(port, CR_RES_MR);
WRITE_SC_PORT(port, MRx, mr1);
WRITE_SC_PORT(port, MRx, mr2);
- WRITE_SC(port, ACR, 0x80);
+ WRITE_SC(port, ACR, up->acr);
WRITE_SC_PORT(port, CSR, csr);
/* reset tx and rx */
@@ -528,7 +617,7 @@ out:
static const char *sc26xx_type(struct uart_port *port)
{
- return "SC26XX";
+ return driver_info(port)->chip->name;
}
static void sc26xx_release_port(struct uart_port *port)
@@ -662,6 +751,60 @@ static void __devinit sc26xx_init_masks(struct uart_sc26xx_port *up,
up->ri_mask[line] = sc26xx_flags2mask(data, 20);
}
+static int __devinit init_baudgroup(struct uart_sc26xx_port *up)
+{
+ u8 baud_mode = up->chip->default_baud_mode;
+ u8 baud_group = up->chip->default_baud_group;
+
+ if (baud_mode > up->chip->max_baud_mode) {
+ printk(KERN_ERR "Baud mode %d not supported for %s\n",
+ baud_mode, up->chip->name);
+ return -EINVAL;
+ }
+
+ up->acr = baud_group ? 0x80 : 0;
+ up->baud_rates = baud_rates[baud_mode][baud_group];
+
+ switch (baud_mode) {
+ case 0:
+ up->mr0_baud = 0;
+ break;
+ case 1:
+ up->mr0_baud = 1;
+ break;
+ case 2:
+ up->mr0_baud = 4;
+ break;
+ }
+ return 0;
+}
+
+static const struct chip_def * __devinit detect_chip_type(
+ struct uart_sc26xx_port *up)
+{
+ struct uart_port *port = &up->port[0];
+ struct chip_def *chip;
+ int i;
+ u8 mrx[3];
+
+ /* Code below needs to be tested on 26xx hardware
+ * Idea is that 26xx will ignore SEL_MR0 so 2nd and 3rd reads
+ * will return same data.*/
+ write_cmd_port(port, CR_RES_MR); /* MR1 */
+ write_cmd_port(port, CR_SEL_MR0); /* Ignored on 26xx */
+
+ for (i = 0; i < 3; i++)
+ mrx[i] = READ_SC_PORT(port, MRx);
+
+ if (mrx[1] == mrx[2])
+ chip = &chip_26xx;
+ else
+ chip = &chip_2892;
+
+ dev_info(port->dev, "Autodetected %s\n", chip->name);
+ return chip;
+}
+
static int __devinit sc26xx_probe(struct platform_device *dev)
{
struct resource *res, *irq_res;
@@ -702,6 +845,11 @@ static int __devinit sc26xx_probe(struct platform_device *dev)
sc26xx_init_masks(up, 1, sc26xx_data[1]);
+ up->chip = detect_chip_type(up);
+ err = init_baudgroup(up);
+ if (err)
+ goto out_free_port;
+
err = uart_register_driver(&sc26xx_reg);
if (err)
goto out_free_port;
--
To unsubscribe from this list: send the line "unsubscribe linux-serial" in
the body of a message to majordomo@vger.kernel.org
More majordomo info at http://vger.kernel.org/majordomo-info.html
^ permalink raw reply related [flat|nested] 15+ messages in thread
* [PATCH V2 10/14] Serial: sc26xx - introduce a structure for platform data.
2010-02-25 13:34 [PATCH 00/14] Serial : sc26xx - generalize and support SC2892 Martin Fuzzey
` (8 preceding siblings ...)
2010-02-25 13:35 ` [PATCH V2 09/14] Serial: sc26xx - add support for SC2892 chips Martin Fuzzey
@ 2010-02-25 13:35 ` Martin Fuzzey
2010-02-25 13:35 ` [PATCH V2 11/14] Serial: sc26xx - initialise hardware if not done by bootloader Martin Fuzzey
` (3 subsequent siblings)
13 siblings, 0 replies; 15+ messages in thread
From: Martin Fuzzey @ 2010-02-25 13:35 UTC (permalink / raw)
To: linux-serial, tsbogend
Encapsulates the existing array of uint for signal mapping
and adds baudrate group selection.
Acked-By: Thomas Bogendoerfer <tsbogend@alpha.franken.de>
Signed-off-by: Martin Fuzzey <mfuzzey@gmail.com>
---
arch/mips/sni/a20r.c | 15 ++++++++----
drivers/serial/sc26xx.c | 49 +++++++++++++++++++++++++++++++++++----
include/linux/serial_sc2xxx.h | 52 +++++++++++++++++++++++++++++++++++++++++
3 files changed, 107 insertions(+), 9 deletions(-)
create mode 100644 include/linux/serial_sc2xxx.h
diff --git a/arch/mips/sni/a20r.c b/arch/mips/sni/a20r.c
index e698089..2fbbb65 100644
--- a/arch/mips/sni/a20r.c
+++ b/arch/mips/sni/a20r.c
@@ -12,6 +12,7 @@
#include <linux/interrupt.h>
#include <linux/platform_device.h>
#include <linux/serial_8250.h>
+#include <linux/serial_sc2xxx.h>
#include <asm/sni.h>
#include <asm/time.h>
@@ -117,10 +118,14 @@ static struct resource sc26xx_rsrc[] = {
}
};
-static unsigned int sc26xx_data[2] = {
- /* DTR | RTS | DSR | CTS | DCD | RI */
- (8 << 0) | (4 << 4) | (6 << 8) | (0 << 12) | (6 << 16) | (0 << 20),
- (3 << 0) | (2 << 4) | (1 << 8) | (2 << 12) | (3 << 16) | (4 << 20)
+static struct plat_serial_sc2xxx sc26xx_data = {
+ .signal_map = {
+ /* DTR | RTS | DSR | CTS | DCD | RI */
+ (8 << 0) | (4 << 4) | (6 << 8) | (0 << 12) | (6 << 16) | (0 << 20),
+ (3 << 0) | (2 << 4) | (1 << 8) | (2 << 12) | (3 << 16) | (4 << 20)
+ },
+ .baud_mode = 1,
+ .baud_group = 2,
};
static struct platform_device sc26xx_pdev = {
@@ -128,7 +133,7 @@ static struct platform_device sc26xx_pdev = {
.num_resources = ARRAY_SIZE(sc26xx_rsrc),
.resource = sc26xx_rsrc,
.dev = {
- .platform_data = sc26xx_data,
+ .platform_data = &sc26xx_data,
}
};
diff --git a/drivers/serial/sc26xx.c b/drivers/serial/sc26xx.c
index 053520d..09e73a3 100644
--- a/drivers/serial/sc26xx.c
+++ b/drivers/serial/sc26xx.c
@@ -22,6 +22,7 @@
#include <linux/platform_device.h>
#include <linux/irq.h>
#include <linux/io.h>
+#include <linux/serial_sc2xxx.h>
#if defined(CONFIG_MAGIC_SYSRQ)
#define SUPPORT_SYSRQ
@@ -171,6 +172,10 @@ static struct chip_def chip_2892 = {
.init_mr1 = (1 << 6),
};
+static const struct chip_def *chips[] = {
+ &chip_26xx,
+ &chip_2892
+};
static struct uart_sc26xx_port *driver_info(struct uart_port *port)
{
@@ -753,9 +758,17 @@ static void __devinit sc26xx_init_masks(struct uart_sc26xx_port *up,
static int __devinit init_baudgroup(struct uart_sc26xx_port *up)
{
+ struct plat_serial_sc2xxx *pdata = up->port[0].dev->platform_data;
+
u8 baud_mode = up->chip->default_baud_mode;
u8 baud_group = up->chip->default_baud_group;
+ if (pdata->baud_mode > 0)
+ baud_mode = pdata->baud_mode - 1;
+
+ if (pdata->baud_group > 0)
+ baud_group = pdata->baud_group - 1;
+
if (baud_mode > up->chip->max_baud_mode) {
printk(KERN_ERR "Baud mode %d not supported for %s\n",
baud_mode, up->chip->name);
@@ -779,6 +792,20 @@ static int __devinit init_baudgroup(struct uart_sc26xx_port *up)
return 0;
}
+static const struct chip_def * __devinit chip_by_name(const char *name)
+{
+ int i;
+ const struct chip_def *chip;
+
+ for (i = 0; i < ARRAY_SIZE(chips); i++) {
+ chip = chips[i];
+ if (!strcmp(chip->name, name))
+ return chip;
+ }
+
+ return NULL;
+}
+
static const struct chip_def * __devinit detect_chip_type(
struct uart_sc26xx_port *up)
{
@@ -809,9 +836,14 @@ static int __devinit sc26xx_probe(struct platform_device *dev)
{
struct resource *res, *irq_res;
struct uart_sc26xx_port *up;
- unsigned int *sc26xx_data = dev->dev.platform_data;
+ struct plat_serial_sc2xxx *pdata = dev->dev.platform_data;
int err;
+ if (!pdata) {
+ dev_err(&dev->dev, "No platform data\n");
+ return -EINVAL;
+ }
+
res = platform_get_resource(dev, IORESOURCE_MEM, 0);
if (!res)
return -ENODEV;
@@ -836,16 +868,25 @@ static int __devinit sc26xx_probe(struct platform_device *dev)
up->port[0].dev = &dev->dev;
- sc26xx_init_masks(up, 0, sc26xx_data[0]);
+ sc26xx_init_masks(up, 0, pdata->signal_map[0]);
sc26xx_port = &up->port[0];
memcpy(&up->port[1], &up->port[0], sizeof(up->port[0]));
up->port[1].line = 1;
- sc26xx_init_masks(up, 1, sc26xx_data[1]);
+ sc26xx_init_masks(up, 1, pdata->signal_map[1]);
+
+ if (pdata->chip_name)
+ up->chip = chip_by_name(pdata->chip_name);
+ if (!up->chip) {
+ if (pdata->chip_name)
+ dev_warn(&dev->dev,
+ "Unknown chip %s requested - use autodetect\n",
+ pdata->chip_name);
+ up->chip = detect_chip_type(up);
+ }
- up->chip = detect_chip_type(up);
err = init_baudgroup(up);
if (err)
goto out_free_port;
diff --git a/include/linux/serial_sc2xxx.h b/include/linux/serial_sc2xxx.h
new file mode 100644
index 0000000..d93977f
--- /dev/null
+++ b/include/linux/serial_sc2xxx.h
@@ -0,0 +1,52 @@
+/*
+ *
+ * Copyright (C) 2009 Martin Fuzzey
+ *
+ * This program is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation; either version 2 of the License, or
+ * (at your option) any later version.
+ */
+
+
+#ifndef _LINUX_SERIAL_SC26XX_H
+#define _LINUX_SERIAL_SC26XX_H 1
+
+
+/**
+ * struct plat_sc2xxx - Philips UART platform data
+ * @signal_map: Hardware signal mapping (see below)
+ *
+ * @chip_name: One of "SC26xx", "SC2892" or NULL for autodetect
+ *
+ * @baud_mode: Baudrate mode + 1 (1,2,3) must be 1 for SC26xx see
+ * datasheet or baud_rates[] in driver code for available
+ * baudrates in each mode
+ * 0 = use driver default
+ *
+ * @baud_group: Baudrate group + 1 (1, 2) within mode
+ * 0 = use driver default
+ *
+ * For each port signal_map is a bitfield defined as follows:
+ * bits 0-3 DTR
+ * bits 4-7 RTS
+ * bits 8-11 DSR
+ * bits 12-15 CTS
+ * bits 16-19 DCD
+ * bits 20-23 RI
+ *
+ * Value of each field is 1 + corresponding IP/OP pin or 0 if not connected
+ * Eg:
+ * (3 << 0) | (1 << 4) | (3 << 8) | (1 << 12) | (4 << 16) | (0 << 20),
+ * =>
+ * DTR=OP2, RTS=OP0, DSR=IP2, CTS=IP0, DCD=IP3, RI=NC
+ *
+ **/
+struct plat_serial_sc2xxx {
+ unsigned int signal_map[2];
+ const char *chip_name;
+ u8 baud_mode;
+ u8 baud_group;
+};
+
+#endif
^ permalink raw reply related [flat|nested] 15+ messages in thread
* [PATCH V2 11/14] Serial: sc26xx - initialise hardware if not done by bootloader
2010-02-25 13:34 [PATCH 00/14] Serial : sc26xx - generalize and support SC2892 Martin Fuzzey
` (9 preceding siblings ...)
2010-02-25 13:35 ` [PATCH V2 10/14] Serial: sc26xx - introduce a structure for platform data Martin Fuzzey
@ 2010-02-25 13:35 ` Martin Fuzzey
2010-02-25 13:35 ` [PATCH V2 12/14] Serial: sc26xx - Use ttySC0 instead of ttySC205 Martin Fuzzey
` (2 subsequent siblings)
13 siblings, 0 replies; 15+ messages in thread
From: Martin Fuzzey @ 2010-02-25 13:35 UTC (permalink / raw)
To: linux-serial, tsbogend
If hardware is not initialised by bootloader after a hard reset
the MR1,MR2 registers may be 0xFF.
This causes the transmitter to never initialise and an infinite
loop to occur later.
Acked-By: Thomas Bogendoerfer <tsbogend@alpha.franken.de>
Signed-off-by: Martin Fuzzey <mfuzzey@gmail.com>
---
drivers/serial/sc26xx.c | 23 +++++++++++++++++++++++
1 files changed, 23 insertions(+), 0 deletions(-)
diff --git a/drivers/serial/sc26xx.c b/drivers/serial/sc26xx.c
index 09e73a3..2e17bbc 100644
--- a/drivers/serial/sc26xx.c
+++ b/drivers/serial/sc26xx.c
@@ -832,6 +832,27 @@ static const struct chip_def * __devinit detect_chip_type(
return chip;
}
+static void __devinit hw_init(struct uart_port *port)
+{
+ u8 mr;
+
+ /* Sometimes on cold boot MR1,MR2 are 0xFF (reset problem?)
+ * Initialise if channel mode in MR2 is not normal otherwise
+ * assume bootloader has done the init.
+ */
+ write_cmd_port(port, CR_RES_MR); /* MR1 */
+ READ_SC_PORT(port, MRx); /* skip MR1 */
+ mr = READ_SC_PORT(port, MRx);
+ if (mr & 0xC0) {
+ write_cmd_port(port, CR_RES_MR);
+
+ /* Values below are arbitary (will be changed by set_termios)
+ * but must be different so that chip detection works */
+ WRITE_SC_PORT(port, MRx, 0x10);
+ WRITE_SC_PORT(port, MRx, 0x00);
+ }
+}
+
static int __devinit sc26xx_probe(struct platform_device *dev)
{
struct resource *res, *irq_res;
@@ -869,6 +890,7 @@ static int __devinit sc26xx_probe(struct platform_device *dev)
up->port[0].dev = &dev->dev;
sc26xx_init_masks(up, 0, pdata->signal_map[0]);
+ hw_init(&up->port[0]);
sc26xx_port = &up->port[0];
@@ -876,6 +898,7 @@ static int __devinit sc26xx_probe(struct platform_device *dev)
up->port[1].line = 1;
sc26xx_init_masks(up, 1, pdata->signal_map[1]);
+ hw_init(&up->port[1]);
if (pdata->chip_name)
up->chip = chip_by_name(pdata->chip_name);
^ permalink raw reply related [flat|nested] 15+ messages in thread
* [PATCH V2 12/14] Serial: sc26xx - Use ttySC0 instead of ttySC205
2010-02-25 13:34 [PATCH 00/14] Serial : sc26xx - generalize and support SC2892 Martin Fuzzey
` (10 preceding siblings ...)
2010-02-25 13:35 ` [PATCH V2 11/14] Serial: sc26xx - initialise hardware if not done by bootloader Martin Fuzzey
@ 2010-02-25 13:35 ` Martin Fuzzey
2010-02-25 13:35 ` [PATCH V2 13/14] Serial: sc26xx - Avoid null pointer dereference Martin Fuzzey
2010-02-25 13:35 ` [PATCH V2 14/14] Serial: sc26xx - rename to sc2xxx Martin Fuzzey
13 siblings, 0 replies; 15+ messages in thread
From: Martin Fuzzey @ 2010-02-25 13:35 UTC (permalink / raw)
To: linux-serial, tsbogend
Use device name ttySC0 as per Documentation/devices.txt
Acked-By: Thomas Bogendoerfer <tsbogend@alpha.franken.de>
Signed-off-by: Martin Fuzzey <mfuzzey@gmail.com>
---
drivers/serial/sc26xx.c | 2 --
1 files changed, 0 insertions(+), 2 deletions(-)
diff --git a/drivers/serial/sc26xx.c b/drivers/serial/sc26xx.c
index 2e17bbc..9b0ede0 100644
--- a/drivers/serial/sc26xx.c
+++ b/drivers/serial/sc26xx.c
@@ -918,8 +918,6 @@ static int __devinit sc26xx_probe(struct platform_device *dev)
if (err)
goto out_free_port;
- sc26xx_reg.tty_driver->name_base = sc26xx_reg.minor;
-
err = uart_add_one_port(&sc26xx_reg, &up->port[0]);
if (err)
goto out_unregister_driver;
^ permalink raw reply related [flat|nested] 15+ messages in thread
* [PATCH V2 13/14] Serial: sc26xx - Avoid null pointer dereference
2010-02-25 13:34 [PATCH 00/14] Serial : sc26xx - generalize and support SC2892 Martin Fuzzey
` (11 preceding siblings ...)
2010-02-25 13:35 ` [PATCH V2 12/14] Serial: sc26xx - Use ttySC0 instead of ttySC205 Martin Fuzzey
@ 2010-02-25 13:35 ` Martin Fuzzey
2010-02-25 13:35 ` [PATCH V2 14/14] Serial: sc26xx - rename to sc2xxx Martin Fuzzey
13 siblings, 0 replies; 15+ messages in thread
From: Martin Fuzzey @ 2010-02-25 13:35 UTC (permalink / raw)
To: linux-serial, tsbogend
Acked-By: Thomas Bogendoerfer <tsbogend@alpha.franken.de>
Signed-off-by: Martin Fuzzey <mfuzzey@gmail.com>
---
drivers/serial/sc26xx.c | 3 ++-
1 files changed, 2 insertions(+), 1 deletions(-)
diff --git a/drivers/serial/sc26xx.c b/drivers/serial/sc26xx.c
index 9b0ede0..33b21b9 100644
--- a/drivers/serial/sc26xx.c
+++ b/drivers/serial/sc26xx.c
@@ -301,7 +301,8 @@ static struct tty_struct *receive_chars(struct uart_port *port)
if (status & port->ignore_status_mask)
continue;
- tty_insert_flip_char(tty, ch, flag);
+ if (tty)
+ tty_insert_flip_char(tty, ch, flag);
}
return tty;
}
^ permalink raw reply related [flat|nested] 15+ messages in thread
* [PATCH V2 14/14] Serial: sc26xx - rename to sc2xxx
2010-02-25 13:34 [PATCH 00/14] Serial : sc26xx - generalize and support SC2892 Martin Fuzzey
` (12 preceding siblings ...)
2010-02-25 13:35 ` [PATCH V2 13/14] Serial: sc26xx - Avoid null pointer dereference Martin Fuzzey
@ 2010-02-25 13:35 ` Martin Fuzzey
13 siblings, 0 replies; 15+ messages in thread
From: Martin Fuzzey @ 2010-02-25 13:35 UTC (permalink / raw)
To: linux-serial, tsbogend
As driver now supports 28xx chips rename it.
Acked-By: Thomas Bogendoerfer <tsbogend@alpha.franken.de>
Signed-off-by: Martin Fuzzey <mfuzzey@gmail.com>
---
arch/mips/sni/a20r.c | 2
drivers/serial/Kconfig | 14 -
drivers/serial/Makefile | 2
drivers/serial/sc26xx.c | 998 -------------------------------------------
drivers/serial/sc2xxx.c | 998 +++++++++++++++++++++++++++++++++++++++++++
include/linux/serial_core.h | 2
6 files changed, 1008 insertions(+), 1008 deletions(-)
delete mode 100644 drivers/serial/sc26xx.c
create mode 100644 drivers/serial/sc2xxx.c
diff --git a/arch/mips/sni/a20r.c b/arch/mips/sni/a20r.c
index 2fbbb65..c2e4680 100644
--- a/arch/mips/sni/a20r.c
+++ b/arch/mips/sni/a20r.c
@@ -129,7 +129,7 @@ static struct plat_serial_sc2xxx sc26xx_data = {
};
static struct platform_device sc26xx_pdev = {
- .name = "SC26xx",
+ .name = "SC2xxx",
.num_resources = ARRAY_SIZE(sc26xx_rsrc),
.resource = sc26xx_rsrc,
.dev = {
diff --git a/drivers/serial/Kconfig b/drivers/serial/Kconfig
index 10bd461..a64424c 100644
--- a/drivers/serial/Kconfig
+++ b/drivers/serial/Kconfig
@@ -1393,20 +1393,20 @@ config SERIAL_QE
This driver supports the QE serial ports on Freescale embedded
PowerPC that contain a QUICC Engine.
-config SERIAL_SC26XX
- tristate "SC2681/SC2692 serial port support"
+config SERIAL_SC2XXX
+ tristate "SC2681/SC2692/SC2892 serial port support"
depends on SNI_RM || EMBEDDED
select SERIAL_CORE
help
This is a driver for the onboard serial ports of
- older RM400 machines.
+ older RM400 machines and some embedded systems.
-config SERIAL_SC26XX_CONSOLE
- bool "Console on SC2681/SC2692 serial port"
- depends on SERIAL_SC26XX
+config SERIAL_SC2XXX_CONSOLE
+ bool "Console on SC2681/SC2692/SC2892 serial port"
+ depends on SERIAL_SC2XXX
select SERIAL_CORE_CONSOLE
help
- Support for Console on SC2681/SC2692 serial ports.
+ Support for Console on SC2681/SC2692/SC2892 serial ports.
config SERIAL_BFIN_SPORT
tristate "Blackfin SPORT emulate UART (EXPERIMENTAL)"
diff --git a/drivers/serial/Makefile b/drivers/serial/Makefile
index 5548fe7..926515b 100644
--- a/drivers/serial/Makefile
+++ b/drivers/serial/Makefile
@@ -65,7 +65,7 @@ obj-$(CONFIG_SERIAL_M32R_SIO) += m32r_sio.o
obj-$(CONFIG_SERIAL_MPSC) += mpsc.o
obj-$(CONFIG_SERIAL_SB1250_DUART) += sb1250-duart.o
obj-$(CONFIG_ETRAX_SERIAL) += crisv10.o
-obj-$(CONFIG_SERIAL_SC26XX) += sc26xx.o
+obj-$(CONFIG_SERIAL_SC2XXX) += sc2xxx.o
obj-$(CONFIG_SERIAL_JSM) += jsm/
obj-$(CONFIG_SERIAL_TXX9) += serial_txx9.o
obj-$(CONFIG_SERIAL_VR41XX) += vr41xx_siu.o
diff --git a/drivers/serial/sc26xx.c b/drivers/serial/sc26xx.c
deleted file mode 100644
index 33b21b9..0000000
--- a/drivers/serial/sc26xx.c
+++ /dev/null
@@ -1,998 +0,0 @@
-/*
- * SC26xx.c: Serial driver for Philips SC2681/SC2692/SC2892 devices.
- *
- * Copyright (C) 2006,2007 Thomas Bogendörfer (tsbogend@alpha.franken.de)
- * SC2892 support by Martin Fuzzey (mfuzzey@gmail.com)
- */
-
-#include <linux/module.h>
-#include <linux/kernel.h>
-#include <linux/errno.h>
-#include <linux/tty.h>
-#include <linux/tty_flip.h>
-#include <linux/major.h>
-#include <linux/circ_buf.h>
-#include <linux/serial.h>
-#include <linux/sysrq.h>
-#include <linux/console.h>
-#include <linux/spinlock.h>
-#include <linux/slab.h>
-#include <linux/delay.h>
-#include <linux/init.h>
-#include <linux/platform_device.h>
-#include <linux/irq.h>
-#include <linux/io.h>
-#include <linux/serial_sc2xxx.h>
-
-#if defined(CONFIG_MAGIC_SYSRQ)
-#define SUPPORT_SYSRQ
-#endif
-
-#include <linux/serial_core.h>
-
-#define SC26XX_MAJOR 204
-#define SC26XX_MINOR_START 205
-#define SC26XX_NR 2
-
-struct chip_def {
- u8 has_mr0;
- u8 init_mr0;
- u8 init_mr1;
- u8 max_baud_mode;
- u8 default_baud_mode;
- u8 default_baud_group;
- const char *name;
-};
-
-struct uart_sc26xx_port {
- struct uart_port port[2];
- u8 dsr_mask[2];
- u8 cts_mask[2];
- u8 dcd_mask[2];
- u8 ri_mask[2];
- u8 dtr_mask[2];
- u8 rts_mask[2];
- u8 imr;
- u8 acr;
- u8 mr0_baud;
- const unsigned int *baud_rates;
- const struct chip_def *chip;
-};
-
-/* register common to both ports */
-#define RD_ISR 0x14
-#define RD_IPR 0x34
-
-#define WR_ACR 0x10
-#define WR_IMR 0x14
-#define WR_OPCR 0x34
-#define WR_OPR_SET 0x38
-#define WR_OPR_CLR 0x3C
-
-/* access common register */
-#define READ_SC(p, r) readb((p)->membase + RD_##r)
-#define WRITE_SC(p, r, v) writeb((v), (p)->membase + WR_##r)
-
-/* register per port */
-#define RD_PORT_MRx 0x00
-#define RD_PORT_SR 0x04
-#define RD_PORT_RHR 0x0c
-
-#define WR_PORT_MRx 0x00
-#define WR_PORT_CSR 0x04
-#define WR_PORT_CR 0x08
-#define WR_PORT_THR 0x0c
-
-/* SR bits */
-#define SR_BREAK (1 << 7)
-#define SR_FRAME (1 << 6)
-#define SR_PARITY (1 << 5)
-#define SR_OVERRUN (1 << 4)
-#define SR_TXEMT (1 << 3)
-#define SR_TXRDY (1 << 2)
-#define SR_RXRDY (1 << 0)
-
-#define CR_RES_MR (1 << 4)
-#define CR_RES_RX (2 << 4)
-#define CR_RES_TX (3 << 4)
-#define CR_STRT_BRK (6 << 4)
-#define CR_STOP_BRK (7 << 4)
-#define CR_SEL_MR0 (11 << 4)
-#define CR_DIS_TX (1 << 3)
-#define CR_ENA_TX (1 << 2)
-#define CR_DIS_RX (1 << 1)
-#define CR_ENA_RX (1 << 0)
-
-/* ISR bits */
-#define ISR_RXRDYB (1 << 5)
-#define ISR_TXRDYB (1 << 4)
-#define ISR_RXRDYA (1 << 1)
-#define ISR_TXRDYA (1 << 0)
-
-/* IMR bits */
-#define IMR_RXRDY (1 << 1)
-#define IMR_TXRDY (1 << 0)
-
-/* MR0 bits (>= 28L92 only */
-#define MR0_WATCHDOG (1 << 7)
-#define MR0_RXINT2 (1 << 6)
-#define MR0_TXINT(x) ((x) << 4)
-#define MR0_FIFO_SIZE (1 << 3)
-#define MR0_BAUD_MODE ((1 << 2) + (1 << 0))
-
-
-#define NR_BAUD_GROUPS 2
-#define NR_BAUD_MODES 3
-#define NR_BAUDS 13
-#define DEFAULT_BAUD_INDEX 11
-static const unsigned baud_rates[NR_BAUD_MODES][NR_BAUD_GROUPS][NR_BAUDS] = {
- {
- /* Normal mode ACR[7] = 0 */
- {50, 110, 134, 200, 300, 600, 1200, 1050,
- 2400, 4800, 7200, 9600, 38400},
-
- /* Normal mode ACR[7] = 1 */
- {75, 110, 134, 150, 300, 600, 1200, 2000,
- 2400, 4800, 1800, 9600, 19200},
- }, {
- /* Extended mode 1 ACR[7] = 0 */
- {300, 110, 134, 1200, 1800, 3600, 7200, 1050,
- 14400, 28800, 7200, 57600, 230400},
-
- /* Extended mode 1 ACR[7] = 1 */
- {450, 110, 134, 900, 1800, 3600, 72000, 2000,
- 14400, 28800, 1800, 57600, 115200},
- }, {
- /* Extended mode 2 ACR[7] = 0 */
- {4800, 880, 1076, 19200, 28800, 57600, 115200, 1050,
- 57600, 4800, 57600, 9600, 38400},
-
- /* Extended mode 2 ACR[7] = 1 */
- {7200, 880, 1076, 14400, 28800, 57600, 115200, 2000,
- 57600, 4800, 14400, 9600, 19200},
- }
-};
-
-static struct chip_def chip_26xx = {
- .name = "SC26XX",
- .max_baud_mode = 0,
- .default_baud_mode = 0,
- .default_baud_group = 1,
- .has_mr0 = 0,
- .init_mr1 = 0,
-};
-
-static struct chip_def chip_2892 = {
- .name = "SC2892",
- .max_baud_mode = 2,
- .default_baud_mode = 2,
- .default_baud_group = 0,
- .has_mr0 = 1,
- .init_mr0 = MR0_WATCHDOG | MR0_FIFO_SIZE | MR0_TXINT(1),
- .init_mr1 = (1 << 6),
-};
-
-static const struct chip_def *chips[] = {
- &chip_26xx,
- &chip_2892
-};
-
-static struct uart_sc26xx_port *driver_info(struct uart_port *port)
-{
- port -= port->line;
- return container_of(port, struct uart_sc26xx_port, port[0]);
-}
-
-/* access port register */
-static inline u8 read_sc_line(struct uart_port *p, int line, u8 reg)
-{
- return readb(p->membase + line * 0x20 + reg);
-}
-
-static inline u8 read_sc_port(struct uart_port *p, u8 reg)
-{
- return read_sc_line(p, p->line, reg);
-}
-
-static inline void write_sc_line(struct uart_port *p, int line, u8 reg, u8 val)
-{
- writeb(val, p->membase + line * 0x20 + reg);
-}
-
-static inline void write_sc_port(struct uart_port *p, u8 reg, u8 val)
-{
- write_sc_line(p, p->line, reg, val);
-}
-
-#define READ_SC_PORT(p, r) read_sc_port(p, RD_PORT_##r)
-#define WRITE_SC_PORT(p, r, v) write_sc_port(p, WR_PORT_##r, v)
-
-static void write_cmd_line(struct uart_port *port, int line, u8 cmd)
-{
- int i;
-
- write_sc_line(port, line, WR_PORT_CR, cmd);
-
- /* According to data sheet require 3 NOPs before next command */
- for (i = 0; i < 3; i++)
- write_sc_line(port, line, WR_PORT_CR, 0);
-}
-
-static inline void write_cmd_port(struct uart_port *port, u8 cmd)
-{
- write_cmd_line(port, port->line, cmd);
-}
-
-
-static u8 read_mr0(struct uart_port *port, int line)
-{
- write_cmd_line(port, line, CR_SEL_MR0);
- return read_sc_line(port, line, RD_PORT_MRx);
-}
-
-static void write_mr0(struct uart_port *port, int line, u8 val)
-{
- write_cmd_line(port, line, CR_SEL_MR0);
- write_sc_line(port, line, WR_PORT_MRx, val);
-}
-
-static void sc26xx_enable_irq(struct uart_port *port, int mask)
-{
- struct uart_sc26xx_port *up = driver_info(port);
-
- up->imr |= mask << (port->line * 4);
- WRITE_SC(port, IMR, up->imr);
-}
-
-static void sc26xx_disable_irq(struct uart_port *port, int mask)
-{
- struct uart_sc26xx_port *up = driver_info(port);
-
- up->imr &= ~(mask << (port->line * 4));
- WRITE_SC(port, IMR, up->imr);
-}
-
-static struct tty_struct *receive_chars(struct uart_port *port)
-{
- struct tty_struct *tty = NULL;
- int limit = 10000;
- unsigned char ch;
- char flag;
- u8 status;
-
- if (port->state != NULL) /* Unopened serial console */
- tty = port->state->port.tty;
-
- while (limit-- > 0) {
- status = READ_SC_PORT(port, SR);
- if (!(status & SR_RXRDY))
- break;
- ch = READ_SC_PORT(port, RHR);
-
- flag = TTY_NORMAL;
- port->icount.rx++;
-
- if (unlikely(status & (SR_BREAK | SR_FRAME |
- SR_PARITY | SR_OVERRUN))) {
- if (status & SR_BREAK) {
- status &= ~(SR_PARITY | SR_FRAME);
- port->icount.brk++;
- if (uart_handle_break(port))
- continue;
- } else if (status & SR_PARITY)
- port->icount.parity++;
- else if (status & SR_FRAME)
- port->icount.frame++;
- if (status & SR_OVERRUN)
- port->icount.overrun++;
-
- status &= port->read_status_mask;
- if (status & SR_BREAK)
- flag = TTY_BREAK;
- else if (status & SR_PARITY)
- flag = TTY_PARITY;
- else if (status & SR_FRAME)
- flag = TTY_FRAME;
- }
-
- if (uart_handle_sysrq_char(port, ch))
- continue;
-
- if (status & port->ignore_status_mask)
- continue;
-
- if (tty)
- tty_insert_flip_char(tty, ch, flag);
- }
- return tty;
-}
-
-static void transmit_chars(struct uart_port *port)
-{
- struct circ_buf *xmit;
-
- if (!port->state)
- return;
-
- xmit = &port->state->xmit;
- if (uart_circ_empty(xmit) || uart_tx_stopped(port)) {
- sc26xx_disable_irq(port, IMR_TXRDY);
- return;
- }
- while (!uart_circ_empty(xmit)) {
- if (!(READ_SC_PORT(port, SR) & SR_TXRDY))
- break;
-
- WRITE_SC_PORT(port, THR, xmit->buf[xmit->tail]);
- xmit->tail = (xmit->tail + 1) & (UART_XMIT_SIZE - 1);
- port->icount.tx++;
- }
- if (uart_circ_chars_pending(xmit) < WAKEUP_CHARS)
- uart_write_wakeup(port);
-}
-
-static irqreturn_t sc26xx_interrupt(int irq, void *dev_id)
-{
- struct uart_sc26xx_port *up = dev_id;
- struct tty_struct *tty;
- unsigned long flags;
- u8 isr;
-
- spin_lock_irqsave(&up->port[0].lock, flags);
-
- tty = NULL;
- isr = READ_SC(&up->port[0], ISR);
- if (isr & ISR_TXRDYA)
- transmit_chars(&up->port[0]);
- if (isr & ISR_RXRDYA)
- tty = receive_chars(&up->port[0]);
-
- spin_unlock(&up->port[0].lock);
-
- if (tty)
- tty_flip_buffer_push(tty);
-
- spin_lock(&up->port[1].lock);
-
- tty = NULL;
- if (isr & ISR_TXRDYB)
- transmit_chars(&up->port[1]);
- if (isr & ISR_RXRDYB)
- tty = receive_chars(&up->port[1]);
-
- spin_unlock_irqrestore(&up->port[1].lock, flags);
-
- if (tty)
- tty_flip_buffer_push(tty);
-
- return IRQ_HANDLED;
-}
-
-/* port->lock is not held. */
-static unsigned int sc26xx_tx_empty(struct uart_port *port)
-{
- return (READ_SC_PORT(port, SR) & SR_TXRDY) ? TIOCSER_TEMT : 0;
-}
-
-/* port->lock held by caller. */
-static void sc26xx_set_mctrl(struct uart_port *port, unsigned int mctrl)
-{
- struct uart_sc26xx_port *up = driver_info(port);
- int line = port->line;
-
- if (up->dtr_mask[line]) {
- if (mctrl & TIOCM_DTR)
- WRITE_SC(port, OPR_SET, up->dtr_mask[line]);
- else
- WRITE_SC(port, OPR_CLR, up->dtr_mask[line]);
- }
- if (up->rts_mask[line]) {
- if (mctrl & TIOCM_RTS)
- WRITE_SC(port, OPR_SET, up->rts_mask[line]);
- else
- WRITE_SC(port, OPR_CLR, up->rts_mask[line]);
- }
-}
-
-/* port->lock is held by caller and interrupts are disabled. */
-static unsigned int sc26xx_get_mctrl(struct uart_port *port)
-{
- struct uart_sc26xx_port *up = driver_info(port);
- int line = port->line;
- unsigned int mctrl = TIOCM_DSR | TIOCM_CTS | TIOCM_CAR;
- u8 ipr;
-
- ipr = READ_SC(port, IPR) ^ 0xff;
-
- if (up->dsr_mask[line]) {
- mctrl &= ~TIOCM_DSR;
- mctrl |= ipr & up->dsr_mask[line] ? TIOCM_DSR : 0;
- }
- if (up->cts_mask[line]) {
- mctrl &= ~TIOCM_CTS;
- mctrl |= ipr & up->cts_mask[line] ? TIOCM_CTS : 0;
- }
- if (up->dcd_mask[line]) {
- mctrl &= ~TIOCM_CAR;
- mctrl |= ipr & up->dcd_mask[line] ? TIOCM_CAR : 0;
- }
- if (up->ri_mask[line]) {
- mctrl &= ~TIOCM_RNG;
- mctrl |= ipr & up->ri_mask[line] ? TIOCM_RNG : 0;
- }
- return mctrl;
-}
-
-/* port->lock held by caller. */
-static void sc26xx_stop_tx(struct uart_port *port)
-{
- return;
-}
-
-/* port->lock held by caller. */
-static void sc26xx_start_tx(struct uart_port *port)
-{
- struct circ_buf *xmit = &port->state->xmit;
-
- while (!uart_circ_empty(xmit)) {
- if (!(READ_SC_PORT(port, SR) & SR_TXRDY)) {
- sc26xx_enable_irq(port, IMR_TXRDY);
- break;
- }
- WRITE_SC_PORT(port, THR, xmit->buf[xmit->tail]);
- xmit->tail = (xmit->tail + 1) & (UART_XMIT_SIZE - 1);
- port->icount.tx++;
- }
-}
-
-/* port->lock held by caller. */
-static void sc26xx_stop_rx(struct uart_port *port)
-{
-}
-
-/* port->lock held by caller. */
-static void sc26xx_enable_ms(struct uart_port *port)
-{
-}
-
-/* port->lock is not held. */
-static void sc26xx_break_ctl(struct uart_port *port, int break_state)
-{
- if (break_state == -1)
- write_cmd_port(port, CR_STRT_BRK);
- else
- write_cmd_port(port, CR_STOP_BRK);
-}
-
-/* port->lock is not held. */
-static int sc26xx_startup(struct uart_port *port)
-{
- struct uart_sc26xx_port *up = driver_info(port);
-
- sc26xx_disable_irq(port, IMR_TXRDY | IMR_RXRDY);
- WRITE_SC(port, OPCR, 0);
-
- /* reset tx and rx */
- write_cmd_port(port, CR_RES_RX);
- write_cmd_port(port, CR_RES_TX);
-
- if (up->chip->has_mr0)
- write_mr0(port, port->line, up->chip->init_mr0);
-
- /* start rx/tx */
- WRITE_SC_PORT(port, CR, CR_ENA_TX | CR_ENA_RX);
-
- /* enable irqs */
- sc26xx_enable_irq(port, IMR_RXRDY);
- return 0;
-}
-
-/* port->lock is not held. */
-static void sc26xx_shutdown(struct uart_port *port)
-{
- /* disable interrupst */
- sc26xx_disable_irq(port, IMR_TXRDY | IMR_RXRDY);
-
- /* stop tx/rx */
- WRITE_SC_PORT(port, CR, CR_DIS_TX | CR_DIS_RX);
-}
-
-static int wait_tx_empty(struct uart_port *port)
-{
- int i;
- u8 sr;
- u8 bits = SR_TXEMT | SR_TXRDY;
-
- for (i = 0; i < 10000; i++) {
- sr = READ_SC_PORT(port, SR);
- if ((sr & bits) == bits)
- return 0;
- udelay(2);
- }
- dev_warn(port->dev, "Timed out waiting for TX Empty sr=%02X\n", sr);
- return -1;
-}
-
-static u8 find_csr(struct uart_sc26xx_port *up, unsigned int baud)
-{
- int i, found = -1;
-
- for (i = 0; i < NR_BAUDS; i++) {
- if (up->baud_rates[i] == baud) {
- found = i;
- break;
- }
- }
-
- if (found == -1) {
- found = DEFAULT_BAUD_INDEX;
- dev_warn(up->port[0].dev,
- "%d baud not available using %d\n",
- baud, up->baud_rates[found]);
- }
-
- return (u8)found | ((u8)found << 4);
-}
-
-/* port->lock is not held. */
-static void sc26xx_set_termios(struct uart_port *port, struct ktermios *termios,
- struct ktermios *old)
-{
- struct uart_sc26xx_port *up = driver_info(port);
- unsigned int baud = uart_get_baud_rate(port, termios, old, 0, 4000000);
- unsigned int iflag, cflag;
- unsigned long flags;
- u8 mr1, mr2, csr;
-
- spin_lock_irqsave(&port->lock, flags);
-
- if (wait_tx_empty(port))
- goto out;
-
- WRITE_SC_PORT(port, CR, CR_DIS_TX | CR_DIS_RX);
-
- iflag = termios->c_iflag;
- cflag = termios->c_cflag;
-
- port->read_status_mask = SR_OVERRUN;
- if (iflag & INPCK)
- port->read_status_mask |= SR_PARITY | SR_FRAME;
- if (iflag & (BRKINT | PARMRK))
- port->read_status_mask |= SR_BREAK;
-
- port->ignore_status_mask = 0;
- if (iflag & IGNBRK)
- port->ignore_status_mask |= SR_BREAK;
- if ((cflag & CREAD) == 0)
- port->ignore_status_mask |= SR_BREAK | SR_FRAME |
- SR_PARITY | SR_OVERRUN;
-
- switch (cflag & CSIZE) {
- case CS5:
- mr1 = 0x00;
- break;
- case CS6:
- mr1 = 0x01;
- break;
- case CS7:
- mr1 = 0x02;
- break;
- default:
- case CS8:
- mr1 = 0x03;
- break;
- }
- mr2 = 0x07;
- if (cflag & CSTOPB)
- mr2 = 0x0f;
- if (cflag & PARENB) {
- if (cflag & PARODD)
- mr1 |= (1 << 2);
- } else
- mr1 |= (2 << 3);
-
- mr1 |= up->chip->init_mr1;
- csr = find_csr(up, baud);
-
- if (up->chip->has_mr0) {
- u8 mr0a = read_mr0(port, 0);
- mr0a &= ~MR0_BAUD_MODE;
- mr0a |= up->mr0_baud;
- write_mr0(port, 0, mr0a);
- }
-
- write_cmd_port(port, CR_RES_MR);
- WRITE_SC_PORT(port, MRx, mr1);
- WRITE_SC_PORT(port, MRx, mr2);
-
- WRITE_SC(port, ACR, up->acr);
- WRITE_SC_PORT(port, CSR, csr);
-
- /* reset tx and rx */
- write_cmd_port(port, CR_RES_RX);
- write_cmd_port(port, CR_RES_TX);
-
- WRITE_SC_PORT(port, CR, CR_ENA_TX | CR_ENA_RX);
- if (wait_tx_empty(port))
- goto out;
-
- uart_update_timeout(port, cflag, baud);
-out:
- spin_unlock_irqrestore(&port->lock, flags);
-}
-
-static const char *sc26xx_type(struct uart_port *port)
-{
- return driver_info(port)->chip->name;
-}
-
-static void sc26xx_release_port(struct uart_port *port)
-{
-}
-
-static int sc26xx_request_port(struct uart_port *port)
-{
- return 0;
-}
-
-static void sc26xx_config_port(struct uart_port *port, int flags)
-{
-}
-
-static int sc26xx_verify_port(struct uart_port *port, struct serial_struct *ser)
-{
- return -EINVAL;
-}
-
-static struct uart_ops sc26xx_ops = {
- .tx_empty = sc26xx_tx_empty,
- .set_mctrl = sc26xx_set_mctrl,
- .get_mctrl = sc26xx_get_mctrl,
- .stop_tx = sc26xx_stop_tx,
- .start_tx = sc26xx_start_tx,
- .stop_rx = sc26xx_stop_rx,
- .enable_ms = sc26xx_enable_ms,
- .break_ctl = sc26xx_break_ctl,
- .startup = sc26xx_startup,
- .shutdown = sc26xx_shutdown,
- .set_termios = sc26xx_set_termios,
- .type = sc26xx_type,
- .release_port = sc26xx_release_port,
- .request_port = sc26xx_request_port,
- .config_port = sc26xx_config_port,
- .verify_port = sc26xx_verify_port,
-};
-
-static struct uart_port *sc26xx_port;
-
-#ifdef CONFIG_SERIAL_SC26XX_CONSOLE
-static void sc26xx_console_putchar(struct uart_port *port, char c)
-{
- unsigned long flags;
- int limit = 1000000;
-
- spin_lock_irqsave(&port->lock, flags);
-
- while (limit-- > 0) {
- if (READ_SC_PORT(port, SR) & SR_TXRDY) {
- WRITE_SC_PORT(port, THR, c);
- break;
- }
- udelay(2);
- }
-
- spin_unlock_irqrestore(&port->lock, flags);
-}
-
-static void sc26xx_console_write(struct console *con, const char *s, unsigned n)
-{
- struct uart_port *port = sc26xx_port;
- int i;
-
- for (i = 0; i < n; i++) {
- if (*s == '\n')
- sc26xx_console_putchar(port, '\r');
- sc26xx_console_putchar(port, *s++);
- }
-}
-
-static int __init sc26xx_console_setup(struct console *con, char *options)
-{
- struct uart_port *port = sc26xx_port;
- int baud = 9600;
- int bits = 8;
- int parity = 'n';
- int flow = 'n';
-
- if (port->type != PORT_SC26XX)
- return -1;
-
- printk(KERN_INFO "Console: ttySC%d (SC26XX)\n", con->index);
- if (options)
- uart_parse_options(options, &baud, &parity, &bits, &flow);
-
- return uart_set_options(port, con, baud, parity, bits, flow);
-}
-
-static struct uart_driver sc26xx_reg;
-static struct console sc26xx_console = {
- .name = "ttySC",
- .write = sc26xx_console_write,
- .device = uart_console_device,
- .setup = sc26xx_console_setup,
- .flags = CON_PRINTBUFFER,
- .index = -1,
- .data = &sc26xx_reg,
-};
-#define SC26XX_CONSOLE &sc26xx_console
-#else
-#define SC26XX_CONSOLE NULL
-#endif
-
-static struct uart_driver sc26xx_reg = {
- .owner = THIS_MODULE,
- .driver_name = "SC26xx",
- .dev_name = "ttySC",
- .major = SC26XX_MAJOR,
- .minor = SC26XX_MINOR_START,
- .nr = SC26XX_NR,
- .cons = SC26XX_CONSOLE,
-};
-
-static u8 sc26xx_flags2mask(unsigned int flags, unsigned int bitpos)
-{
- unsigned int bit = (flags >> bitpos) & 15;
-
- return bit ? (1 << (bit - 1)) : 0;
-}
-
-static void __devinit sc26xx_init_masks(struct uart_sc26xx_port *up,
- int line, unsigned int data)
-{
- up->dtr_mask[line] = sc26xx_flags2mask(data, 0);
- up->rts_mask[line] = sc26xx_flags2mask(data, 4);
- up->dsr_mask[line] = sc26xx_flags2mask(data, 8);
- up->cts_mask[line] = sc26xx_flags2mask(data, 12);
- up->dcd_mask[line] = sc26xx_flags2mask(data, 16);
- up->ri_mask[line] = sc26xx_flags2mask(data, 20);
-}
-
-static int __devinit init_baudgroup(struct uart_sc26xx_port *up)
-{
- struct plat_serial_sc2xxx *pdata = up->port[0].dev->platform_data;
-
- u8 baud_mode = up->chip->default_baud_mode;
- u8 baud_group = up->chip->default_baud_group;
-
- if (pdata->baud_mode > 0)
- baud_mode = pdata->baud_mode - 1;
-
- if (pdata->baud_group > 0)
- baud_group = pdata->baud_group - 1;
-
- if (baud_mode > up->chip->max_baud_mode) {
- printk(KERN_ERR "Baud mode %d not supported for %s\n",
- baud_mode, up->chip->name);
- return -EINVAL;
- }
-
- up->acr = baud_group ? 0x80 : 0;
- up->baud_rates = baud_rates[baud_mode][baud_group];
-
- switch (baud_mode) {
- case 0:
- up->mr0_baud = 0;
- break;
- case 1:
- up->mr0_baud = 1;
- break;
- case 2:
- up->mr0_baud = 4;
- break;
- }
- return 0;
-}
-
-static const struct chip_def * __devinit chip_by_name(const char *name)
-{
- int i;
- const struct chip_def *chip;
-
- for (i = 0; i < ARRAY_SIZE(chips); i++) {
- chip = chips[i];
- if (!strcmp(chip->name, name))
- return chip;
- }
-
- return NULL;
-}
-
-static const struct chip_def * __devinit detect_chip_type(
- struct uart_sc26xx_port *up)
-{
- struct uart_port *port = &up->port[0];
- struct chip_def *chip;
- int i;
- u8 mrx[3];
-
- /* Code below needs to be tested on 26xx hardware
- * Idea is that 26xx will ignore SEL_MR0 so 2nd and 3rd reads
- * will return same data.*/
- write_cmd_port(port, CR_RES_MR); /* MR1 */
- write_cmd_port(port, CR_SEL_MR0); /* Ignored on 26xx */
-
- for (i = 0; i < 3; i++)
- mrx[i] = READ_SC_PORT(port, MRx);
-
- if (mrx[1] == mrx[2])
- chip = &chip_26xx;
- else
- chip = &chip_2892;
-
- dev_info(port->dev, "Autodetected %s\n", chip->name);
- return chip;
-}
-
-static void __devinit hw_init(struct uart_port *port)
-{
- u8 mr;
-
- /* Sometimes on cold boot MR1,MR2 are 0xFF (reset problem?)
- * Initialise if channel mode in MR2 is not normal otherwise
- * assume bootloader has done the init.
- */
- write_cmd_port(port, CR_RES_MR); /* MR1 */
- READ_SC_PORT(port, MRx); /* skip MR1 */
- mr = READ_SC_PORT(port, MRx);
- if (mr & 0xC0) {
- write_cmd_port(port, CR_RES_MR);
-
- /* Values below are arbitary (will be changed by set_termios)
- * but must be different so that chip detection works */
- WRITE_SC_PORT(port, MRx, 0x10);
- WRITE_SC_PORT(port, MRx, 0x00);
- }
-}
-
-static int __devinit sc26xx_probe(struct platform_device *dev)
-{
- struct resource *res, *irq_res;
- struct uart_sc26xx_port *up;
- struct plat_serial_sc2xxx *pdata = dev->dev.platform_data;
- int err;
-
- if (!pdata) {
- dev_err(&dev->dev, "No platform data\n");
- return -EINVAL;
- }
-
- res = platform_get_resource(dev, IORESOURCE_MEM, 0);
- if (!res)
- return -ENODEV;
-
- irq_res = platform_get_resource(dev, IORESOURCE_IRQ, 0);
- if (!irq_res)
- return -ENXIO;
-
- up = kzalloc(sizeof *up, GFP_KERNEL);
- if (unlikely(!up))
- return -ENOMEM;
-
- up->port[0].line = 0;
- up->port[0].ops = &sc26xx_ops;
- up->port[0].type = PORT_SC26XX;
- up->port[0].uartclk = (29491200 / 16); /* arbitrary */
-
- up->port[0].mapbase = res->start;
- up->port[0].membase = ioremap_nocache(up->port[0].mapbase, 0x40);
- up->port[0].iotype = UPIO_MEM;
- up->port[0].irq = irq_res->start;
-
- up->port[0].dev = &dev->dev;
-
- sc26xx_init_masks(up, 0, pdata->signal_map[0]);
- hw_init(&up->port[0]);
-
- sc26xx_port = &up->port[0];
-
- memcpy(&up->port[1], &up->port[0], sizeof(up->port[0]));
- up->port[1].line = 1;
-
- sc26xx_init_masks(up, 1, pdata->signal_map[1]);
- hw_init(&up->port[1]);
-
- if (pdata->chip_name)
- up->chip = chip_by_name(pdata->chip_name);
- if (!up->chip) {
- if (pdata->chip_name)
- dev_warn(&dev->dev,
- "Unknown chip %s requested - use autodetect\n",
- pdata->chip_name);
- up->chip = detect_chip_type(up);
- }
-
- err = init_baudgroup(up);
- if (err)
- goto out_free_port;
-
- err = uart_register_driver(&sc26xx_reg);
- if (err)
- goto out_free_port;
-
- err = uart_add_one_port(&sc26xx_reg, &up->port[0]);
- if (err)
- goto out_unregister_driver;
-
- err = uart_add_one_port(&sc26xx_reg, &up->port[1]);
- if (err)
- goto out_remove_port0;
-
- err = request_irq(up->port[0].irq, sc26xx_interrupt,
- irq_res->flags & IRQF_TRIGGER_MASK, "sc26xx", up);
- if (err)
- goto out_remove_ports;
-
- dev_set_drvdata(&dev->dev, up);
- return 0;
-
-out_remove_ports:
- uart_remove_one_port(&sc26xx_reg, &up->port[1]);
-out_remove_port0:
- uart_remove_one_port(&sc26xx_reg, &up->port[0]);
-
-out_unregister_driver:
- uart_unregister_driver(&sc26xx_reg);
-
-out_free_port:
- kfree(up);
- sc26xx_port = NULL;
- return err;
-}
-
-
-static int __devexit sc26xx_driver_remove(struct platform_device *dev)
-{
- struct uart_sc26xx_port *up = dev_get_drvdata(&dev->dev);
-
- free_irq(up->port[0].irq, up);
-
- uart_remove_one_port(&sc26xx_reg, &up->port[0]);
- uart_remove_one_port(&sc26xx_reg, &up->port[1]);
-
- uart_unregister_driver(&sc26xx_reg);
-
- kfree(up);
- sc26xx_port = NULL;
-
- dev_set_drvdata(&dev->dev, NULL);
- return 0;
-}
-
-static struct platform_driver sc26xx_driver = {
- .probe = sc26xx_probe,
- .remove = __devexit_p(sc26xx_driver_remove),
- .driver = {
- .name = "SC26xx",
- .owner = THIS_MODULE,
- },
-};
-
-static int __init sc26xx_init(void)
-{
- return platform_driver_register(&sc26xx_driver);
-}
-
-static void __exit sc26xx_exit(void)
-{
- platform_driver_unregister(&sc26xx_driver);
-}
-
-module_init(sc26xx_init);
-module_exit(sc26xx_exit);
-
-
-MODULE_AUTHOR("Thomas Bogendörfer");
-MODULE_DESCRIPTION("SC681/SC2692 serial driver");
-MODULE_VERSION("1.0");
-MODULE_LICENSE("GPL");
-MODULE_ALIAS("platform:SC26xx");
diff --git a/drivers/serial/sc2xxx.c b/drivers/serial/sc2xxx.c
new file mode 100644
index 0000000..3e87c37
--- /dev/null
+++ b/drivers/serial/sc2xxx.c
@@ -0,0 +1,998 @@
+/*
+ * SC2xxx.c: Serial driver for Philips SC2X81/SC2X92/SC2892 devices.
+ *
+ * Copyright (C) 2006,2007 Thomas Bogendörfer (tsbogend@alpha.franken.de)
+ * SC2892 support by Martin Fuzzey (mfuzzey@gmail.com)
+ */
+
+#include <linux/module.h>
+#include <linux/kernel.h>
+#include <linux/errno.h>
+#include <linux/tty.h>
+#include <linux/tty_flip.h>
+#include <linux/major.h>
+#include <linux/circ_buf.h>
+#include <linux/serial.h>
+#include <linux/sysrq.h>
+#include <linux/console.h>
+#include <linux/spinlock.h>
+#include <linux/slab.h>
+#include <linux/delay.h>
+#include <linux/init.h>
+#include <linux/platform_device.h>
+#include <linux/irq.h>
+#include <linux/io.h>
+#include <linux/serial_sc2xxx.h>
+
+#if defined(CONFIG_MAGIC_SYSRQ)
+#define SUPPORT_SYSRQ
+#endif
+
+#include <linux/serial_core.h>
+
+#define SC2XXX_MAJOR 204
+#define SC2XXX_MINOR_START 205
+#define SC2XXX_NR 2
+
+struct chip_def {
+ u8 has_mr0;
+ u8 init_mr0;
+ u8 init_mr1;
+ u8 max_baud_mode;
+ u8 default_baud_mode;
+ u8 default_baud_group;
+ const char *name;
+};
+
+struct uart_sc2xxx_port {
+ struct uart_port port[2];
+ u8 dsr_mask[2];
+ u8 cts_mask[2];
+ u8 dcd_mask[2];
+ u8 ri_mask[2];
+ u8 dtr_mask[2];
+ u8 rts_mask[2];
+ u8 imr;
+ u8 acr;
+ u8 mr0_baud;
+ const unsigned int *baud_rates;
+ const struct chip_def *chip;
+};
+
+/* register common to both ports */
+#define RD_ISR 0x14
+#define RD_IPR 0x34
+
+#define WR_ACR 0x10
+#define WR_IMR 0x14
+#define WR_OPCR 0x34
+#define WR_OPR_SET 0x38
+#define WR_OPR_CLR 0x3C
+
+/* access common register */
+#define READ_SC(p, r) readb((p)->membase + RD_##r)
+#define WRITE_SC(p, r, v) writeb((v), (p)->membase + WR_##r)
+
+/* register per port */
+#define RD_PORT_MRx 0x00
+#define RD_PORT_SR 0x04
+#define RD_PORT_RHR 0x0c
+
+#define WR_PORT_MRx 0x00
+#define WR_PORT_CSR 0x04
+#define WR_PORT_CR 0x08
+#define WR_PORT_THR 0x0c
+
+/* SR bits */
+#define SR_BREAK (1 << 7)
+#define SR_FRAME (1 << 6)
+#define SR_PARITY (1 << 5)
+#define SR_OVERRUN (1 << 4)
+#define SR_TXEMT (1 << 3)
+#define SR_TXRDY (1 << 2)
+#define SR_RXRDY (1 << 0)
+
+#define CR_RES_MR (1 << 4)
+#define CR_RES_RX (2 << 4)
+#define CR_RES_TX (3 << 4)
+#define CR_STRT_BRK (6 << 4)
+#define CR_STOP_BRK (7 << 4)
+#define CR_SEL_MR0 (11 << 4)
+#define CR_DIS_TX (1 << 3)
+#define CR_ENA_TX (1 << 2)
+#define CR_DIS_RX (1 << 1)
+#define CR_ENA_RX (1 << 0)
+
+/* ISR bits */
+#define ISR_RXRDYB (1 << 5)
+#define ISR_TXRDYB (1 << 4)
+#define ISR_RXRDYA (1 << 1)
+#define ISR_TXRDYA (1 << 0)
+
+/* IMR bits */
+#define IMR_RXRDY (1 << 1)
+#define IMR_TXRDY (1 << 0)
+
+/* MR0 bits (>= 28L92 only */
+#define MR0_WATCHDOG (1 << 7)
+#define MR0_RXINT2 (1 << 6)
+#define MR0_TXINT(x) ((x) << 4)
+#define MR0_FIFO_SIZE (1 << 3)
+#define MR0_BAUD_MODE ((1 << 2) + (1 << 0))
+
+
+#define NR_BAUD_GROUPS 2
+#define NR_BAUD_MODES 3
+#define NR_BAUDS 13
+#define DEFAULT_BAUD_INDEX 11
+static const unsigned baud_rates[NR_BAUD_MODES][NR_BAUD_GROUPS][NR_BAUDS] = {
+ {
+ /* Normal mode ACR[7] = 0 */
+ {50, 110, 134, 200, 300, 600, 1200, 1050,
+ 2400, 4800, 7200, 9600, 38400},
+
+ /* Normal mode ACR[7] = 1 */
+ {75, 110, 134, 150, 300, 600, 1200, 2000,
+ 2400, 4800, 1800, 9600, 19200},
+ }, {
+ /* Extended mode 1 ACR[7] = 0 */
+ {300, 110, 134, 1200, 1800, 3600, 7200, 1050,
+ 14400, 28800, 7200, 57600, 230400},
+
+ /* Extended mode 1 ACR[7] = 1 */
+ {450, 110, 134, 900, 1800, 3600, 72000, 2000,
+ 14400, 28800, 1800, 57600, 115200},
+ }, {
+ /* Extended mode 2 ACR[7] = 0 */
+ {4800, 880, 1076, 19200, 28800, 57600, 115200, 1050,
+ 57600, 4800, 57600, 9600, 38400},
+
+ /* Extended mode 2 ACR[7] = 1 */
+ {7200, 880, 1076, 14400, 28800, 57600, 115200, 2000,
+ 57600, 4800, 14400, 9600, 19200},
+ }
+};
+
+static struct chip_def chip_2xxx = {
+ .name = "SC2XXX",
+ .max_baud_mode = 0,
+ .default_baud_mode = 0,
+ .default_baud_group = 1,
+ .has_mr0 = 0,
+ .init_mr1 = 0,
+};
+
+static struct chip_def chip_2892 = {
+ .name = "SC2892",
+ .max_baud_mode = 2,
+ .default_baud_mode = 2,
+ .default_baud_group = 0,
+ .has_mr0 = 1,
+ .init_mr0 = MR0_WATCHDOG | MR0_FIFO_SIZE | MR0_TXINT(1),
+ .init_mr1 = (1 << 6),
+};
+
+static const struct chip_def *chips[] = {
+ &chip_2xxx,
+ &chip_2892
+};
+
+static struct uart_sc2xxx_port *driver_info(struct uart_port *port)
+{
+ port -= port->line;
+ return container_of(port, struct uart_sc2xxx_port, port[0]);
+}
+
+/* access port register */
+static inline u8 read_sc_line(struct uart_port *p, int line, u8 reg)
+{
+ return readb(p->membase + line * 0x20 + reg);
+}
+
+static inline u8 read_sc_port(struct uart_port *p, u8 reg)
+{
+ return read_sc_line(p, p->line, reg);
+}
+
+static inline void write_sc_line(struct uart_port *p, int line, u8 reg, u8 val)
+{
+ writeb(val, p->membase + line * 0x20 + reg);
+}
+
+static inline void write_sc_port(struct uart_port *p, u8 reg, u8 val)
+{
+ write_sc_line(p, p->line, reg, val);
+}
+
+#define READ_SC_PORT(p, r) read_sc_port(p, RD_PORT_##r)
+#define WRITE_SC_PORT(p, r, v) write_sc_port(p, WR_PORT_##r, v)
+
+static void write_cmd_line(struct uart_port *port, int line, u8 cmd)
+{
+ int i;
+
+ write_sc_line(port, line, WR_PORT_CR, cmd);
+
+ /* According to data sheet require 3 NOPs before next command */
+ for (i = 0; i < 3; i++)
+ write_sc_line(port, line, WR_PORT_CR, 0);
+}
+
+static inline void write_cmd_port(struct uart_port *port, u8 cmd)
+{
+ write_cmd_line(port, port->line, cmd);
+}
+
+
+static u8 read_mr0(struct uart_port *port, int line)
+{
+ write_cmd_line(port, line, CR_SEL_MR0);
+ return read_sc_line(port, line, RD_PORT_MRx);
+}
+
+static void write_mr0(struct uart_port *port, int line, u8 val)
+{
+ write_cmd_line(port, line, CR_SEL_MR0);
+ write_sc_line(port, line, WR_PORT_MRx, val);
+}
+
+static void sc2xxx_enable_irq(struct uart_port *port, int mask)
+{
+ struct uart_sc2xxx_port *up = driver_info(port);
+
+ up->imr |= mask << (port->line * 4);
+ WRITE_SC(port, IMR, up->imr);
+}
+
+static void sc2xxx_disable_irq(struct uart_port *port, int mask)
+{
+ struct uart_sc2xxx_port *up = driver_info(port);
+
+ up->imr &= ~(mask << (port->line * 4));
+ WRITE_SC(port, IMR, up->imr);
+}
+
+static struct tty_struct *receive_chars(struct uart_port *port)
+{
+ struct tty_struct *tty = NULL;
+ int limit = 10000;
+ unsigned char ch;
+ char flag;
+ u8 status;
+
+ if (port->state != NULL) /* Unopened serial console */
+ tty = port->state->port.tty;
+
+ while (limit-- > 0) {
+ status = READ_SC_PORT(port, SR);
+ if (!(status & SR_RXRDY))
+ break;
+ ch = READ_SC_PORT(port, RHR);
+
+ flag = TTY_NORMAL;
+ port->icount.rx++;
+
+ if (unlikely(status & (SR_BREAK | SR_FRAME |
+ SR_PARITY | SR_OVERRUN))) {
+ if (status & SR_BREAK) {
+ status &= ~(SR_PARITY | SR_FRAME);
+ port->icount.brk++;
+ if (uart_handle_break(port))
+ continue;
+ } else if (status & SR_PARITY)
+ port->icount.parity++;
+ else if (status & SR_FRAME)
+ port->icount.frame++;
+ if (status & SR_OVERRUN)
+ port->icount.overrun++;
+
+ status &= port->read_status_mask;
+ if (status & SR_BREAK)
+ flag = TTY_BREAK;
+ else if (status & SR_PARITY)
+ flag = TTY_PARITY;
+ else if (status & SR_FRAME)
+ flag = TTY_FRAME;
+ }
+
+ if (uart_handle_sysrq_char(port, ch))
+ continue;
+
+ if (status & port->ignore_status_mask)
+ continue;
+
+ if (tty)
+ tty_insert_flip_char(tty, ch, flag);
+ }
+ return tty;
+}
+
+static void transmit_chars(struct uart_port *port)
+{
+ struct circ_buf *xmit;
+
+ if (!port->state)
+ return;
+
+ xmit = &port->state->xmit;
+ if (uart_circ_empty(xmit) || uart_tx_stopped(port)) {
+ sc2xxx_disable_irq(port, IMR_TXRDY);
+ return;
+ }
+ while (!uart_circ_empty(xmit)) {
+ if (!(READ_SC_PORT(port, SR) & SR_TXRDY))
+ break;
+
+ WRITE_SC_PORT(port, THR, xmit->buf[xmit->tail]);
+ xmit->tail = (xmit->tail + 1) & (UART_XMIT_SIZE - 1);
+ port->icount.tx++;
+ }
+ if (uart_circ_chars_pending(xmit) < WAKEUP_CHARS)
+ uart_write_wakeup(port);
+}
+
+static irqreturn_t sc2xxx_interrupt(int irq, void *dev_id)
+{
+ struct uart_sc2xxx_port *up = dev_id;
+ struct tty_struct *tty;
+ unsigned long flags;
+ u8 isr;
+
+ spin_lock_irqsave(&up->port[0].lock, flags);
+
+ tty = NULL;
+ isr = READ_SC(&up->port[0], ISR);
+ if (isr & ISR_TXRDYA)
+ transmit_chars(&up->port[0]);
+ if (isr & ISR_RXRDYA)
+ tty = receive_chars(&up->port[0]);
+
+ spin_unlock(&up->port[0].lock);
+
+ if (tty)
+ tty_flip_buffer_push(tty);
+
+ spin_lock(&up->port[1].lock);
+
+ tty = NULL;
+ if (isr & ISR_TXRDYB)
+ transmit_chars(&up->port[1]);
+ if (isr & ISR_RXRDYB)
+ tty = receive_chars(&up->port[1]);
+
+ spin_unlock_irqrestore(&up->port[1].lock, flags);
+
+ if (tty)
+ tty_flip_buffer_push(tty);
+
+ return IRQ_HANDLED;
+}
+
+/* port->lock is not held. */
+static unsigned int sc2xxx_tx_empty(struct uart_port *port)
+{
+ return (READ_SC_PORT(port, SR) & SR_TXRDY) ? TIOCSER_TEMT : 0;
+}
+
+/* port->lock held by caller. */
+static void sc2xxx_set_mctrl(struct uart_port *port, unsigned int mctrl)
+{
+ struct uart_sc2xxx_port *up = driver_info(port);
+ int line = port->line;
+
+ if (up->dtr_mask[line]) {
+ if (mctrl & TIOCM_DTR)
+ WRITE_SC(port, OPR_SET, up->dtr_mask[line]);
+ else
+ WRITE_SC(port, OPR_CLR, up->dtr_mask[line]);
+ }
+ if (up->rts_mask[line]) {
+ if (mctrl & TIOCM_RTS)
+ WRITE_SC(port, OPR_SET, up->rts_mask[line]);
+ else
+ WRITE_SC(port, OPR_CLR, up->rts_mask[line]);
+ }
+}
+
+/* port->lock is held by caller and interrupts are disabled. */
+static unsigned int sc2xxx_get_mctrl(struct uart_port *port)
+{
+ struct uart_sc2xxx_port *up = driver_info(port);
+ int line = port->line;
+ unsigned int mctrl = TIOCM_DSR | TIOCM_CTS | TIOCM_CAR;
+ u8 ipr;
+
+ ipr = READ_SC(port, IPR) ^ 0xff;
+
+ if (up->dsr_mask[line]) {
+ mctrl &= ~TIOCM_DSR;
+ mctrl |= ipr & up->dsr_mask[line] ? TIOCM_DSR : 0;
+ }
+ if (up->cts_mask[line]) {
+ mctrl &= ~TIOCM_CTS;
+ mctrl |= ipr & up->cts_mask[line] ? TIOCM_CTS : 0;
+ }
+ if (up->dcd_mask[line]) {
+ mctrl &= ~TIOCM_CAR;
+ mctrl |= ipr & up->dcd_mask[line] ? TIOCM_CAR : 0;
+ }
+ if (up->ri_mask[line]) {
+ mctrl &= ~TIOCM_RNG;
+ mctrl |= ipr & up->ri_mask[line] ? TIOCM_RNG : 0;
+ }
+ return mctrl;
+}
+
+/* port->lock held by caller. */
+static void sc2xxx_stop_tx(struct uart_port *port)
+{
+ return;
+}
+
+/* port->lock held by caller. */
+static void sc2xxx_start_tx(struct uart_port *port)
+{
+ struct circ_buf *xmit = &port->state->xmit;
+
+ while (!uart_circ_empty(xmit)) {
+ if (!(READ_SC_PORT(port, SR) & SR_TXRDY)) {
+ sc2xxx_enable_irq(port, IMR_TXRDY);
+ break;
+ }
+ WRITE_SC_PORT(port, THR, xmit->buf[xmit->tail]);
+ xmit->tail = (xmit->tail + 1) & (UART_XMIT_SIZE - 1);
+ port->icount.tx++;
+ }
+}
+
+/* port->lock held by caller. */
+static void sc2xxx_stop_rx(struct uart_port *port)
+{
+}
+
+/* port->lock held by caller. */
+static void sc2xxx_enable_ms(struct uart_port *port)
+{
+}
+
+/* port->lock is not held. */
+static void sc2xxx_break_ctl(struct uart_port *port, int break_state)
+{
+ if (break_state == -1)
+ write_cmd_port(port, CR_STRT_BRK);
+ else
+ write_cmd_port(port, CR_STOP_BRK);
+}
+
+/* port->lock is not held. */
+static int sc2xxx_startup(struct uart_port *port)
+{
+ struct uart_sc2xxx_port *up = driver_info(port);
+
+ sc2xxx_disable_irq(port, IMR_TXRDY | IMR_RXRDY);
+ WRITE_SC(port, OPCR, 0);
+
+ /* reset tx and rx */
+ write_cmd_port(port, CR_RES_RX);
+ write_cmd_port(port, CR_RES_TX);
+
+ if (up->chip->has_mr0)
+ write_mr0(port, port->line, up->chip->init_mr0);
+
+ /* start rx/tx */
+ WRITE_SC_PORT(port, CR, CR_ENA_TX | CR_ENA_RX);
+
+ /* enable irqs */
+ sc2xxx_enable_irq(port, IMR_RXRDY);
+ return 0;
+}
+
+/* port->lock is not held. */
+static void sc2xxx_shutdown(struct uart_port *port)
+{
+ /* disable interrupst */
+ sc2xxx_disable_irq(port, IMR_TXRDY | IMR_RXRDY);
+
+ /* stop tx/rx */
+ WRITE_SC_PORT(port, CR, CR_DIS_TX | CR_DIS_RX);
+}
+
+static int wait_tx_empty(struct uart_port *port)
+{
+ int i;
+ u8 sr;
+ u8 bits = SR_TXEMT | SR_TXRDY;
+
+ for (i = 0; i < 10000; i++) {
+ sr = READ_SC_PORT(port, SR);
+ if ((sr & bits) == bits)
+ return 0;
+ udelay(2);
+ }
+ dev_warn(port->dev, "Timed out waiting for TX Empty sr=%02X\n", sr);
+ return -1;
+}
+
+static u8 find_csr(struct uart_sc2xxx_port *up, unsigned int baud)
+{
+ int i, found = -1;
+
+ for (i = 0; i < NR_BAUDS; i++) {
+ if (up->baud_rates[i] == baud) {
+ found = i;
+ break;
+ }
+ }
+
+ if (found == -1) {
+ found = DEFAULT_BAUD_INDEX;
+ dev_warn(up->port[0].dev,
+ "%d baud not available using %d\n",
+ baud, up->baud_rates[found]);
+ }
+
+ return (u8)found | ((u8)found << 4);
+}
+
+/* port->lock is not held. */
+static void sc2xxx_set_termios(struct uart_port *port, struct ktermios *termios,
+ struct ktermios *old)
+{
+ struct uart_sc2xxx_port *up = driver_info(port);
+ unsigned int baud = uart_get_baud_rate(port, termios, old, 0, 4000000);
+ unsigned int iflag, cflag;
+ unsigned long flags;
+ u8 mr1, mr2, csr;
+
+ spin_lock_irqsave(&port->lock, flags);
+
+ if (wait_tx_empty(port))
+ goto out;
+
+ WRITE_SC_PORT(port, CR, CR_DIS_TX | CR_DIS_RX);
+
+ iflag = termios->c_iflag;
+ cflag = termios->c_cflag;
+
+ port->read_status_mask = SR_OVERRUN;
+ if (iflag & INPCK)
+ port->read_status_mask |= SR_PARITY | SR_FRAME;
+ if (iflag & (BRKINT | PARMRK))
+ port->read_status_mask |= SR_BREAK;
+
+ port->ignore_status_mask = 0;
+ if (iflag & IGNBRK)
+ port->ignore_status_mask |= SR_BREAK;
+ if ((cflag & CREAD) == 0)
+ port->ignore_status_mask |= SR_BREAK | SR_FRAME |
+ SR_PARITY | SR_OVERRUN;
+
+ switch (cflag & CSIZE) {
+ case CS5:
+ mr1 = 0x00;
+ break;
+ case CS6:
+ mr1 = 0x01;
+ break;
+ case CS7:
+ mr1 = 0x02;
+ break;
+ default:
+ case CS8:
+ mr1 = 0x03;
+ break;
+ }
+ mr2 = 0x07;
+ if (cflag & CSTOPB)
+ mr2 = 0x0f;
+ if (cflag & PARENB) {
+ if (cflag & PARODD)
+ mr1 |= (1 << 2);
+ } else
+ mr1 |= (2 << 3);
+
+ mr1 |= up->chip->init_mr1;
+ csr = find_csr(up, baud);
+
+ if (up->chip->has_mr0) {
+ u8 mr0a = read_mr0(port, 0);
+ mr0a &= ~MR0_BAUD_MODE;
+ mr0a |= up->mr0_baud;
+ write_mr0(port, 0, mr0a);
+ }
+
+ write_cmd_port(port, CR_RES_MR);
+ WRITE_SC_PORT(port, MRx, mr1);
+ WRITE_SC_PORT(port, MRx, mr2);
+
+ WRITE_SC(port, ACR, up->acr);
+ WRITE_SC_PORT(port, CSR, csr);
+
+ /* reset tx and rx */
+ write_cmd_port(port, CR_RES_RX);
+ write_cmd_port(port, CR_RES_TX);
+
+ WRITE_SC_PORT(port, CR, CR_ENA_TX | CR_ENA_RX);
+ if (wait_tx_empty(port))
+ goto out;
+
+ uart_update_timeout(port, cflag, baud);
+out:
+ spin_unlock_irqrestore(&port->lock, flags);
+}
+
+static const char *sc2xxx_type(struct uart_port *port)
+{
+ return driver_info(port)->chip->name;
+}
+
+static void sc2xxx_release_port(struct uart_port *port)
+{
+}
+
+static int sc2xxx_request_port(struct uart_port *port)
+{
+ return 0;
+}
+
+static void sc2xxx_config_port(struct uart_port *port, int flags)
+{
+}
+
+static int sc2xxx_verify_port(struct uart_port *port, struct serial_struct *ser)
+{
+ return -EINVAL;
+}
+
+static struct uart_ops sc2xxx_ops = {
+ .tx_empty = sc2xxx_tx_empty,
+ .set_mctrl = sc2xxx_set_mctrl,
+ .get_mctrl = sc2xxx_get_mctrl,
+ .stop_tx = sc2xxx_stop_tx,
+ .start_tx = sc2xxx_start_tx,
+ .stop_rx = sc2xxx_stop_rx,
+ .enable_ms = sc2xxx_enable_ms,
+ .break_ctl = sc2xxx_break_ctl,
+ .startup = sc2xxx_startup,
+ .shutdown = sc2xxx_shutdown,
+ .set_termios = sc2xxx_set_termios,
+ .type = sc2xxx_type,
+ .release_port = sc2xxx_release_port,
+ .request_port = sc2xxx_request_port,
+ .config_port = sc2xxx_config_port,
+ .verify_port = sc2xxx_verify_port,
+};
+
+static struct uart_port *sc2xxx_port;
+
+#ifdef CONFIG_SERIAL_SC2XXX_CONSOLE
+static void sc2xxx_console_putchar(struct uart_port *port, char c)
+{
+ unsigned long flags;
+ int limit = 1000000;
+
+ spin_lock_irqsave(&port->lock, flags);
+
+ while (limit-- > 0) {
+ if (READ_SC_PORT(port, SR) & SR_TXRDY) {
+ WRITE_SC_PORT(port, THR, c);
+ break;
+ }
+ udelay(2);
+ }
+
+ spin_unlock_irqrestore(&port->lock, flags);
+}
+
+static void sc2xxx_console_write(struct console *con, const char *s, unsigned n)
+{
+ struct uart_port *port = sc2xxx_port;
+ int i;
+
+ for (i = 0; i < n; i++) {
+ if (*s == '\n')
+ sc2xxx_console_putchar(port, '\r');
+ sc2xxx_console_putchar(port, *s++);
+ }
+}
+
+static int __init sc2xxx_console_setup(struct console *con, char *options)
+{
+ struct uart_port *port = sc2xxx_port;
+ int baud = 9600;
+ int bits = 8;
+ int parity = 'n';
+ int flow = 'n';
+
+ if (port->type != PORT_SC2XXX)
+ return -1;
+
+ printk(KERN_INFO "Console: ttySC%d (SC2XXX)\n", con->index);
+ if (options)
+ uart_parse_options(options, &baud, &parity, &bits, &flow);
+
+ return uart_set_options(port, con, baud, parity, bits, flow);
+}
+
+static struct uart_driver sc2xxx_reg;
+static struct console sc2xxx_console = {
+ .name = "ttySC",
+ .write = sc2xxx_console_write,
+ .device = uart_console_device,
+ .setup = sc2xxx_console_setup,
+ .flags = CON_PRINTBUFFER,
+ .index = -1,
+ .data = &sc2xxx_reg,
+};
+#define SC2XXX_CONSOLE &sc2xxx_console
+#else
+#define SC2XXX_CONSOLE NULL
+#endif
+
+static struct uart_driver sc2xxx_reg = {
+ .owner = THIS_MODULE,
+ .driver_name = "SC2xxx",
+ .dev_name = "ttySC",
+ .major = SC2XXX_MAJOR,
+ .minor = SC2XXX_MINOR_START,
+ .nr = SC2XXX_NR,
+ .cons = SC2XXX_CONSOLE,
+};
+
+static u8 sc2xxx_flags2mask(unsigned int flags, unsigned int bitpos)
+{
+ unsigned int bit = (flags >> bitpos) & 15;
+
+ return bit ? (1 << (bit - 1)) : 0;
+}
+
+static void __devinit sc2xxx_init_masks(struct uart_sc2xxx_port *up,
+ int line, unsigned int data)
+{
+ up->dtr_mask[line] = sc2xxx_flags2mask(data, 0);
+ up->rts_mask[line] = sc2xxx_flags2mask(data, 4);
+ up->dsr_mask[line] = sc2xxx_flags2mask(data, 8);
+ up->cts_mask[line] = sc2xxx_flags2mask(data, 12);
+ up->dcd_mask[line] = sc2xxx_flags2mask(data, 16);
+ up->ri_mask[line] = sc2xxx_flags2mask(data, 20);
+}
+
+static int __devinit init_baudgroup(struct uart_sc2xxx_port *up)
+{
+ struct plat_serial_sc2xxx *pdata = up->port[0].dev->platform_data;
+
+ u8 baud_mode = up->chip->default_baud_mode;
+ u8 baud_group = up->chip->default_baud_group;
+
+ if (pdata->baud_mode > 0)
+ baud_mode = pdata->baud_mode - 1;
+
+ if (pdata->baud_group > 0)
+ baud_group = pdata->baud_group - 1;
+
+ if (baud_mode > up->chip->max_baud_mode) {
+ printk(KERN_ERR "Baud mode %d not supported for %s\n",
+ baud_mode, up->chip->name);
+ return -EINVAL;
+ }
+
+ up->acr = baud_group ? 0x80 : 0;
+ up->baud_rates = baud_rates[baud_mode][baud_group];
+
+ switch (baud_mode) {
+ case 0:
+ up->mr0_baud = 0;
+ break;
+ case 1:
+ up->mr0_baud = 1;
+ break;
+ case 2:
+ up->mr0_baud = 4;
+ break;
+ }
+ return 0;
+}
+
+static const struct chip_def * __devinit chip_by_name(const char *name)
+{
+ int i;
+ const struct chip_def *chip;
+
+ for (i = 0; i < ARRAY_SIZE(chips); i++) {
+ chip = chips[i];
+ if (!strcmp(chip->name, name))
+ return chip;
+ }
+
+ return NULL;
+}
+
+static const struct chip_def * __devinit detect_chip_type(
+ struct uart_sc2xxx_port *up)
+{
+ struct uart_port *port = &up->port[0];
+ struct chip_def *chip;
+ int i;
+ u8 mrx[3];
+
+ /* Code below needs to be tested on 2xxx hardware
+ * Idea is that 2xxx will ignore SEL_MR0 so 2nd and 3rd reads
+ * will return same data.*/
+ write_cmd_port(port, CR_RES_MR); /* MR1 */
+ write_cmd_port(port, CR_SEL_MR0); /* Ignored on 2xxx */
+
+ for (i = 0; i < 3; i++)
+ mrx[i] = READ_SC_PORT(port, MRx);
+
+ if (mrx[1] == mrx[2])
+ chip = &chip_2xxx;
+ else
+ chip = &chip_2892;
+
+ dev_info(port->dev, "Autodetected %s\n", chip->name);
+ return chip;
+}
+
+static void __devinit hw_init(struct uart_port *port)
+{
+ u8 mr;
+
+ /* Sometimes on cold boot MR1,MR2 are 0xFF (reset problem?)
+ * Initialise if channel mode in MR2 is not normal otherwise
+ * assume bootloader has done the init.
+ */
+ write_cmd_port(port, CR_RES_MR); /* MR1 */
+ READ_SC_PORT(port, MRx); /* skip MR1 */
+ mr = READ_SC_PORT(port, MRx);
+ if (mr & 0xC0) {
+ write_cmd_port(port, CR_RES_MR);
+
+ /* Values below are arbitary (will be changed by set_termios)
+ * but must be different so that chip detection works */
+ WRITE_SC_PORT(port, MRx, 0x10);
+ WRITE_SC_PORT(port, MRx, 0x00);
+ }
+}
+
+static int __devinit sc2xxx_probe(struct platform_device *dev)
+{
+ struct resource *res, *irq_res;
+ struct uart_sc2xxx_port *up;
+ struct plat_serial_sc2xxx *pdata = dev->dev.platform_data;
+ int err;
+
+ if (!pdata) {
+ dev_err(&dev->dev, "No platform data\n");
+ return -EINVAL;
+ }
+
+ res = platform_get_resource(dev, IORESOURCE_MEM, 0);
+ if (!res)
+ return -ENODEV;
+
+ irq_res = platform_get_resource(dev, IORESOURCE_IRQ, 0);
+ if (!irq_res)
+ return -ENXIO;
+
+ up = kzalloc(sizeof *up, GFP_KERNEL);
+ if (unlikely(!up))
+ return -ENOMEM;
+
+ up->port[0].line = 0;
+ up->port[0].ops = &sc2xxx_ops;
+ up->port[0].type = PORT_SC2XXX;
+ up->port[0].uartclk = (29491200 / 16); /* arbitrary */
+
+ up->port[0].mapbase = res->start;
+ up->port[0].membase = ioremap_nocache(up->port[0].mapbase, 0x40);
+ up->port[0].iotype = UPIO_MEM;
+ up->port[0].irq = irq_res->start;
+
+ up->port[0].dev = &dev->dev;
+
+ sc2xxx_init_masks(up, 0, pdata->signal_map[0]);
+ hw_init(&up->port[0]);
+
+ sc2xxx_port = &up->port[0];
+
+ memcpy(&up->port[1], &up->port[0], sizeof(up->port[0]));
+ up->port[1].line = 1;
+
+ sc2xxx_init_masks(up, 1, pdata->signal_map[1]);
+ hw_init(&up->port[1]);
+
+ if (pdata->chip_name)
+ up->chip = chip_by_name(pdata->chip_name);
+ if (!up->chip) {
+ if (pdata->chip_name)
+ dev_warn(&dev->dev,
+ "Unknown chip %s requested - use autodetect\n",
+ pdata->chip_name);
+ up->chip = detect_chip_type(up);
+ }
+
+ err = init_baudgroup(up);
+ if (err)
+ goto out_free_port;
+
+ err = uart_register_driver(&sc2xxx_reg);
+ if (err)
+ goto out_free_port;
+
+ err = uart_add_one_port(&sc2xxx_reg, &up->port[0]);
+ if (err)
+ goto out_unregister_driver;
+
+ err = uart_add_one_port(&sc2xxx_reg, &up->port[1]);
+ if (err)
+ goto out_remove_port0;
+
+ err = request_irq(up->port[0].irq, sc2xxx_interrupt,
+ irq_res->flags & IRQF_TRIGGER_MASK, "sc2xxx", up);
+ if (err)
+ goto out_remove_ports;
+
+ dev_set_drvdata(&dev->dev, up);
+ return 0;
+
+out_remove_ports:
+ uart_remove_one_port(&sc2xxx_reg, &up->port[1]);
+out_remove_port0:
+ uart_remove_one_port(&sc2xxx_reg, &up->port[0]);
+
+out_unregister_driver:
+ uart_unregister_driver(&sc2xxx_reg);
+
+out_free_port:
+ kfree(up);
+ sc2xxx_port = NULL;
+ return err;
+}
+
+
+static int __devexit sc2xxx_driver_remove(struct platform_device *dev)
+{
+ struct uart_sc2xxx_port *up = dev_get_drvdata(&dev->dev);
+
+ free_irq(up->port[0].irq, up);
+
+ uart_remove_one_port(&sc2xxx_reg, &up->port[0]);
+ uart_remove_one_port(&sc2xxx_reg, &up->port[1]);
+
+ uart_unregister_driver(&sc2xxx_reg);
+
+ kfree(up);
+ sc2xxx_port = NULL;
+
+ dev_set_drvdata(&dev->dev, NULL);
+ return 0;
+}
+
+static struct platform_driver sc2xxx_driver = {
+ .probe = sc2xxx_probe,
+ .remove = __devexit_p(sc2xxx_driver_remove),
+ .driver = {
+ .name = "SC2xxx",
+ .owner = THIS_MODULE,
+ },
+};
+
+static int __init sc2xxx_init(void)
+{
+ return platform_driver_register(&sc2xxx_driver);
+}
+
+static void __exit sc2xxx_exit(void)
+{
+ platform_driver_unregister(&sc2xxx_driver);
+}
+
+module_init(sc2xxx_init);
+module_exit(sc2xxx_exit);
+
+
+MODULE_AUTHOR("Thomas Bogendörfer");
+MODULE_DESCRIPTION("SC681/SC2XXX serial driver");
+MODULE_VERSION("1.0");
+MODULE_LICENSE("GPL");
+MODULE_ALIAS("platform:SC2xxx");
diff --git a/include/linux/serial_core.h b/include/linux/serial_core.h
index 8c3dd36..768984e 100644
--- a/include/linux/serial_core.h
+++ b/include/linux/serial_core.h
@@ -157,7 +157,7 @@
#define PORT_MN10300 80
#define PORT_MN10300_CTS 81
-#define PORT_SC26XX 82
+#define PORT_SC2XXX 82
/* SH-SCI */
#define PORT_SCIFA 83
--
To unsubscribe from this list: send the line "unsubscribe linux-serial" in
the body of a message to majordomo@vger.kernel.org
More majordomo info at http://vger.kernel.org/majordomo-info.html
^ permalink raw reply related [flat|nested] 15+ messages in thread
end of thread, other threads:[~2010-02-25 13:35 UTC | newest]
Thread overview: 15+ messages (download: mbox.gz follow: Atom feed
-- links below jump to the message on this page --
2010-02-25 13:34 [PATCH 00/14] Serial : sc26xx - generalize and support SC2892 Martin Fuzzey
2010-02-25 13:34 ` [PATCH V2 01/14] Serial: Enable build of sc26xx driver for embedded platforms Martin Fuzzey
2010-02-25 13:35 ` [PATCH V2 02/14] Serial: sc26xx fix build errors Martin Fuzzey
2010-02-25 13:35 ` [PATCH V2 03/14] Serial: sc26xx - use interrupt trigger flags from resources Martin Fuzzey
2010-02-25 13:35 ` [PATCH V2 04/14] Serial: sc26xx - add accessor function for driver data Martin Fuzzey
2010-02-25 13:35 ` [PATCH V2 05/14] Serial: sc26xx - refactor register access Martin Fuzzey
2010-02-25 13:35 ` [PATCH V2 06/14] Serial: sc26xx simplify timeout calculation Martin Fuzzey
2010-02-25 13:35 ` [PATCH V2 07/14] Serial: sc26xx - simplify port initialisation Martin Fuzzey
2010-02-25 13:35 ` [PATCH V2 08/14] Serial: sc26xx - avoid endless loop with IRQs masked Martin Fuzzey
2010-02-25 13:35 ` [PATCH V2 09/14] Serial: sc26xx - add support for SC2892 chips Martin Fuzzey
2010-02-25 13:35 ` [PATCH V2 10/14] Serial: sc26xx - introduce a structure for platform data Martin Fuzzey
2010-02-25 13:35 ` [PATCH V2 11/14] Serial: sc26xx - initialise hardware if not done by bootloader Martin Fuzzey
2010-02-25 13:35 ` [PATCH V2 12/14] Serial: sc26xx - Use ttySC0 instead of ttySC205 Martin Fuzzey
2010-02-25 13:35 ` [PATCH V2 13/14] Serial: sc26xx - Avoid null pointer dereference Martin Fuzzey
2010-02-25 13:35 ` [PATCH V2 14/14] Serial: sc26xx - rename to sc2xxx Martin Fuzzey
This is a public inbox, see mirroring instructions
for how to clone and mirror all data and code used for this inbox;
as well as URLs for NNTP newsgroup(s).