* [PATCH v7 00/21] OMAP2+: UART: Runtime adaptation + cleanup
@ 2011-10-18 15:25 Govindraj.R
2011-10-18 15:25 ` [PATCH v7 01/21] OMAP2+: UART: cleanup + remove uart pm specific API Govindraj.R
` (12 more replies)
0 siblings, 13 replies; 17+ messages in thread
From: Govindraj.R @ 2011-10-18 15:25 UTC (permalink / raw)
To: linux-arm-kernel
Converting uart driver to adapt to pm runtime API's.
Code re-org + cleanup.
Moving some functionality from serial.c to omap-serial.c
Changes involves:
================
1.) Cleaning up certain uart calls from sram_idle func.
2.) Removed all types of uart clock handling code from serial.c
3.) Using hwmod_mux API enable wakeup capability for uart pad during
hwmod_idle state i.e., when uart clocks are disabled we can enable
io-pad wakeup capability for uart if mux_data is available for
given uart. Also during during resume from idle call to uart we need
to enable clocks back conditionally and this can be done only when io-pad
wakeup event bit is set for uart_rx pad. So we need a hwmod API
which can probe the uart pad and let us know whether a uart wakeup
happened. So omap_hmwod_pad_wakeup_status API is added to meet this
requirement.
3.) Adapted omap-serial driver to use runtime API's.
4.) Modify serial_init calls to accept uart parameters from board file.
Like dma_usage, rx_timeout, dma_rx_pollrate, auto_suspend_timeout etc.
5.) Use the omap_prm driver with irq_chaining to wake up uart after clocks are
cut.
Patch series is based on 3.1.0-rc9 + omap_device fixes from Kevin's tree.
git://gitorious.org/khilman/linux-omap-pm.git for_3.2/omap_device
Also the patch series depends on *Tero's v9 Irq_chaining patches*.
Dependent irq_chaining patches are as below.
e9e7ae1 omap3+: add omap prm driver initialization
e52486f OMAP3: pm: do not enable PRCM MPU interrupts manually
ae5f2af omap3: pm: use prcm chain handler
61ad50f OMAP2+: mux: add support for PAD wakeup interrupts
cab47bf mfd: omap-prm: added suspend prepare and complete callbacks
8ed5bcd mfd: omap-prm: added chain interrupt handler
024f0e3 mfd: omap-prm: add driver skeleton
d285827 TEMP: OMAP4xxx: hwmod data: add PRM hwmod
da6f48f TEMP: OMAP3xxx: hwmod data: add PRM hwmod
Same combination is hosted at:
git://gitorious.org/runtime_3-0/runtime_3-0.git v7_rc9_uart_runtime
Ensure CONFIG_OMAP_PRM is set while testing irq_chaining with uart.
Changes from v6:
---------------
http://www.mail-archive.com/linux-omap at vger.kernel.org/msg57469.html
http://www.mail-archive.com/linux-omap at vger.kernel.org/msg57538.html
Errata handling:
http://www.mail-archive.com/linux-omap at vger.kernel.org/msg57543.html
PM_qos usage suggestion:
http://www.mail-archive.com/linux-omap at vger.kernel.org/msg57588.html
Adding custom hwmod activate func.
http://www.mail-archive.com/linux-omap at vger.kernel.org/msg57679.html
Changes from v5:
---------------
* Incorporating omap_uart_can_sleep function to avoid
console sluglishness as reported by tero.
* fixing below comments adding omap4 for autosuspend and wakeup.
http://www.mail-archive.com/linux-omap at vger.kernel.org/msg56221.html
In addition cleaning up pads from omap4430sdp/panda board file
to use default pads from serial.c
Changes from v4:
---------------
1.) Fixing v4 comments from Kevin.
Spilt into smaller logical patches.
2.) Using Irq_chaining OMAP_PRM driver for waking up uart.
Testing updates:
----------------
OMAP2420/2430SDP: Boot tested.
OMAP3430SDP:
retention, off_mode, system_wide suspend is tested.
(earlyprintk & no_console_suspend checked)
OMAP3630 - Zoom3:
pm-retention checked with quart/omap-uart3
[Also tested with uart3 as console uart and pm-ret checked]
BeagleBoard XM Rev C(3630):
retention, off_mode, system_wide suspend is tested.
Deepak K (1):
OMAP2+: UART: Allow UART parameters to be configured from board file.
Govindraj.R (19):
OMAP2+: UART: cleanup + remove uart pm specific API
OMAP2+: UART: cleanup 8250 console driver support
OMAP2+: UART: Cleanup part of clock gating mechanism for uart
OMAP2+: UART: Add default mux for all uarts.
OMAP2+: UART: Remove mapbase/membase fields from pdata.
OMAP2+: UART: Add runtime pm support for omap-serial driver
OMAP2+: UART: Remove context_save and move context restore to driver
OMAP2+: UART: Ensure all reg values configured are available from
port structure
OMAP2+: UART: Remove uart reset function.
OMAP2+: UART: Get context loss count to context restore
OMAP2+: UART: Move errata handling from serial.c to omap-serial
OMAP2+: UART: Add wakeup mechanism for omap-uarts
OMAP2+: UART: Remove old and unused clocks handling funcs
OMAP2+: UART: Remove custom activate funcs and use generic funcs.
OMAP2+: UART: Remove omap_uart_can_sleep and add pm_qos
OMAP2+: UART: remove temporary variable used to count uart instance
OMAP2+: UART: Use custom activate func for console uart.
OMAP2+: UART: Avoid uart idling on suspend for no_console_suspend
usecase
OMAP2+: UART: Do not gate uart clocks if used for debug_prints
Jon Hunter (1):
OMAP2+: UART: Make the RX_TIMEOUT for DMA configurable for each UART
arch/arm/mach-omap2/board-3430sdp.c | 100 +---
arch/arm/mach-omap2/board-4430sdp.c | 68 +--
arch/arm/mach-omap2/board-n8x0.c | 6 +-
arch/arm/mach-omap2/board-omap4panda.c | 68 +--
arch/arm/mach-omap2/cpuidle34xx.c | 5 -
arch/arm/mach-omap2/pm24xx.c | 20 -
arch/arm/mach-omap2/pm34xx.c | 33 -
arch/arm/mach-omap2/serial.c | 937 +++++++------------------
arch/arm/plat-omap/include/plat/omap-serial.h | 38 +-
arch/arm/plat-omap/include/plat/serial.h | 10 +-
drivers/tty/serial/omap-serial.c | 345 ++++++++--
11 files changed, 609 insertions(+), 1021 deletions(-)
--
1.7.4.1
^ permalink raw reply [flat|nested] 17+ messages in thread
* [PATCH v7 01/21] OMAP2+: UART: cleanup + remove uart pm specific API
2011-10-18 15:25 [PATCH v7 00/21] OMAP2+: UART: Runtime adaptation + cleanup Govindraj.R
@ 2011-10-18 15:25 ` Govindraj.R
2011-10-18 15:25 ` [PATCH v7 02/21] OMAP2+: UART: cleanup 8250 console driver support Govindraj.R
` (11 subsequent siblings)
12 siblings, 0 replies; 17+ messages in thread
From: Govindraj.R @ 2011-10-18 15:25 UTC (permalink / raw)
To: linux-arm-kernel
In preparation to UART runtime conversion remove uart specific calls
from pm24xx/34xx files and their definition from serial.c
These func calls will no more be used with upcoming uart runtime design.
1.) omap_uart_prepare_suspend :- can be taken care with driver suspend hooks.
2.) omap_uart_enable_irqs :- Used to enable/disable uart irq's in suspend
path from PM code, this is removed as same is handled by
uart_suspend_port/uart_resume_port in omap-serial driver which will
do an port_shutdown on suspend freeing irq and port_startup on resume
enabling back irq.
3.) Remove prepare_idle/resume_idle calls used to gate uart clocks.
UART clocks can be gated within driver using runtime funcs
and be woken up using irq_chaining from omap_prm driver.
4.) Remove console_locking from idle path as clock gating is done withing
driver itself with runtime API.
Signed-off-by: Govindraj.R <govindraj.raja@ti.com>
---
arch/arm/mach-omap2/pm24xx.c | 18 --------
arch/arm/mach-omap2/pm34xx.c | 23 ----------
arch/arm/mach-omap2/serial.c | 65 ------------------------------
arch/arm/plat-omap/include/plat/serial.h | 4 --
4 files changed, 0 insertions(+), 110 deletions(-)
diff --git a/arch/arm/mach-omap2/pm24xx.c b/arch/arm/mach-omap2/pm24xx.c
index bf089e7..a75f764 100644
--- a/arch/arm/mach-omap2/pm24xx.c
+++ b/arch/arm/mach-omap2/pm24xx.c
@@ -30,7 +30,6 @@
#include <linux/irq.h>
#include <linux/time.h>
#include <linux/gpio.h>
-#include <linux/console.h>
#include <asm/mach/time.h>
#include <asm/mach/irq.h>
@@ -133,27 +132,11 @@ static void omap2_enter_full_retention(void)
if (omap_irq_pending())
goto no_sleep;
- /* Block console output in case it is on one of the OMAP UARTs */
- if (!is_suspending())
- if (!console_trylock())
- goto no_sleep;
-
- omap_uart_prepare_idle(0);
- omap_uart_prepare_idle(1);
- omap_uart_prepare_idle(2);
-
/* Jump to SRAM suspend code */
omap2_sram_suspend(sdrc_read_reg(SDRC_DLLA_CTRL),
OMAP_SDRC_REGADDR(SDRC_DLLA_CTRL),
OMAP_SDRC_REGADDR(SDRC_POWER));
- omap_uart_resume_idle(2);
- omap_uart_resume_idle(1);
- omap_uart_resume_idle(0);
-
- if (!is_suspending())
- console_unlock();
-
no_sleep:
if (omap2_pm_debug) {
unsigned long long tmp;
@@ -317,7 +300,6 @@ static int omap2_pm_suspend(void)
mir1 = omap_readl(0x480fe0a4);
omap_writel(1 << 5, 0x480fe0ac);
- omap_uart_prepare_suspend();
omap2_enter_full_retention();
omap_writel(mir1, 0x480fe0a4);
diff --git a/arch/arm/mach-omap2/pm34xx.c b/arch/arm/mach-omap2/pm34xx.c
index 4bbf1cd..6e7f276 100644
--- a/arch/arm/mach-omap2/pm34xx.c
+++ b/arch/arm/mach-omap2/pm34xx.c
@@ -28,7 +28,6 @@
#include <linux/clk.h>
#include <linux/delay.h>
#include <linux/slab.h>
-#include <linux/console.h>
#include <linux/mfd/omap-prm.h>
#include <trace/events/power.h>
@@ -341,18 +340,9 @@ void omap_sram_idle(void)
omap3_enable_io_chain();
}
- /* Block console output in case it is on one of the OMAP UARTs */
- if (!is_suspending())
- if (per_next_state < PWRDM_POWER_ON ||
- core_next_state < PWRDM_POWER_ON)
- if (!console_trylock())
- goto console_still_active;
-
/* PER */
if (per_next_state < PWRDM_POWER_ON) {
per_going_off = (per_next_state == PWRDM_POWER_OFF) ? 1 : 0;
- omap_uart_prepare_idle(2);
- omap_uart_prepare_idle(3);
omap2_gpio_prepare_for_idle(per_going_off);
if (per_next_state == PWRDM_POWER_OFF)
omap3_per_save_context();
@@ -360,8 +350,6 @@ void omap_sram_idle(void)
/* CORE */
if (core_next_state < PWRDM_POWER_ON) {
- omap_uart_prepare_idle(0);
- omap_uart_prepare_idle(1);
if (core_next_state == PWRDM_POWER_OFF) {
omap3_core_save_context();
omap3_cm_save_context();
@@ -408,8 +396,6 @@ void omap_sram_idle(void)
omap3_sram_restore_context();
omap2_sms_restore_context();
}
- omap_uart_resume_idle(0);
- omap_uart_resume_idle(1);
if (core_next_state == PWRDM_POWER_OFF)
omap2_prm_clear_mod_reg_bits(OMAP3430_AUTO_OFF_MASK,
OMAP3430_GR_MOD,
@@ -423,14 +409,8 @@ void omap_sram_idle(void)
omap2_gpio_resume_after_idle();
if (per_prev_state == PWRDM_POWER_OFF)
omap3_per_restore_context();
- omap_uart_resume_idle(2);
- omap_uart_resume_idle(3);
}
- if (!is_suspending())
- console_unlock();
-
-console_still_active:
/* Disable IO-PAD and IO-CHAIN wakeup */
if (omap3_has_io_wakeup() &&
(per_next_state < PWRDM_POWER_ON ||
@@ -493,7 +473,6 @@ static int omap3_pm_suspend(void)
goto restore;
}
- omap_uart_prepare_suspend();
omap3_intc_suspend();
omap_sram_idle();
@@ -540,14 +519,12 @@ static int omap3_pm_begin(suspend_state_t state)
{
disable_hlt();
suspend_state = state;
- omap_uart_enable_irqs(0);
return 0;
}
static void omap3_pm_end(void)
{
suspend_state = PM_SUSPEND_ON;
- omap_uart_enable_irqs(1);
enable_hlt();
return;
}
diff --git a/arch/arm/mach-omap2/serial.c b/arch/arm/mach-omap2/serial.c
index 3d1c1d3..62d15ad 100644
--- a/arch/arm/mach-omap2/serial.c
+++ b/arch/arm/mach-omap2/serial.c
@@ -389,51 +389,6 @@ static void omap_uart_idle_timer(unsigned long data)
omap_uart_allow_sleep(uart);
}
-void omap_uart_prepare_idle(int num)
-{
- struct omap_uart_state *uart;
-
- list_for_each_entry(uart, &uart_list, node) {
- if (num == uart->num && uart->can_sleep) {
- omap_uart_disable_clocks(uart);
- return;
- }
- }
-}
-
-void omap_uart_resume_idle(int num)
-{
- struct omap_uart_state *uart;
-
- list_for_each_entry(uart, &uart_list, node) {
- if (num == uart->num && uart->can_sleep) {
- omap_uart_enable_clocks(uart);
-
- /* Check for IO pad wakeup */
- if (cpu_is_omap34xx() && uart->padconf) {
- u16 p = omap_ctrl_readw(uart->padconf);
-
- if (p & OMAP3_PADCONF_WAKEUPEVENT0)
- omap_uart_block_sleep(uart);
- }
-
- /* Check for normal UART wakeup */
- if (__raw_readl(uart->wk_st) & uart->wk_mask)
- omap_uart_block_sleep(uart);
- return;
- }
- }
-}
-
-void omap_uart_prepare_suspend(void)
-{
- struct omap_uart_state *uart;
-
- list_for_each_entry(uart, &uart_list, node) {
- omap_uart_allow_sleep(uart);
- }
-}
-
int omap_uart_can_sleep(void)
{
struct omap_uart_state *uart;
@@ -552,26 +507,6 @@ static void omap_uart_idle_init(struct omap_uart_state *uart)
WARN_ON(ret);
}
-void omap_uart_enable_irqs(int enable)
-{
- int ret;
- struct omap_uart_state *uart;
-
- list_for_each_entry(uart, &uart_list, node) {
- if (enable) {
- pm_runtime_put_sync(&uart->pdev->dev);
- ret = request_threaded_irq(uart->irq, NULL,
- omap_uart_interrupt,
- IRQF_SHARED,
- "serial idle",
- (void *)uart);
- } else {
- pm_runtime_get_noresume(&uart->pdev->dev);
- free_irq(uart->irq, (void *)uart);
- }
- }
-}
-
static ssize_t sleep_timeout_show(struct device *dev,
struct device_attribute *attr,
char *buf)
diff --git a/arch/arm/plat-omap/include/plat/serial.h b/arch/arm/plat-omap/include/plat/serial.h
index de3b10c..fc8b60c 100644
--- a/arch/arm/plat-omap/include/plat/serial.h
+++ b/arch/arm/plat-omap/include/plat/serial.h
@@ -111,10 +111,6 @@ extern void omap_serial_init(void);
extern void omap_serial_init_port(struct omap_board_data *bdata);
extern int omap_uart_can_sleep(void);
extern void omap_uart_check_wakeup(void);
-extern void omap_uart_prepare_suspend(void);
-extern void omap_uart_prepare_idle(int num);
-extern void omap_uart_resume_idle(int num);
-extern void omap_uart_enable_irqs(int enable);
#endif
#endif
--
1.7.4.1
^ permalink raw reply related [flat|nested] 17+ messages in thread
* [PATCH v7 02/21] OMAP2+: UART: cleanup 8250 console driver support
2011-10-18 15:25 [PATCH v7 00/21] OMAP2+: UART: Runtime adaptation + cleanup Govindraj.R
2011-10-18 15:25 ` [PATCH v7 01/21] OMAP2+: UART: cleanup + remove uart pm specific API Govindraj.R
@ 2011-10-18 15:25 ` Govindraj.R
2011-10-18 15:25 ` [PATCH v7 03/21] OMAP2+: UART: Cleanup part of clock gating mechanism for uart Govindraj.R
` (10 subsequent siblings)
12 siblings, 0 replies; 17+ messages in thread
From: Govindraj.R @ 2011-10-18 15:25 UTC (permalink / raw)
To: linux-arm-kernel
We had been using traditional 8250 driver as uart console driver
prior to omap-serial driver. Since we have omap-serial driver
in mainline kernel for some time now it has been used as default
uart console driver on omap2+ platforms. Remove 8250 support for
omap-uarts.
Serial_in and serial_out override for 8250 serial driver is also
removed. Empty fifo read fix is already taken care with omap-serial
driver with data ready bit check from LSR reg before reading RX fifo.
Also waiting for THRE(transmit hold reg empty) is done with wait_for_xmitr
in omap-serial driver.
Serial_in/out overrides are not neceesary for omap-serial driver
and things that are taken with omap-serial driver are removed here.
Remove headers that were necessary to support 8250 support
and remove all config bindings done to keep 8250 backward compatibility
while adding omap-serial driver. Remove omap_uart_reset needed for
8250 autoconf.
Signed-off-by: Govindraj.R <govindraj.raja@ti.com>
---
arch/arm/mach-omap2/serial.c | 97 ------------------------------------------
1 files changed, 0 insertions(+), 97 deletions(-)
diff --git a/arch/arm/mach-omap2/serial.c b/arch/arm/mach-omap2/serial.c
index 62d15ad..61b260a 100644
--- a/arch/arm/mach-omap2/serial.c
+++ b/arch/arm/mach-omap2/serial.c
@@ -19,23 +19,17 @@
*/
#include <linux/kernel.h>
#include <linux/init.h>
-#include <linux/serial_reg.h>
#include <linux/clk.h>
#include <linux/io.h>
#include <linux/delay.h>
#include <linux/platform_device.h>
#include <linux/slab.h>
-#include <linux/serial_8250.h>
#include <linux/pm_runtime.h>
#include <linux/console.h>
-#ifdef CONFIG_SERIAL_OMAP
#include <plat/omap-serial.h>
-#endif
-
#include <plat/common.h>
#include <plat/board.h>
-#include <plat/clock.h>
#include <plat/dma.h>
#include <plat/omap_hwmod.h>
#include <plat/omap_device.h>
@@ -47,10 +41,8 @@
#include "control.h"
#include "mux.h"
-#define UART_OMAP_NO_EMPTY_FIFO_READ_IP_REV 0x52
#define UART_OMAP_WER 0x17 /* Wake-up enable register */
-#define UART_ERRATA_FIFO_FULL_ABORT (0x1 << 0)
#define UART_ERRATA_i202_MDR1_ACCESS (0x1 << 1)
/*
@@ -555,41 +547,6 @@ static void omap_uart_block_sleep(struct omap_uart_state *uart)
#define DEV_CREATE_FILE(dev, attr)
#endif /* CONFIG_PM */
-#ifndef CONFIG_SERIAL_OMAP
-/*
- * Override the default 8250 read handler: mem_serial_in()
- * Empty RX fifo read causes an abort on omap3630 and omap4
- * This function makes sure that an empty rx fifo is not read on these silicons
- * (OMAP1/2/3430 are not affected)
- */
-static unsigned int serial_in_override(struct uart_port *up, int offset)
-{
- if (UART_RX == offset) {
- unsigned int lsr;
- lsr = __serial_read_reg(up, UART_LSR);
- if (!(lsr & UART_LSR_DR))
- return -EPERM;
- }
-
- return __serial_read_reg(up, offset);
-}
-
-static void serial_out_override(struct uart_port *up, int offset, int value)
-{
- unsigned int status, tmout = 10000;
-
- status = __serial_read_reg(up, UART_LSR);
- while (!(status & UART_LSR_THRE)) {
- /* Wait up to 10ms for the character(s) to be sent. */
- if (--tmout == 0)
- break;
- udelay(1);
- status = __serial_read_reg(up, UART_LSR);
- }
- __serial_write_reg(up, offset, value);
-}
-#endif
-
static int __init omap_serial_early_init(void)
{
int i = 0;
@@ -650,15 +607,7 @@ void __init omap_serial_init_port(struct omap_board_data *bdata)
void *pdata = NULL;
u32 pdata_size = 0;
char *name;
-#ifndef CONFIG_SERIAL_OMAP
- struct plat_serial8250_port ports[2] = {
- {},
- {.flags = 0},
- };
- struct plat_serial8250_port *p = &ports[0];
-#else
struct omap_uart_port_info omap_up;
-#endif
if (WARN_ON(!bdata))
return;
@@ -673,51 +622,6 @@ void __init omap_serial_init_port(struct omap_board_data *bdata)
oh = uart->oh;
uart->dma_enabled = 0;
-#ifndef CONFIG_SERIAL_OMAP
- name = "serial8250";
-
- /*
- * !! 8250 driver does not use standard IORESOURCE* It
- * has it's own custom pdata that can be taken from
- * the hwmod resource data. But, this needs to be
- * done after the build.
- *
- * ?? does it have to be done before the register ??
- * YES, because platform_device_data_add() copies
- * pdata, it does not use a pointer.
- */
- p->flags = UPF_BOOT_AUTOCONF;
- p->iotype = UPIO_MEM;
- p->regshift = 2;
- p->uartclk = OMAP24XX_BASE_BAUD * 16;
- p->irq = oh->mpu_irqs[0].irq;
- p->mapbase = oh->slaves[0]->addr->pa_start;
- p->membase = omap_hwmod_get_mpu_rt_va(oh);
- p->irqflags = IRQF_SHARED;
- p->private_data = uart;
-
- /*
- * omap44xx, ti816x: Never read empty UART fifo
- * omap3xxx: Never read empty UART fifo on UARTs
- * with IP rev >=0x52
- */
- uart->regshift = p->regshift;
- uart->membase = p->membase;
- if (cpu_is_omap44xx() || cpu_is_ti816x())
- uart->errata |= UART_ERRATA_FIFO_FULL_ABORT;
- else if ((serial_read_reg(uart, UART_OMAP_MVER) & 0xFF)
- >= UART_OMAP_NO_EMPTY_FIFO_READ_IP_REV)
- uart->errata |= UART_ERRATA_FIFO_FULL_ABORT;
-
- if (uart->errata & UART_ERRATA_FIFO_FULL_ABORT) {
- p->serial_in = serial_in_override;
- p->serial_out = serial_out_override;
- }
-
- pdata = &ports[0];
- pdata_size = 2 * sizeof(struct plat_serial8250_port);
-#else
-
name = DRIVER_NAME;
omap_up.dma_enabled = uart->dma_enabled;
@@ -729,7 +633,6 @@ void __init omap_serial_init_port(struct omap_board_data *bdata)
pdata = &omap_up;
pdata_size = sizeof(struct omap_uart_port_info);
-#endif
if (WARN_ON(!oh))
return;
--
1.7.4.1
^ permalink raw reply related [flat|nested] 17+ messages in thread
* [PATCH v7 03/21] OMAP2+: UART: Cleanup part of clock gating mechanism for uart
2011-10-18 15:25 [PATCH v7 00/21] OMAP2+: UART: Runtime adaptation + cleanup Govindraj.R
2011-10-18 15:25 ` [PATCH v7 01/21] OMAP2+: UART: cleanup + remove uart pm specific API Govindraj.R
2011-10-18 15:25 ` [PATCH v7 02/21] OMAP2+: UART: cleanup 8250 console driver support Govindraj.R
@ 2011-10-18 15:25 ` Govindraj.R
2011-10-18 15:25 ` [PATCH v7 04/21] OMAP2+: UART: Add default mux for all uarts Govindraj.R
` (9 subsequent siblings)
12 siblings, 0 replies; 17+ messages in thread
From: Govindraj.R @ 2011-10-18 15:25 UTC (permalink / raw)
To: linux-arm-kernel
Currently we use a shared irq handler to identify uart activity and then
trigger a timer. By default the timeout value is zero and can be set or
modified from sysfs. If there was no uart activity for the period set
through sysfs, the timer will expire and call timer handler this will
set a flag can_sleep using which decision to gate uart clocks can be taken.
Since the clock gating mechanism is outside the uart driver, we currently
use this mechanism. In preparation to runtime implementation for omap-serial
driver we can cleanup this mechanism and use runtime API's to gate uart clocks.
Removes the following:
* timer related info from local uart_state struct
* the code used to set timeout value from sysfs.
* irqflags used to set shared irq handler.
* un-used function omap_uart_check_wakeup.
Signed-off-by: Govindraj.R <govindraj.raja@ti.com>
---
arch/arm/mach-omap2/serial.c | 118 +------------------------
arch/arm/plat-omap/include/plat/omap-serial.h | 1 -
arch/arm/plat-omap/include/plat/serial.h | 1 -
drivers/tty/serial/omap-serial.c | 1 -
4 files changed, 2 insertions(+), 119 deletions(-)
diff --git a/arch/arm/mach-omap2/serial.c b/arch/arm/mach-omap2/serial.c
index 61b260a..5632de5 100644
--- a/arch/arm/mach-omap2/serial.c
+++ b/arch/arm/mach-omap2/serial.c
@@ -58,8 +58,6 @@
struct omap_uart_state {
int num;
int can_sleep;
- struct timer_list timer;
- u32 timeout;
void __iomem *wk_st;
void __iomem *wk_en;
@@ -67,13 +65,9 @@ struct omap_uart_state {
u32 padconf;
u32 dma_enabled;
- struct clk *ick;
- struct clk *fck;
int clocked;
- int irq;
int regshift;
- int irqflags;
void __iomem *membase;
resource_size_t mapbase;
@@ -353,32 +347,6 @@ static void omap_uart_block_sleep(struct omap_uart_state *uart)
omap_uart_smart_idle_enable(uart, 0);
uart->can_sleep = 0;
- if (uart->timeout)
- mod_timer(&uart->timer, jiffies + uart->timeout);
- else
- del_timer(&uart->timer);
-}
-
-static void omap_uart_allow_sleep(struct omap_uart_state *uart)
-{
- if (device_may_wakeup(&uart->pdev->dev))
- omap_uart_enable_wakeup(uart);
- else
- omap_uart_disable_wakeup(uart);
-
- if (!uart->clocked)
- return;
-
- omap_uart_smart_idle_enable(uart, 1);
- uart->can_sleep = 1;
- del_timer(&uart->timer);
-}
-
-static void omap_uart_idle_timer(unsigned long data)
-{
- struct omap_uart_state *uart = (struct omap_uart_state *)data;
-
- omap_uart_allow_sleep(uart);
}
int omap_uart_can_sleep(void)
@@ -402,35 +370,11 @@ int omap_uart_can_sleep(void)
return can_sleep;
}
-/**
- * omap_uart_interrupt()
- *
- * This handler is used only to detect that *any* UART interrupt has
- * occurred. It does _nothing_ to handle the interrupt. Rather,
- * any UART interrupt will trigger the inactivity timer so the
- * UART will not idle or sleep for its timeout period.
- *
- **/
-/* static int first_interrupt; */
-static irqreturn_t omap_uart_interrupt(int irq, void *dev_id)
-{
- struct omap_uart_state *uart = dev_id;
-
- omap_uart_block_sleep(uart);
-
- return IRQ_NONE;
-}
-
static void omap_uart_idle_init(struct omap_uart_state *uart)
{
int ret;
uart->can_sleep = 0;
- uart->timeout = DEFAULT_TIMEOUT;
- setup_timer(&uart->timer, omap_uart_idle_timer,
- (unsigned long) uart);
- if (uart->timeout)
- mod_timer(&uart->timer, jiffies + uart->timeout);
omap_uart_smart_idle_enable(uart, 0);
if (cpu_is_omap34xx() && !cpu_is_ti816x()) {
@@ -492,51 +436,8 @@ static void omap_uart_idle_init(struct omap_uart_state *uart)
uart->wk_mask = 0;
uart->padconf = 0;
}
-
- uart->irqflags |= IRQF_SHARED;
- ret = request_threaded_irq(uart->irq, NULL, omap_uart_interrupt,
- IRQF_SHARED, "serial idle", (void *)uart);
- WARN_ON(ret);
-}
-
-static ssize_t sleep_timeout_show(struct device *dev,
- struct device_attribute *attr,
- char *buf)
-{
- struct platform_device *pdev = to_platform_device(dev);
- struct omap_device *odev = to_omap_device(pdev);
- struct omap_uart_state *uart = odev->hwmods[0]->dev_attr;
-
- return sprintf(buf, "%u\n", uart->timeout / HZ);
}
-static ssize_t sleep_timeout_store(struct device *dev,
- struct device_attribute *attr,
- const char *buf, size_t n)
-{
- struct platform_device *pdev = to_platform_device(dev);
- struct omap_device *odev = to_omap_device(pdev);
- struct omap_uart_state *uart = odev->hwmods[0]->dev_attr;
- unsigned int value;
-
- if (sscanf(buf, "%u", &value) != 1) {
- dev_err(dev, "sleep_timeout_store: Invalid value\n");
- return -EINVAL;
- }
-
- uart->timeout = value * HZ;
- if (uart->timeout)
- mod_timer(&uart->timer, jiffies + uart->timeout);
- else
- /* A zero value means disable timeout feature */
- omap_uart_block_sleep(uart);
-
- return n;
-}
-
-static DEVICE_ATTR(sleep_timeout, 0644, sleep_timeout_show,
- sleep_timeout_store);
-#define DEV_CREATE_FILE(dev, attr) WARN_ON(device_create_file(dev, attr))
#else
static inline void omap_uart_idle_init(struct omap_uart_state *uart) {}
static void omap_uart_block_sleep(struct omap_uart_state *uart)
@@ -544,7 +445,6 @@ static void omap_uart_block_sleep(struct omap_uart_state *uart)
/* Needed to enable UART clocks when built without CONFIG_PM */
omap_uart_enable_clocks(uart);
}
-#define DEV_CREATE_FILE(dev, attr)
#endif /* CONFIG_PM */
static int __init omap_serial_early_init(void)
@@ -628,8 +528,7 @@ void __init omap_serial_init_port(struct omap_board_data *bdata)
omap_up.uartclk = OMAP24XX_BASE_BAUD * 16;
omap_up.mapbase = oh->slaves[0]->addr->pa_start;
omap_up.membase = omap_hwmod_get_mpu_rt_va(oh);
- omap_up.irqflags = IRQF_SHARED;
- omap_up.flags = UPF_BOOT_AUTOCONF | UPF_SHARE_IRQ;
+ omap_up.flags = UPF_BOOT_AUTOCONF;
pdata = &omap_up;
pdata_size = sizeof(struct omap_uart_port_info);
@@ -646,7 +545,6 @@ void __init omap_serial_init_port(struct omap_board_data *bdata)
omap_device_disable_idle_on_suspend(pdev);
oh->mux = omap_hwmod_mux_init(bdata->pads, bdata->pads_cnt);
- uart->irq = oh->mpu_irqs[0].irq;
uart->regshift = 2;
uart->mapbase = oh->slaves[0]->addr->pa_start;
uart->membase = omap_hwmod_get_mpu_rt_va(oh);
@@ -669,24 +567,12 @@ void __init omap_serial_init_port(struct omap_board_data *bdata)
omap_hwmod_enable_wakeup(uart->oh);
omap_device_idle(uart->pdev);
- /*
- * Need to block sleep long enough for interrupt driven
- * driver to start. Console driver is in polling mode
- * so device needs to be kept enabled while polling driver
- * is in use.
- */
- if (uart->timeout)
- uart->timeout = (30 * HZ);
omap_uart_block_sleep(uart);
- uart->timeout = DEFAULT_TIMEOUT;
-
console_unlock();
if ((cpu_is_omap34xx() && uart->padconf) ||
- (uart->wk_en && uart->wk_mask)) {
+ (uart->wk_en && uart->wk_mask))
device_init_wakeup(&pdev->dev, true);
- DEV_CREATE_FILE(&pdev->dev, &dev_attr_sleep_timeout);
- }
/* Enable the MDR1 errata for OMAP3 */
if (cpu_is_omap34xx() && !cpu_is_ti816x())
diff --git a/arch/arm/plat-omap/include/plat/omap-serial.h b/arch/arm/plat-omap/include/plat/omap-serial.h
index 2682043..307cd6f 100644
--- a/arch/arm/plat-omap/include/plat/omap-serial.h
+++ b/arch/arm/plat-omap/include/plat/omap-serial.h
@@ -61,7 +61,6 @@ struct omap_uart_port_info {
unsigned int uartclk; /* UART clock rate */
void __iomem *membase; /* ioremap cookie or NULL */
resource_size_t mapbase; /* resource base */
- unsigned long irqflags; /* request_irq flags */
upf_t flags; /* UPF_* flags */
};
diff --git a/arch/arm/plat-omap/include/plat/serial.h b/arch/arm/plat-omap/include/plat/serial.h
index fc8b60c..a8bc1f1 100644
--- a/arch/arm/plat-omap/include/plat/serial.h
+++ b/arch/arm/plat-omap/include/plat/serial.h
@@ -110,7 +110,6 @@ struct omap_board_data;
extern void omap_serial_init(void);
extern void omap_serial_init_port(struct omap_board_data *bdata);
extern int omap_uart_can_sleep(void);
-extern void omap_uart_check_wakeup(void);
#endif
#endif
diff --git a/drivers/tty/serial/omap-serial.c b/drivers/tty/serial/omap-serial.c
index 5e713d3..be368cf7 100644
--- a/drivers/tty/serial/omap-serial.c
+++ b/drivers/tty/serial/omap-serial.c
@@ -1278,7 +1278,6 @@ static int serial_omap_probe(struct platform_device *pdev)
up->port.membase = omap_up_info->membase;
up->port.mapbase = omap_up_info->mapbase;
up->port.flags = omap_up_info->flags;
- up->port.irqflags = omap_up_info->irqflags;
up->port.uartclk = omap_up_info->uartclk;
up->uart_dma.uart_base = mem->start;
--
1.7.4.1
^ permalink raw reply related [flat|nested] 17+ messages in thread
* [PATCH v7 04/21] OMAP2+: UART: Add default mux for all uarts.
2011-10-18 15:25 [PATCH v7 00/21] OMAP2+: UART: Runtime adaptation + cleanup Govindraj.R
` (2 preceding siblings ...)
2011-10-18 15:25 ` [PATCH v7 03/21] OMAP2+: UART: Cleanup part of clock gating mechanism for uart Govindraj.R
@ 2011-10-18 15:25 ` Govindraj.R
2011-10-18 15:26 ` [PATCH v7 05/21] OMAP2+: UART: Remove mapbase/membase fields from pdata Govindraj.R
` (8 subsequent siblings)
12 siblings, 0 replies; 17+ messages in thread
From: Govindraj.R @ 2011-10-18 15:25 UTC (permalink / raw)
To: linux-arm-kernel
Padconf wakeup is used to wakeup uart after uart fclks/iclks are gated.
Rx-Pad wakeup was done by writing to rx-pad offset value populated in
serial.c idle_init. Remove the direct reading and writing into rx pad.
Remove the padconf field part of omap_uart_state struct and pad offsets
populated.
Now with mux framework support we can use mux_utilities
along with hmwod framework to handle io-pad configuration and enable rx-pad
wake-up mechanism.
To avoid breaking any board support add default mux data for all uart's
if mux info is not passed from board file.
With the default pads populated in serial.c wakeup capability for
rx pads is set, this can be used to enable uart_rx io-pad wakeup from
hwmod framework. The pad values in 3430sdp/4430sdp/omap4panda board file
are same as the default pad values populated in serial.c. Remove pad values
from 3430sdp/4430sdp/omap4panda board file and use the default pads
from serial.c file.
Signed-off-by: Govindraj.R <govindraj.raja@ti.com>
---
arch/arm/mach-omap2/board-3430sdp.c | 100 +--------------------
arch/arm/mach-omap2/board-4430sdp.c | 68 +--------------
arch/arm/mach-omap2/board-omap4panda.c | 68 +--------------
arch/arm/mach-omap2/serial.c | 155 ++++++++++++++++++++++++++-----
4 files changed, 133 insertions(+), 258 deletions(-)
diff --git a/arch/arm/mach-omap2/board-3430sdp.c b/arch/arm/mach-omap2/board-3430sdp.c
index bd600cf..b12b38f 100644
--- a/arch/arm/mach-omap2/board-3430sdp.c
+++ b/arch/arm/mach-omap2/board-3430sdp.c
@@ -482,106 +482,8 @@ static const struct usbhs_omap_board_data usbhs_bdata __initconst = {
static struct omap_board_mux board_mux[] __initdata = {
{ .reg_offset = OMAP_MUX_TERMINATOR },
};
-
-static struct omap_device_pad serial1_pads[] __initdata = {
- /*
- * Note that off output enable is an active low
- * signal. So setting this means pin is a
- * input enabled in off mode
- */
- OMAP_MUX_STATIC("uart1_cts.uart1_cts",
- OMAP_PIN_INPUT |
- OMAP_PIN_OFF_INPUT_PULLDOWN |
- OMAP_OFFOUT_EN |
- OMAP_MUX_MODE0),
- OMAP_MUX_STATIC("uart1_rts.uart1_rts",
- OMAP_PIN_OUTPUT |
- OMAP_OFF_EN |
- OMAP_MUX_MODE0),
- OMAP_MUX_STATIC("uart1_rx.uart1_rx",
- OMAP_PIN_INPUT |
- OMAP_PIN_OFF_INPUT_PULLDOWN |
- OMAP_OFFOUT_EN |
- OMAP_MUX_MODE0),
- OMAP_MUX_STATIC("uart1_tx.uart1_tx",
- OMAP_PIN_OUTPUT |
- OMAP_OFF_EN |
- OMAP_MUX_MODE0),
-};
-
-static struct omap_device_pad serial2_pads[] __initdata = {
- OMAP_MUX_STATIC("uart2_cts.uart2_cts",
- OMAP_PIN_INPUT_PULLUP |
- OMAP_PIN_OFF_INPUT_PULLDOWN |
- OMAP_OFFOUT_EN |
- OMAP_MUX_MODE0),
- OMAP_MUX_STATIC("uart2_rts.uart2_rts",
- OMAP_PIN_OUTPUT |
- OMAP_OFF_EN |
- OMAP_MUX_MODE0),
- OMAP_MUX_STATIC("uart2_rx.uart2_rx",
- OMAP_PIN_INPUT |
- OMAP_PIN_OFF_INPUT_PULLDOWN |
- OMAP_OFFOUT_EN |
- OMAP_MUX_MODE0),
- OMAP_MUX_STATIC("uart2_tx.uart2_tx",
- OMAP_PIN_OUTPUT |
- OMAP_OFF_EN |
- OMAP_MUX_MODE0),
-};
-
-static struct omap_device_pad serial3_pads[] __initdata = {
- OMAP_MUX_STATIC("uart3_cts_rctx.uart3_cts_rctx",
- OMAP_PIN_INPUT_PULLDOWN |
- OMAP_PIN_OFF_INPUT_PULLDOWN |
- OMAP_OFFOUT_EN |
- OMAP_MUX_MODE0),
- OMAP_MUX_STATIC("uart3_rts_sd.uart3_rts_sd",
- OMAP_PIN_OUTPUT |
- OMAP_OFF_EN |
- OMAP_MUX_MODE0),
- OMAP_MUX_STATIC("uart3_rx_irrx.uart3_rx_irrx",
- OMAP_PIN_INPUT |
- OMAP_PIN_OFF_INPUT_PULLDOWN |
- OMAP_OFFOUT_EN |
- OMAP_MUX_MODE0),
- OMAP_MUX_STATIC("uart3_tx_irtx.uart3_tx_irtx",
- OMAP_PIN_OUTPUT |
- OMAP_OFF_EN |
- OMAP_MUX_MODE0),
-};
-
-static struct omap_board_data serial1_data __initdata = {
- .id = 0,
- .pads = serial1_pads,
- .pads_cnt = ARRAY_SIZE(serial1_pads),
-};
-
-static struct omap_board_data serial2_data __initdata = {
- .id = 1,
- .pads = serial2_pads,
- .pads_cnt = ARRAY_SIZE(serial2_pads),
-};
-
-static struct omap_board_data serial3_data __initdata = {
- .id = 2,
- .pads = serial3_pads,
- .pads_cnt = ARRAY_SIZE(serial3_pads),
-};
-
-static inline void board_serial_init(void)
-{
- omap_serial_init_port(&serial1_data);
- omap_serial_init_port(&serial2_data);
- omap_serial_init_port(&serial3_data);
-}
#else
#define board_mux NULL
-
-static inline void board_serial_init(void)
-{
- omap_serial_init();
-}
#endif
/*
@@ -718,7 +620,7 @@ static void __init omap_3430sdp_init(void)
else
gpio_pendown = SDP3430_TS_GPIO_IRQ_SDPV1;
omap_ads7846_init(1, gpio_pendown, 310, NULL);
- board_serial_init();
+ omap_serial_init();
usb_musb_init(NULL);
board_smc91x_init();
board_flash_init(sdp_flash_partitions, chip_sel_3430, 0);
diff --git a/arch/arm/mach-omap2/board-4430sdp.c b/arch/arm/mach-omap2/board-4430sdp.c
index c7cef44..b80e506 100644
--- a/arch/arm/mach-omap2/board-4430sdp.c
+++ b/arch/arm/mach-omap2/board-4430sdp.c
@@ -688,74 +688,8 @@ static struct omap_board_mux board_mux[] __initdata = {
{ .reg_offset = OMAP_MUX_TERMINATOR },
};
-static struct omap_device_pad serial2_pads[] __initdata = {
- OMAP_MUX_STATIC("uart2_cts.uart2_cts",
- OMAP_PIN_INPUT_PULLUP | OMAP_MUX_MODE0),
- OMAP_MUX_STATIC("uart2_rts.uart2_rts",
- OMAP_PIN_OUTPUT | OMAP_MUX_MODE0),
- OMAP_MUX_STATIC("uart2_rx.uart2_rx",
- OMAP_PIN_INPUT_PULLUP | OMAP_MUX_MODE0),
- OMAP_MUX_STATIC("uart2_tx.uart2_tx",
- OMAP_PIN_OUTPUT | OMAP_MUX_MODE0),
-};
-
-static struct omap_device_pad serial3_pads[] __initdata = {
- OMAP_MUX_STATIC("uart3_cts_rctx.uart3_cts_rctx",
- OMAP_PIN_INPUT_PULLUP | OMAP_MUX_MODE0),
- OMAP_MUX_STATIC("uart3_rts_sd.uart3_rts_sd",
- OMAP_PIN_OUTPUT | OMAP_MUX_MODE0),
- OMAP_MUX_STATIC("uart3_rx_irrx.uart3_rx_irrx",
- OMAP_PIN_INPUT | OMAP_MUX_MODE0),
- OMAP_MUX_STATIC("uart3_tx_irtx.uart3_tx_irtx",
- OMAP_PIN_OUTPUT | OMAP_MUX_MODE0),
-};
-
-static struct omap_device_pad serial4_pads[] __initdata = {
- OMAP_MUX_STATIC("uart4_rx.uart4_rx",
- OMAP_PIN_INPUT | OMAP_MUX_MODE0),
- OMAP_MUX_STATIC("uart4_tx.uart4_tx",
- OMAP_PIN_OUTPUT | OMAP_MUX_MODE0),
-};
-
-static struct omap_board_data serial2_data __initdata = {
- .id = 1,
- .pads = serial2_pads,
- .pads_cnt = ARRAY_SIZE(serial2_pads),
-};
-
-static struct omap_board_data serial3_data __initdata = {
- .id = 2,
- .pads = serial3_pads,
- .pads_cnt = ARRAY_SIZE(serial3_pads),
-};
-
-static struct omap_board_data serial4_data __initdata = {
- .id = 3,
- .pads = serial4_pads,
- .pads_cnt = ARRAY_SIZE(serial4_pads),
-};
-
-static inline void board_serial_init(void)
-{
- struct omap_board_data bdata;
- bdata.flags = 0;
- bdata.pads = NULL;
- bdata.pads_cnt = 0;
- bdata.id = 0;
- /* pass dummy data for UART1 */
- omap_serial_init_port(&bdata);
-
- omap_serial_init_port(&serial2_data);
- omap_serial_init_port(&serial3_data);
- omap_serial_init_port(&serial4_data);
-}
#else
#define board_mux NULL
-
-static inline void board_serial_init(void)
-{
- omap_serial_init();
-}
#endif
static void omap4_sdp4430_wifi_mux_init(void)
@@ -808,7 +742,7 @@ static void __init omap_4430sdp_init(void)
omap4_i2c_init();
omap_sfh7741prox_init();
platform_add_devices(sdp4430_devices, ARRAY_SIZE(sdp4430_devices));
- board_serial_init();
+ omap_serial_init();
omap4_sdp4430_wifi_init();
omap4_twl6030_hsmmc_init(mmc);
diff --git a/arch/arm/mach-omap2/board-omap4panda.c b/arch/arm/mach-omap2/board-omap4panda.c
index 9aaa960..1410312 100644
--- a/arch/arm/mach-omap2/board-omap4panda.c
+++ b/arch/arm/mach-omap2/board-omap4panda.c
@@ -370,74 +370,8 @@ static struct omap_board_mux board_mux[] __initdata = {
{ .reg_offset = OMAP_MUX_TERMINATOR },
};
-static struct omap_device_pad serial2_pads[] __initdata = {
- OMAP_MUX_STATIC("uart2_cts.uart2_cts",
- OMAP_PIN_INPUT_PULLUP | OMAP_MUX_MODE0),
- OMAP_MUX_STATIC("uart2_rts.uart2_rts",
- OMAP_PIN_OUTPUT | OMAP_MUX_MODE0),
- OMAP_MUX_STATIC("uart2_rx.uart2_rx",
- OMAP_PIN_INPUT_PULLUP | OMAP_MUX_MODE0),
- OMAP_MUX_STATIC("uart2_tx.uart2_tx",
- OMAP_PIN_OUTPUT | OMAP_MUX_MODE0),
-};
-
-static struct omap_device_pad serial3_pads[] __initdata = {
- OMAP_MUX_STATIC("uart3_cts_rctx.uart3_cts_rctx",
- OMAP_PIN_INPUT_PULLUP | OMAP_MUX_MODE0),
- OMAP_MUX_STATIC("uart3_rts_sd.uart3_rts_sd",
- OMAP_PIN_OUTPUT | OMAP_MUX_MODE0),
- OMAP_MUX_STATIC("uart3_rx_irrx.uart3_rx_irrx",
- OMAP_PIN_INPUT | OMAP_MUX_MODE0),
- OMAP_MUX_STATIC("uart3_tx_irtx.uart3_tx_irtx",
- OMAP_PIN_OUTPUT | OMAP_MUX_MODE0),
-};
-
-static struct omap_device_pad serial4_pads[] __initdata = {
- OMAP_MUX_STATIC("uart4_rx.uart4_rx",
- OMAP_PIN_INPUT | OMAP_MUX_MODE0),
- OMAP_MUX_STATIC("uart4_tx.uart4_tx",
- OMAP_PIN_OUTPUT | OMAP_MUX_MODE0),
-};
-
-static struct omap_board_data serial2_data __initdata = {
- .id = 1,
- .pads = serial2_pads,
- .pads_cnt = ARRAY_SIZE(serial2_pads),
-};
-
-static struct omap_board_data serial3_data __initdata = {
- .id = 2,
- .pads = serial3_pads,
- .pads_cnt = ARRAY_SIZE(serial3_pads),
-};
-
-static struct omap_board_data serial4_data __initdata = {
- .id = 3,
- .pads = serial4_pads,
- .pads_cnt = ARRAY_SIZE(serial4_pads),
-};
-
-static inline void board_serial_init(void)
-{
- struct omap_board_data bdata;
- bdata.flags = 0;
- bdata.pads = NULL;
- bdata.pads_cnt = 0;
- bdata.id = 0;
- /* pass dummy data for UART1 */
- omap_serial_init_port(&bdata);
-
- omap_serial_init_port(&serial2_data);
- omap_serial_init_port(&serial3_data);
- omap_serial_init_port(&serial4_data);
-}
#else
#define board_mux NULL
-
-static inline void board_serial_init(void)
-{
- omap_serial_init();
-}
#endif
/* Display DVI */
@@ -568,7 +502,7 @@ static void __init omap4_panda_init(void)
omap4_panda_i2c_init();
platform_add_devices(panda_devices, ARRAY_SIZE(panda_devices));
platform_device_register(&omap_vwlan_device);
- board_serial_init();
+ omap_serial_init();
omap4_twl6030_hsmmc_init(mmc);
omap4_ehci_init();
usb_musb_init(&musb_board_data);
diff --git a/arch/arm/mach-omap2/serial.c b/arch/arm/mach-omap2/serial.c
index 5632de5..6d3e228 100644
--- a/arch/arm/mach-omap2/serial.c
+++ b/arch/arm/mach-omap2/serial.c
@@ -62,7 +62,6 @@ struct omap_uart_state {
void __iomem *wk_st;
void __iomem *wk_en;
u32 wk_mask;
- u32 padconf;
u32 dma_enabled;
int clocked;
@@ -294,13 +293,6 @@ static void omap_uart_enable_wakeup(struct omap_uart_state *uart)
v |= uart->wk_mask;
__raw_writel(v, uart->wk_en);
}
-
- /* Ensure IOPAD wake-enables are set */
- if (cpu_is_omap34xx() && uart->padconf) {
- u16 v = omap_ctrl_readw(uart->padconf);
- v |= OMAP3_PADCONF_WAKEUPENABLE0;
- omap_ctrl_writew(v, uart->padconf);
- }
}
static void omap_uart_disable_wakeup(struct omap_uart_state *uart)
@@ -311,13 +303,6 @@ static void omap_uart_disable_wakeup(struct omap_uart_state *uart)
v &= ~uart->wk_mask;
__raw_writel(v, uart->wk_en);
}
-
- /* Ensure IOPAD wake-enables are cleared */
- if (cpu_is_omap34xx() && uart->padconf) {
- u16 v = omap_ctrl_readw(uart->padconf);
- v &= ~OMAP3_PADCONF_WAKEUPENABLE0;
- omap_ctrl_writew(v, uart->padconf);
- }
}
static void omap_uart_smart_idle_enable(struct omap_uart_state *uart,
@@ -380,7 +365,6 @@ static void omap_uart_idle_init(struct omap_uart_state *uart)
if (cpu_is_omap34xx() && !cpu_is_ti816x()) {
u32 mod = (uart->num > 1) ? OMAP3430_PER_MOD : CORE_MOD;
u32 wk_mask = 0;
- u32 padconf = 0;
/* XXX These PRM accesses do not belong here */
uart->wk_en = OMAP34XX_PRM_REGADDR(mod, PM_WKEN1);
@@ -388,23 +372,18 @@ static void omap_uart_idle_init(struct omap_uart_state *uart)
switch (uart->num) {
case 0:
wk_mask = OMAP3430_ST_UART1_MASK;
- padconf = 0x182;
break;
case 1:
wk_mask = OMAP3430_ST_UART2_MASK;
- padconf = 0x17a;
break;
case 2:
wk_mask = OMAP3430_ST_UART3_MASK;
- padconf = 0x19e;
break;
case 3:
wk_mask = OMAP3630_ST_UART4_MASK;
- padconf = 0x0d2;
break;
}
uart->wk_mask = wk_mask;
- uart->padconf = padconf;
} else if (cpu_is_omap24xx()) {
u32 wk_mask = 0;
u32 wk_en = PM_WKEN1, wk_st = PM_WKST1;
@@ -434,12 +413,10 @@ static void omap_uart_idle_init(struct omap_uart_state *uart)
uart->wk_en = NULL;
uart->wk_st = NULL;
uart->wk_mask = 0;
- uart->padconf = 0;
}
}
#else
-static inline void omap_uart_idle_init(struct omap_uart_state *uart) {}
static void omap_uart_block_sleep(struct omap_uart_state *uart)
{
/* Needed to enable UART clocks when built without CONFIG_PM */
@@ -447,6 +424,130 @@ static void omap_uart_block_sleep(struct omap_uart_state *uart)
}
#endif /* CONFIG_PM */
+#ifdef CONFIG_OMAP_MUX
+static struct omap_device_pad default_uart1_pads[] __initdata = {
+ {
+ .name = "uart1_cts.uart1_cts",
+ .enable = OMAP_PIN_INPUT_PULLUP | OMAP_MUX_MODE0,
+ },
+ {
+ .name = "uart1_rts.uart1_rts",
+ .enable = OMAP_PIN_OUTPUT | OMAP_MUX_MODE0,
+ },
+ {
+ .name = "uart1_tx.uart1_tx",
+ .enable = OMAP_PIN_OUTPUT | OMAP_MUX_MODE0,
+ },
+ {
+ .name = "uart1_rx.uart1_rx",
+ .flags = OMAP_DEVICE_PAD_REMUX | OMAP_DEVICE_PAD_WAKEUP,
+ .enable = OMAP_PIN_INPUT_PULLUP | OMAP_MUX_MODE0,
+ .idle = OMAP_PIN_INPUT_PULLUP | OMAP_MUX_MODE0,
+ },
+};
+
+static struct omap_device_pad default_uart2_pads[] __initdata = {
+ {
+ .name = "uart2_cts.uart2_cts",
+ .enable = OMAP_PIN_INPUT_PULLUP | OMAP_MUX_MODE0,
+ },
+ {
+ .name = "uart2_rts.uart2_rts",
+ .enable = OMAP_PIN_OUTPUT | OMAP_MUX_MODE0,
+ },
+ {
+ .name = "uart2_tx.uart2_tx",
+ .enable = OMAP_PIN_OUTPUT | OMAP_MUX_MODE0,
+ },
+ {
+ .name = "uart2_rx.uart2_rx",
+ .flags = OMAP_DEVICE_PAD_REMUX | OMAP_DEVICE_PAD_WAKEUP,
+ .enable = OMAP_PIN_INPUT_PULLUP | OMAP_MUX_MODE0,
+ .idle = OMAP_PIN_INPUT_PULLUP | OMAP_MUX_MODE0,
+ },
+};
+
+static struct omap_device_pad default_uart3_pads[] __initdata = {
+ {
+ .name = "uart3_cts_rctx.uart3_cts_rctx",
+ .enable = OMAP_PIN_INPUT_PULLUP | OMAP_MUX_MODE0,
+ },
+ {
+ .name = "uart3_rts_sd.uart3_rts_sd",
+ .enable = OMAP_PIN_OUTPUT | OMAP_MUX_MODE0,
+ },
+ {
+ .name = "uart3_tx_irtx.uart3_tx_irtx",
+ .enable = OMAP_PIN_OUTPUT | OMAP_MUX_MODE0,
+ },
+ {
+ .name = "uart3_rx_irrx.uart3_rx_irrx",
+ .flags = OMAP_DEVICE_PAD_REMUX | OMAP_DEVICE_PAD_WAKEUP,
+ .enable = OMAP_PIN_INPUT | OMAP_MUX_MODE0,
+ .idle = OMAP_PIN_INPUT | OMAP_MUX_MODE0,
+ },
+};
+
+static struct omap_device_pad default_omap36xx_uart4_pads[] __initdata = {
+ {
+ .name = "gpmc_wait2.uart4_tx",
+ .enable = OMAP_PIN_OUTPUT | OMAP_MUX_MODE0,
+ },
+ {
+ .name = "gpmc_wait3.uart4_rx",
+ .flags = OMAP_DEVICE_PAD_REMUX | OMAP_DEVICE_PAD_WAKEUP,
+ .enable = OMAP_PIN_INPUT | OMAP_MUX_MODE2,
+ .idle = OMAP_PIN_INPUT | OMAP_MUX_MODE2,
+ },
+};
+
+static struct omap_device_pad default_omap4_uart4_pads[] __initdata = {
+ {
+ .name = "uart4_tx.uart4_tx",
+ .enable = OMAP_PIN_OUTPUT | OMAP_MUX_MODE0,
+ },
+ {
+ .name = "uart4_rx.uart4_rx",
+ .flags = OMAP_DEVICE_PAD_REMUX | OMAP_DEVICE_PAD_WAKEUP,
+ .enable = OMAP_PIN_INPUT | OMAP_MUX_MODE0,
+ .idle = OMAP_PIN_INPUT | OMAP_MUX_MODE0,
+ },
+};
+
+static void omap_serial_fill_default_pads(struct omap_board_data *bdata)
+{
+ switch (bdata->id) {
+ case 0:
+ bdata->pads = default_uart1_pads;
+ bdata->pads_cnt = ARRAY_SIZE(default_uart1_pads);
+ break;
+ case 1:
+ bdata->pads = default_uart2_pads;
+ bdata->pads_cnt = ARRAY_SIZE(default_uart2_pads);
+ break;
+ case 2:
+ bdata->pads = default_uart3_pads;
+ bdata->pads_cnt = ARRAY_SIZE(default_uart3_pads);
+ break;
+ case 3:
+ if (cpu_is_omap44xx()) {
+ bdata->pads = default_omap4_uart4_pads;
+ bdata->pads_cnt =
+ ARRAY_SIZE(default_omap4_uart4_pads);
+ } else {
+ bdata->pads = default_omap36xx_uart4_pads;
+ bdata->pads_cnt =
+ ARRAY_SIZE(default_omap36xx_uart4_pads);
+ }
+ break;
+ default:
+ break;
+ }
+}
+#else
+static void omap_serial_fill_default_pads(struct omap_board_data *bdata) {}
+#endif
+
static int __init omap_serial_early_init(void)
{
int i = 0;
@@ -570,8 +671,8 @@ void __init omap_serial_init_port(struct omap_board_data *bdata)
omap_uart_block_sleep(uart);
console_unlock();
- if ((cpu_is_omap34xx() && uart->padconf) ||
- (uart->wk_en && uart->wk_mask))
+ if (((cpu_is_omap34xx() || cpu_is_omap44xx()) && bdata->pads) ||
+ (pdata->wk_en && pdata->wk_mask))
device_init_wakeup(&pdev->dev, true);
/* Enable the MDR1 errata for OMAP3 */
@@ -596,6 +697,10 @@ void __init omap_serial_init(void)
bdata.flags = 0;
bdata.pads = NULL;
bdata.pads_cnt = 0;
+
+ if (cpu_is_omap44xx() || cpu_is_omap34xx())
+ omap_serial_fill_default_pads(&bdata);
+
omap_serial_init_port(&bdata);
}
--
1.7.4.1
^ permalink raw reply related [flat|nested] 17+ messages in thread
* [PATCH v7 05/21] OMAP2+: UART: Remove mapbase/membase fields from pdata.
2011-10-18 15:25 [PATCH v7 00/21] OMAP2+: UART: Runtime adaptation + cleanup Govindraj.R
` (3 preceding siblings ...)
2011-10-18 15:25 ` [PATCH v7 04/21] OMAP2+: UART: Add default mux for all uarts Govindraj.R
@ 2011-10-18 15:26 ` Govindraj.R
2011-10-18 15:26 ` [PATCH v7 06/21] OMAP2+: UART: Add runtime pm support for omap-serial driver Govindraj.R
` (7 subsequent siblings)
12 siblings, 0 replies; 17+ messages in thread
From: Govindraj.R @ 2011-10-18 15:26 UTC (permalink / raw)
To: linux-arm-kernel
The mapbase (start_address), membase(io_remap cookie) part of
pdata struct omap_uart_port_info are removed as this should be
derived within driver.
Signed-off-by: Govindraj.R <govindraj.raja@ti.com>
---
arch/arm/mach-omap2/serial.c | 2 --
arch/arm/plat-omap/include/plat/omap-serial.h | 2 --
drivers/tty/serial/omap-serial.c | 10 ++++++++--
3 files changed, 8 insertions(+), 6 deletions(-)
diff --git a/arch/arm/mach-omap2/serial.c b/arch/arm/mach-omap2/serial.c
index 6d3e228..e7885fc 100644
--- a/arch/arm/mach-omap2/serial.c
+++ b/arch/arm/mach-omap2/serial.c
@@ -627,8 +627,6 @@ void __init omap_serial_init_port(struct omap_board_data *bdata)
omap_up.dma_enabled = uart->dma_enabled;
omap_up.uartclk = OMAP24XX_BASE_BAUD * 16;
- omap_up.mapbase = oh->slaves[0]->addr->pa_start;
- omap_up.membase = omap_hwmod_get_mpu_rt_va(oh);
omap_up.flags = UPF_BOOT_AUTOCONF;
pdata = &omap_up;
diff --git a/arch/arm/plat-omap/include/plat/omap-serial.h b/arch/arm/plat-omap/include/plat/omap-serial.h
index 307cd6f..db9bda9 100644
--- a/arch/arm/plat-omap/include/plat/omap-serial.h
+++ b/arch/arm/plat-omap/include/plat/omap-serial.h
@@ -59,8 +59,6 @@
struct omap_uart_port_info {
bool dma_enabled; /* To specify DMA Mode */
unsigned int uartclk; /* UART clock rate */
- void __iomem *membase; /* ioremap cookie or NULL */
- resource_size_t mapbase; /* resource base */
upf_t flags; /* UPF_* flags */
};
diff --git a/drivers/tty/serial/omap-serial.c b/drivers/tty/serial/omap-serial.c
index be368cf7..31f0cbf 100644
--- a/drivers/tty/serial/omap-serial.c
+++ b/drivers/tty/serial/omap-serial.c
@@ -1275,8 +1275,14 @@ static int serial_omap_probe(struct platform_device *pdev)
up->port.ops = &serial_omap_pops;
up->port.line = pdev->id;
- up->port.membase = omap_up_info->membase;
- up->port.mapbase = omap_up_info->mapbase;
+ up->port.mapbase = mem->start;
+ up->port.membase = ioremap(mem->start, resource_size(mem));
+ if (!up->port.membase) {
+ dev_err(&pdev->dev, "can't ioremap UART\n");
+ ret = -ENOMEM;
+ goto err;
+ }
+
up->port.flags = omap_up_info->flags;
up->port.uartclk = omap_up_info->uartclk;
up->uart_dma.uart_base = mem->start;
--
1.7.4.1
^ permalink raw reply related [flat|nested] 17+ messages in thread
* [PATCH v7 06/21] OMAP2+: UART: Add runtime pm support for omap-serial driver
2011-10-18 15:25 [PATCH v7 00/21] OMAP2+: UART: Runtime adaptation + cleanup Govindraj.R
` (4 preceding siblings ...)
2011-10-18 15:26 ` [PATCH v7 05/21] OMAP2+: UART: Remove mapbase/membase fields from pdata Govindraj.R
@ 2011-10-18 15:26 ` Govindraj.R
2011-10-18 15:26 ` [PATCH v7 07/21] OMAP2+: UART: Remove context_save and move context restore to driver Govindraj.R
` (6 subsequent siblings)
12 siblings, 0 replies; 17+ messages in thread
From: Govindraj.R @ 2011-10-18 15:26 UTC (permalink / raw)
To: linux-arm-kernel
Adapts omap-serial driver to use pm_runtime API's.
Use runtime runtime API's to handle uart clocks and obtain
device_usage statics. Set runtime API's usage to irq_safe so that
we can use get_sync from irq context. Auto-suspend for port specific
activities and put for reg access. Moving suspend/resume hooks
to dev_pm_ops structure and bing with config_suspend to avoid any
compilation warning if config_suspend is disabled.
By default uart autosuspend delay is set to -1 to avoid character loss
if uart's are autoidled and woken up on rx pin.
After boot up UART's can be autoidled by setting autosuspendi delay from sysfs.
echo 3000 > /sys/devices/platform/omap/omap_uart.X/power/autosuspend_delay_ms
X=0,1,2,3 for UART1/2/3/4. Number of uarts available may vary across omap_soc.
Acked-by: Alan Cox <alan@linux.intel.com>
Signed-off-by: Govindraj.R <govindraj.raja@ti.com>
---
drivers/tty/serial/omap-serial.c | 121 +++++++++++++++++++++++++++++++++----
1 files changed, 108 insertions(+), 13 deletions(-)
diff --git a/drivers/tty/serial/omap-serial.c b/drivers/tty/serial/omap-serial.c
index 31f0cbf..a39fc2f 100644
--- a/drivers/tty/serial/omap-serial.c
+++ b/drivers/tty/serial/omap-serial.c
@@ -37,11 +37,14 @@
#include <linux/clk.h>
#include <linux/serial_core.h>
#include <linux/irq.h>
+#include <linux/pm_runtime.h>
#include <plat/dma.h>
#include <plat/dmtimer.h>
#include <plat/omap-serial.h>
+#define OMAP_UART_AUTOSUSPEND_DELAY -1
+
static struct uart_omap_port *ui[OMAP_MAX_HSUART_PORTS];
/* Forward declaration of functions */
@@ -102,6 +105,8 @@ static void serial_omap_stop_rxdma(struct uart_omap_port *up)
omap_free_dma(up->uart_dma.rx_dma_channel);
up->uart_dma.rx_dma_channel = OMAP_UART_DMA_CH_FREE;
up->uart_dma.rx_dma_used = false;
+ pm_runtime_mark_last_busy(&up->pdev->dev);
+ pm_runtime_put_autosuspend(&up->pdev->dev);
}
}
@@ -110,8 +115,11 @@ static void serial_omap_enable_ms(struct uart_port *port)
struct uart_omap_port *up = (struct uart_omap_port *)port;
dev_dbg(up->port.dev, "serial_omap_enable_ms+%d\n", up->pdev->id);
+
+ pm_runtime_get_sync(&up->pdev->dev);
up->ier |= UART_IER_MSI;
serial_out(up, UART_IER, up->ier);
+ pm_runtime_put(&up->pdev->dev);
}
static void serial_omap_stop_tx(struct uart_port *port)
@@ -129,23 +137,32 @@ static void serial_omap_stop_tx(struct uart_port *port)
omap_stop_dma(up->uart_dma.tx_dma_channel);
omap_free_dma(up->uart_dma.tx_dma_channel);
up->uart_dma.tx_dma_channel = OMAP_UART_DMA_CH_FREE;
+ pm_runtime_mark_last_busy(&up->pdev->dev);
+ pm_runtime_put_autosuspend(&up->pdev->dev);
}
+ pm_runtime_get_sync(&up->pdev->dev);
if (up->ier & UART_IER_THRI) {
up->ier &= ~UART_IER_THRI;
serial_out(up, UART_IER, up->ier);
}
+
+ pm_runtime_mark_last_busy(&up->pdev->dev);
+ pm_runtime_put_autosuspend(&up->pdev->dev);
}
static void serial_omap_stop_rx(struct uart_port *port)
{
struct uart_omap_port *up = (struct uart_omap_port *)port;
+ pm_runtime_get_sync(&up->pdev->dev);
if (up->use_dma)
serial_omap_stop_rxdma(up);
up->ier &= ~UART_IER_RLSI;
up->port.read_status_mask &= ~UART_LSR_DR;
serial_out(up, UART_IER, up->ier);
+ pm_runtime_mark_last_busy(&up->pdev->dev);
+ pm_runtime_put_autosuspend(&up->pdev->dev);
}
static inline void receive_chars(struct uart_omap_port *up, int *status)
@@ -262,7 +279,10 @@ static void serial_omap_start_tx(struct uart_port *port)
int ret = 0;
if (!up->use_dma) {
+ pm_runtime_get_sync(&up->pdev->dev);
serial_omap_enable_ier_thri(up);
+ pm_runtime_mark_last_busy(&up->pdev->dev);
+ pm_runtime_put_autosuspend(&up->pdev->dev);
return;
}
@@ -272,6 +292,7 @@ static void serial_omap_start_tx(struct uart_port *port)
xmit = &up->port.state->xmit;
if (up->uart_dma.tx_dma_channel == OMAP_UART_DMA_CH_FREE) {
+ pm_runtime_get_sync(&up->pdev->dev);
ret = omap_request_dma(up->uart_dma.uart_dma_tx,
"UART Tx DMA",
(void *)uart_tx_dma_callback, up,
@@ -354,9 +375,13 @@ static inline irqreturn_t serial_omap_irq(int irq, void *dev_id)
unsigned int iir, lsr;
unsigned long flags;
+ pm_runtime_get_sync(&up->pdev->dev);
iir = serial_in(up, UART_IIR);
- if (iir & UART_IIR_NO_INT)
+ if (iir & UART_IIR_NO_INT) {
+ pm_runtime_mark_last_busy(&up->pdev->dev);
+ pm_runtime_put_autosuspend(&up->pdev->dev);
return IRQ_NONE;
+ }
spin_lock_irqsave(&up->port.lock, flags);
lsr = serial_in(up, UART_LSR);
@@ -378,6 +403,9 @@ static inline irqreturn_t serial_omap_irq(int irq, void *dev_id)
transmit_chars(up);
spin_unlock_irqrestore(&up->port.lock, flags);
+ pm_runtime_mark_last_busy(&up->pdev->dev);
+ pm_runtime_put_autosuspend(&up->pdev->dev);
+
up->port_activity = jiffies;
return IRQ_HANDLED;
}
@@ -388,11 +416,12 @@ static unsigned int serial_omap_tx_empty(struct uart_port *port)
unsigned long flags = 0;
unsigned int ret = 0;
+ pm_runtime_get_sync(&up->pdev->dev);
dev_dbg(up->port.dev, "serial_omap_tx_empty+%d\n", up->pdev->id);
spin_lock_irqsave(&up->port.lock, flags);
ret = serial_in(up, UART_LSR) & UART_LSR_TEMT ? TIOCSER_TEMT : 0;
spin_unlock_irqrestore(&up->port.lock, flags);
-
+ pm_runtime_put(&up->pdev->dev);
return ret;
}
@@ -402,7 +431,10 @@ static unsigned int serial_omap_get_mctrl(struct uart_port *port)
unsigned char status;
unsigned int ret = 0;
+ pm_runtime_get_sync(&up->pdev->dev);
status = check_modem_status(up);
+ pm_runtime_put(&up->pdev->dev);
+
dev_dbg(up->port.dev, "serial_omap_get_mctrl+%d\n", up->pdev->id);
if (status & UART_MSR_DCD)
@@ -433,8 +465,10 @@ static void serial_omap_set_mctrl(struct uart_port *port, unsigned int mctrl)
if (mctrl & TIOCM_LOOP)
mcr |= UART_MCR_LOOP;
+ pm_runtime_get_sync(&up->pdev->dev);
mcr |= up->mcr;
serial_out(up, UART_MCR, mcr);
+ pm_runtime_put(&up->pdev->dev);
}
static void serial_omap_break_ctl(struct uart_port *port, int break_state)
@@ -443,6 +477,7 @@ static void serial_omap_break_ctl(struct uart_port *port, int break_state)
unsigned long flags = 0;
dev_dbg(up->port.dev, "serial_omap_break_ctl+%d\n", up->pdev->id);
+ pm_runtime_get_sync(&up->pdev->dev);
spin_lock_irqsave(&up->port.lock, flags);
if (break_state == -1)
up->lcr |= UART_LCR_SBC;
@@ -450,6 +485,7 @@ static void serial_omap_break_ctl(struct uart_port *port, int break_state)
up->lcr &= ~UART_LCR_SBC;
serial_out(up, UART_LCR, up->lcr);
spin_unlock_irqrestore(&up->port.lock, flags);
+ pm_runtime_put(&up->pdev->dev);
}
static int serial_omap_startup(struct uart_port *port)
@@ -468,6 +504,7 @@ static int serial_omap_startup(struct uart_port *port)
dev_dbg(up->port.dev, "serial_omap_startup+%d\n", up->pdev->id);
+ pm_runtime_get_sync(&up->pdev->dev);
/*
* Clear the FIFO buffers and disable them.
* (they will be reenabled in set_termios())
@@ -523,6 +560,8 @@ static int serial_omap_startup(struct uart_port *port)
/* Enable module level wake up */
serial_out(up, UART_OMAP_WER, OMAP_UART_WER_MOD_WKUP);
+ pm_runtime_mark_last_busy(&up->pdev->dev);
+ pm_runtime_put_autosuspend(&up->pdev->dev);
up->port_activity = jiffies;
return 0;
}
@@ -533,6 +572,8 @@ static void serial_omap_shutdown(struct uart_port *port)
unsigned long flags = 0;
dev_dbg(up->port.dev, "serial_omap_shutdown+%d\n", up->pdev->id);
+
+ pm_runtime_get_sync(&up->pdev->dev);
/*
* Disable interrupts from this port
*/
@@ -566,6 +607,11 @@ static void serial_omap_shutdown(struct uart_port *port)
up->uart_dma.rx_buf_dma_phys);
up->uart_dma.rx_buf = NULL;
}
+
+ if (!device_may_wakeup(&up->pdev->dev))
+ pm_runtime_allow(&up->pdev->dev);
+
+ pm_runtime_put(&up->pdev->dev);
free_irq(up->port.irq, up);
}
@@ -680,6 +726,7 @@ serial_omap_set_termios(struct uart_port *port, struct ktermios *termios,
* Ok, we're now changing the port state. Do it with
* interrupts disabled.
*/
+ pm_runtime_get_sync(&up->pdev->dev);
spin_lock_irqsave(&up->port.lock, flags);
/*
@@ -809,6 +856,7 @@ serial_omap_set_termios(struct uart_port *port, struct ktermios *termios,
serial_omap_configure_xonxoff(up, termios);
spin_unlock_irqrestore(&up->port.lock, flags);
+ pm_runtime_put(&up->pdev->dev);
dev_dbg(up->port.dev, "serial_omap_set_termios+%d\n", up->pdev->id);
}
@@ -820,6 +868,8 @@ serial_omap_pm(struct uart_port *port, unsigned int state,
unsigned char efr;
dev_dbg(up->port.dev, "serial_omap_pm+%d\n", up->pdev->id);
+
+ pm_runtime_get_sync(&up->pdev->dev);
serial_out(up, UART_LCR, UART_LCR_CONF_MODE_B);
efr = serial_in(up, UART_EFR);
serial_out(up, UART_EFR, efr | UART_EFR_ECB);
@@ -829,6 +879,11 @@ serial_omap_pm(struct uart_port *port, unsigned int state,
serial_out(up, UART_LCR, UART_LCR_CONF_MODE_B);
serial_out(up, UART_EFR, efr);
serial_out(up, UART_LCR, 0);
+
+ if (!state && !device_may_wakeup(&up->pdev->dev))
+ pm_runtime_forbid(&up->pdev->dev);
+
+ pm_runtime_put(&up->pdev->dev);
}
static void serial_omap_release_port(struct uart_port *port)
@@ -906,19 +961,26 @@ static inline void wait_for_xmitr(struct uart_omap_port *up)
static void serial_omap_poll_put_char(struct uart_port *port, unsigned char ch)
{
struct uart_omap_port *up = (struct uart_omap_port *)port;
+
+ pm_runtime_get_sync(&up->pdev->dev);
wait_for_xmitr(up);
serial_out(up, UART_TX, ch);
+ pm_runtime_put(&up->pdev->dev);
}
static int serial_omap_poll_get_char(struct uart_port *port)
{
struct uart_omap_port *up = (struct uart_omap_port *)port;
- unsigned int status = serial_in(up, UART_LSR);
+ unsigned int status;
+ pm_runtime_get_sync(&up->pdev->dev);
+ status = serial_in(up, UART_LSR);
if (!(status & UART_LSR_DR))
return NO_POLL_CHAR;
- return serial_in(up, UART_RX);
+ status = serial_in(up, UART_RX);
+ pm_runtime_put(&up->pdev->dev);
+ return status;
}
#endif /* CONFIG_CONSOLE_POLL */
@@ -946,6 +1008,8 @@ serial_omap_console_write(struct console *co, const char *s,
unsigned int ier;
int locked = 1;
+ pm_runtime_get_sync(&up->pdev->dev);
+
local_irq_save(flags);
if (up->port.sysrq)
locked = 0;
@@ -978,6 +1042,8 @@ serial_omap_console_write(struct console *co, const char *s,
if (up->msr_saved_flags)
check_modem_status(up);
+ pm_runtime_mark_last_busy(&up->pdev->dev);
+ pm_runtime_put_autosuspend(&up->pdev->dev);
if (locked)
spin_unlock(&up->port.lock);
local_irq_restore(flags);
@@ -1060,24 +1126,25 @@ static struct uart_driver serial_omap_reg = {
.cons = OMAP_CONSOLE,
};
-static int
-serial_omap_suspend(struct platform_device *pdev, pm_message_t state)
+#ifdef CONFIG_SUSPEND
+static int serial_omap_suspend(struct device *dev)
{
- struct uart_omap_port *up = platform_get_drvdata(pdev);
+ struct uart_omap_port *up = dev_get_drvdata(dev);
if (up)
uart_suspend_port(&serial_omap_reg, &up->port);
return 0;
}
-static int serial_omap_resume(struct platform_device *dev)
+static int serial_omap_resume(struct device *dev)
{
- struct uart_omap_port *up = platform_get_drvdata(dev);
+ struct uart_omap_port *up = dev_get_drvdata(dev);
if (up)
uart_resume_port(&serial_omap_reg, &up->port);
return 0;
}
+#endif
static void serial_omap_rx_timeout(unsigned long uart_no)
{
@@ -1135,6 +1202,7 @@ static int serial_omap_start_rxdma(struct uart_omap_port *up)
int ret = 0;
if (up->uart_dma.rx_dma_channel == -1) {
+ pm_runtime_get_sync(&up->pdev->dev);
ret = omap_request_dma(up->uart_dma.uart_dma_rx,
"UART Rx DMA",
(void *)uart_rx_dma_callback, up,
@@ -1299,6 +1367,14 @@ static int serial_omap_probe(struct platform_device *pdev)
up->uart_dma.rx_dma_channel = OMAP_UART_DMA_CH_FREE;
}
+ pm_runtime_use_autosuspend(&pdev->dev);
+ pm_runtime_set_autosuspend_delay(&pdev->dev,
+ OMAP_UART_AUTOSUSPEND_DELAY);
+
+ pm_runtime_irq_safe(&pdev->dev);
+ pm_runtime_enable(&pdev->dev);
+ pm_runtime_get_sync(&pdev->dev);
+
ui[pdev->id] = up;
serial_omap_add_console_port(up);
@@ -1306,6 +1382,7 @@ static int serial_omap_probe(struct platform_device *pdev)
if (ret != 0)
goto do_release_region;
+ pm_runtime_put(&pdev->dev);
platform_set_drvdata(pdev, up);
return 0;
err:
@@ -1320,22 +1397,40 @@ static int serial_omap_remove(struct platform_device *dev)
{
struct uart_omap_port *up = platform_get_drvdata(dev);
- platform_set_drvdata(dev, NULL);
if (up) {
+ pm_runtime_disable(&up->pdev->dev);
uart_remove_one_port(&serial_omap_reg, &up->port);
kfree(up);
}
+
+ platform_set_drvdata(dev, NULL);
+ return 0;
+}
+
+#ifdef CONFIG_PM_RUNTIME
+static int serial_omap_runtime_suspend(struct device *dev)
+{
return 0;
}
+static int serial_omap_runtime_resume(struct device *dev)
+{
+ return 0;
+}
+#endif
+
+static const struct dev_pm_ops serial_omap_dev_pm_ops = {
+ SET_SYSTEM_SLEEP_PM_OPS(serial_omap_suspend, serial_omap_resume)
+ SET_RUNTIME_PM_OPS(serial_omap_runtime_suspend,
+ serial_omap_runtime_resume, NULL)
+};
+
static struct platform_driver serial_omap_driver = {
.probe = serial_omap_probe,
.remove = serial_omap_remove,
-
- .suspend = serial_omap_suspend,
- .resume = serial_omap_resume,
.driver = {
.name = DRIVER_NAME,
+ .pm = &serial_omap_dev_pm_ops,
},
};
--
1.7.4.1
^ permalink raw reply related [flat|nested] 17+ messages in thread
* [PATCH v7 07/21] OMAP2+: UART: Remove context_save and move context restore to driver
2011-10-18 15:25 [PATCH v7 00/21] OMAP2+: UART: Runtime adaptation + cleanup Govindraj.R
` (5 preceding siblings ...)
2011-10-18 15:26 ` [PATCH v7 06/21] OMAP2+: UART: Add runtime pm support for omap-serial driver Govindraj.R
@ 2011-10-18 15:26 ` Govindraj.R
2011-10-18 15:26 ` [PATCH v7 08/21] OMAP2+: UART: Ensure all reg values configured are available from port structure Govindraj.R
` (5 subsequent siblings)
12 siblings, 0 replies; 17+ messages in thread
From: Govindraj.R @ 2011-10-18 15:26 UTC (permalink / raw)
To: linux-arm-kernel
Remove context save function from serial.c and move context restore
function to omap-serial. Remove all regs stored in omap_uart_state
for contex_save/restore, reg read write funcs used in context_save/restore,
io_addresses populated for read/write funcs.
Clock gating mechanism was done in serial.c and had no info on uart state
thus we needed context save and restore in serial.c
With runtime conversion and clock gating done within uart driver
context restore can be done from regs value available from uart_omap_port
structure.
Signed-off-by: Govindraj.R <govindraj.raja@ti.com>
---
arch/arm/mach-omap2/serial.c | 118 --------------------------------------
drivers/tty/serial/omap-serial.c | 24 ++++++++
2 files changed, 24 insertions(+), 118 deletions(-)
diff --git a/arch/arm/mach-omap2/serial.c b/arch/arm/mach-omap2/serial.c
index e7885fc..cfe6055 100644
--- a/arch/arm/mach-omap2/serial.c
+++ b/arch/arm/mach-omap2/serial.c
@@ -41,8 +41,6 @@
#include "control.h"
#include "mux.h"
-#define UART_OMAP_WER 0x17 /* Wake-up enable register */
-
#define UART_ERRATA_i202_MDR1_ACCESS (0x1 << 1)
/*
@@ -66,27 +64,11 @@ struct omap_uart_state {
int clocked;
- int regshift;
- void __iomem *membase;
- resource_size_t mapbase;
-
struct list_head node;
struct omap_hwmod *oh;
struct platform_device *pdev;
u32 errata;
-#if defined(CONFIG_ARCH_OMAP3) && defined(CONFIG_PM)
- int context_valid;
-
- /* Registers to be saved/restored for OFF-mode */
- u16 dll;
- u16 dlh;
- u16 ier;
- u16 sysc;
- u16 scr;
- u16 wer;
- u16 mcr;
-#endif
};
static LIST_HEAD(uart_list);
@@ -114,34 +96,6 @@ static struct omap_device_pm_latency omap_uart_latency[] = {
},
};
-static inline unsigned int __serial_read_reg(struct uart_port *up,
- int offset)
-{
- offset <<= up->regshift;
- return (unsigned int)__raw_readb(up->membase + offset);
-}
-
-static inline unsigned int serial_read_reg(struct omap_uart_state *uart,
- int offset)
-{
- offset <<= uart->regshift;
- return (unsigned int)__raw_readb(uart->membase + offset);
-}
-
-static inline void __serial_write_reg(struct uart_port *up, int offset,
- int value)
-{
- offset <<= up->regshift;
- __raw_writeb(value, up->membase + offset);
-}
-
-static inline void serial_write_reg(struct omap_uart_state *uart, int offset,
- int value)
-{
- offset <<= uart->regshift;
- __raw_writeb(value, uart->membase + offset);
-}
-
/*
* Internal UARTs need to be initialized for the 8250 autoconfig to work
* properly. Note that the TX watermark initialization may not be needed
@@ -192,75 +146,6 @@ static void omap_uart_mdr1_errataset(struct omap_uart_state *uart, u8 mdr1_val,
}
}
-static void omap_uart_save_context(struct omap_uart_state *uart)
-{
- u16 lcr = 0;
-
- if (!enable_off_mode)
- return;
-
- lcr = serial_read_reg(uart, UART_LCR);
- serial_write_reg(uart, UART_LCR, UART_LCR_CONF_MODE_B);
- uart->dll = serial_read_reg(uart, UART_DLL);
- uart->dlh = serial_read_reg(uart, UART_DLM);
- serial_write_reg(uart, UART_LCR, lcr);
- uart->ier = serial_read_reg(uart, UART_IER);
- uart->sysc = serial_read_reg(uart, UART_OMAP_SYSC);
- uart->scr = serial_read_reg(uart, UART_OMAP_SCR);
- uart->wer = serial_read_reg(uart, UART_OMAP_WER);
- serial_write_reg(uart, UART_LCR, UART_LCR_CONF_MODE_A);
- uart->mcr = serial_read_reg(uart, UART_MCR);
- serial_write_reg(uart, UART_LCR, lcr);
-
- uart->context_valid = 1;
-}
-
-static void omap_uart_restore_context(struct omap_uart_state *uart)
-{
- u16 efr = 0;
-
- if (!enable_off_mode)
- return;
-
- if (!uart->context_valid)
- return;
-
- uart->context_valid = 0;
-
- if (uart->errata & UART_ERRATA_i202_MDR1_ACCESS)
- omap_uart_mdr1_errataset(uart, UART_OMAP_MDR1_DISABLE, 0xA0);
- else
- serial_write_reg(uart, UART_OMAP_MDR1, UART_OMAP_MDR1_DISABLE);
-
- serial_write_reg(uart, UART_LCR, UART_LCR_CONF_MODE_B);
- efr = serial_read_reg(uart, UART_EFR);
- serial_write_reg(uart, UART_EFR, UART_EFR_ECB);
- serial_write_reg(uart, UART_LCR, 0x0); /* Operational mode */
- serial_write_reg(uart, UART_IER, 0x0);
- serial_write_reg(uart, UART_LCR, UART_LCR_CONF_MODE_B);
- serial_write_reg(uart, UART_DLL, uart->dll);
- serial_write_reg(uart, UART_DLM, uart->dlh);
- serial_write_reg(uart, UART_LCR, 0x0); /* Operational mode */
- serial_write_reg(uart, UART_IER, uart->ier);
- serial_write_reg(uart, UART_LCR, UART_LCR_CONF_MODE_A);
- serial_write_reg(uart, UART_MCR, uart->mcr);
- serial_write_reg(uart, UART_LCR, UART_LCR_CONF_MODE_B);
- serial_write_reg(uart, UART_EFR, efr);
- serial_write_reg(uart, UART_LCR, UART_LCR_WLEN8);
- serial_write_reg(uart, UART_OMAP_SCR, uart->scr);
- serial_write_reg(uart, UART_OMAP_WER, uart->wer);
- serial_write_reg(uart, UART_OMAP_SYSC, uart->sysc);
-
- if (uart->errata & UART_ERRATA_i202_MDR1_ACCESS)
- omap_uart_mdr1_errataset(uart, UART_OMAP_MDR1_16X_MODE, 0xA1);
- else
- /* UART 16x mode */
- serial_write_reg(uart, UART_OMAP_MDR1,
- UART_OMAP_MDR1_16X_MODE);
-}
-#else
-static inline void omap_uart_save_context(struct omap_uart_state *uart) {}
-static inline void omap_uart_restore_context(struct omap_uart_state *uart) {}
#endif /* CONFIG_PM && CONFIG_ARCH_OMAP3 */
static inline void omap_uart_enable_clocks(struct omap_uart_state *uart)
@@ -644,9 +529,6 @@ void __init omap_serial_init_port(struct omap_board_data *bdata)
omap_device_disable_idle_on_suspend(pdev);
oh->mux = omap_hwmod_mux_init(bdata->pads, bdata->pads_cnt);
- uart->regshift = 2;
- uart->mapbase = oh->slaves[0]->addr->pa_start;
- uart->membase = omap_hwmod_get_mpu_rt_va(oh);
uart->pdev = pdev;
oh->dev_attr = uart;
diff --git a/drivers/tty/serial/omap-serial.c b/drivers/tty/serial/omap-serial.c
index a39fc2f..0d87985 100644
--- a/drivers/tty/serial/omap-serial.c
+++ b/drivers/tty/serial/omap-serial.c
@@ -1407,6 +1407,25 @@ static int serial_omap_remove(struct platform_device *dev)
return 0;
}
+static void serial_omap_restore_context(struct uart_omap_port *up)
+{
+ serial_out(up, UART_OMAP_MDR1, UART_OMAP_MDR1_DISABLE);
+ serial_out(up, UART_LCR, UART_LCR_CONF_MODE_B); /* Config B mode */
+ serial_out(up, UART_EFR, UART_EFR_ECB);
+ serial_out(up, UART_LCR, 0x0); /* Operational mode */
+ serial_out(up, UART_IER, 0x0);
+ serial_out(up, UART_LCR, UART_LCR_CONF_MODE_B); /* Config B mode */
+ serial_out(up, UART_LCR, 0x0); /* Operational mode */
+ serial_out(up, UART_IER, up->ier);
+ serial_out(up, UART_FCR, up->fcr);
+ serial_out(up, UART_LCR, UART_LCR_CONF_MODE_A);
+ serial_out(up, UART_MCR, up->mcr);
+ serial_out(up, UART_LCR, UART_LCR_CONF_MODE_B); /* Config B mode */
+ serial_out(up, UART_EFR, up->efr);
+ serial_out(up, UART_LCR, up->lcr);
+ serial_out(up, UART_OMAP_MDR1, UART_OMAP_MDR1_16X_MODE);
+}
+
#ifdef CONFIG_PM_RUNTIME
static int serial_omap_runtime_suspend(struct device *dev)
{
@@ -1415,6 +1434,11 @@ static int serial_omap_runtime_suspend(struct device *dev)
static int serial_omap_runtime_resume(struct device *dev)
{
+ struct uart_omap_port *up = dev_get_drvdata(dev);
+
+ if (up)
+ serial_omap_restore_context(up);
+
return 0;
}
#endif
--
1.7.4.1
^ permalink raw reply related [flat|nested] 17+ messages in thread
* [PATCH v7 08/21] OMAP2+: UART: Ensure all reg values configured are available from port structure
2011-10-18 15:25 [PATCH v7 00/21] OMAP2+: UART: Runtime adaptation + cleanup Govindraj.R
` (6 preceding siblings ...)
2011-10-18 15:26 ` [PATCH v7 07/21] OMAP2+: UART: Remove context_save and move context restore to driver Govindraj.R
@ 2011-10-18 15:26 ` Govindraj.R
2011-10-18 15:26 ` [PATCH v7 09/21] OMAP2+: UART: Remove uart reset function Govindraj.R
` (4 subsequent siblings)
12 siblings, 0 replies; 17+ messages in thread
From: Govindraj.R @ 2011-10-18 15:26 UTC (permalink / raw)
To: linux-arm-kernel
Add missing uart regs to uart_port structure which can be used in
context restore. Store dll, dlh, mdr1, scr, efr, lcr, mcr reg values
into uart_port structure while configuring individual port in termios
function.
Signed-off-by: Govindraj.R <govindraj.raja@ti.com>
---
arch/arm/plat-omap/include/plat/omap-serial.h | 4 ++
drivers/tty/serial/omap-serial.c | 43 +++++++++++++++----------
2 files changed, 30 insertions(+), 17 deletions(-)
diff --git a/arch/arm/plat-omap/include/plat/omap-serial.h b/arch/arm/plat-omap/include/plat/omap-serial.h
index db9bda9..70e7738 100644
--- a/arch/arm/plat-omap/include/plat/omap-serial.h
+++ b/arch/arm/plat-omap/include/plat/omap-serial.h
@@ -97,6 +97,10 @@ struct uart_omap_port {
unsigned char mcr;
unsigned char fcr;
unsigned char efr;
+ unsigned char dll;
+ unsigned char dlh;
+ unsigned char mdr1;
+ unsigned char scr;
int use_dma;
/*
diff --git a/drivers/tty/serial/omap-serial.c b/drivers/tty/serial/omap-serial.c
index 0d87985..192fc8b 100644
--- a/drivers/tty/serial/omap-serial.c
+++ b/drivers/tty/serial/omap-serial.c
@@ -466,8 +466,9 @@ static void serial_omap_set_mctrl(struct uart_port *port, unsigned int mctrl)
mcr |= UART_MCR_LOOP;
pm_runtime_get_sync(&up->pdev->dev);
- mcr |= up->mcr;
- serial_out(up, UART_MCR, mcr);
+ up->mcr = serial_in(up, UART_MCR);
+ up->mcr |= mcr;
+ serial_out(up, UART_MCR, up->mcr);
pm_runtime_put(&up->pdev->dev);
}
@@ -619,8 +620,6 @@ static inline void
serial_omap_configure_xonxoff
(struct uart_omap_port *up, struct ktermios *termios)
{
- unsigned char efr = 0;
-
up->lcr = serial_in(up, UART_LCR);
serial_out(up, UART_LCR, UART_LCR_CONF_MODE_B);
up->efr = serial_in(up, UART_EFR);
@@ -630,8 +629,7 @@ serial_omap_configure_xonxoff
serial_out(up, UART_XOFF1, termios->c_cc[VSTOP]);
/* clear SW control mode bits */
- efr = up->efr;
- efr &= OMAP_UART_SW_CLR;
+ up->efr &= OMAP_UART_SW_CLR;
/*
* IXON Flag:
@@ -639,7 +637,7 @@ serial_omap_configure_xonxoff
* Transmit XON1, XOFF1
*/
if (termios->c_iflag & IXON)
- efr |= OMAP_UART_SW_TX;
+ up->efr |= OMAP_UART_SW_TX;
/*
* IXOFF Flag:
@@ -647,7 +645,7 @@ serial_omap_configure_xonxoff
* Receiver compares XON1, XOFF1.
*/
if (termios->c_iflag & IXOFF)
- efr |= OMAP_UART_SW_RX;
+ up->efr |= OMAP_UART_SW_RX;
serial_out(up, UART_EFR, up->efr | UART_EFR_ECB);
serial_out(up, UART_LCR, UART_LCR_CONF_MODE_A);
@@ -670,7 +668,7 @@ serial_omap_configure_xonxoff
* load the new software flow control mode IXON or IXOFF
* and restore the UARTi.EFR_REG[4] ENHANCED_EN value.
*/
- serial_out(up, UART_EFR, efr | UART_EFR_SCD);
+ serial_out(up, UART_EFR, up->efr | UART_EFR_SCD);
serial_out(up, UART_LCR, UART_LCR_CONF_MODE_A);
serial_out(up, UART_MCR, up->mcr & ~UART_MCR_TCRTLR);
@@ -717,6 +715,10 @@ serial_omap_set_termios(struct uart_port *port, struct ktermios *termios,
baud = uart_get_baud_rate(port, termios, old, 0, port->uartclk/13);
quot = serial_omap_get_divisor(port, baud);
+ up->dll = quot & 0xff;
+ up->dlh = quot >> 8;
+ up->mdr1 = UART_OMAP_MDR1_DISABLE;
+
up->fcr = UART_FCR_R_TRIG_01 | UART_FCR_T_TRIG_01 |
UART_FCR_ENABLE_FIFO;
if (up->use_dma)
@@ -770,6 +772,7 @@ serial_omap_set_termios(struct uart_port *port, struct ktermios *termios,
up->ier |= UART_IER_MSI;
serial_out(up, UART_IER, up->ier);
serial_out(up, UART_LCR, cval); /* reset DLAB */
+ up->lcr = cval;
/* FIFOs and DMA Settings */
@@ -796,17 +799,18 @@ serial_omap_set_termios(struct uart_port *port, struct ktermios *termios,
if (up->use_dma) {
serial_out(up, UART_TI752_TLR, 0);
- serial_out(up, UART_OMAP_SCR,
- (UART_FCR_TRIGGER_4 | UART_FCR_TRIGGER_8));
+ up->scr |= (UART_FCR_TRIGGER_4 | UART_FCR_TRIGGER_8);
}
+ serial_out(up, UART_OMAP_SCR, up->scr);
+
serial_out(up, UART_EFR, up->efr);
serial_out(up, UART_LCR, UART_LCR_CONF_MODE_A);
serial_out(up, UART_MCR, up->mcr);
/* Protocol, Baud Rate, and Interrupt Settings */
- serial_out(up, UART_OMAP_MDR1, UART_OMAP_MDR1_DISABLE);
+ serial_out(up, UART_OMAP_MDR1, up->mdr1);
serial_out(up, UART_LCR, UART_LCR_CONF_MODE_B);
up->efr = serial_in(up, UART_EFR);
@@ -816,8 +820,8 @@ serial_omap_set_termios(struct uart_port *port, struct ktermios *termios,
serial_out(up, UART_IER, 0);
serial_out(up, UART_LCR, UART_LCR_CONF_MODE_B);
- serial_out(up, UART_DLL, quot & 0xff); /* LS of divisor */
- serial_out(up, UART_DLM, quot >> 8); /* MS of divisor */
+ serial_out(up, UART_DLL, up->dll); /* LS of divisor */
+ serial_out(up, UART_DLM, up->dlh); /* MS of divisor */
serial_out(up, UART_LCR, 0);
serial_out(up, UART_IER, up->ier);
@@ -827,9 +831,11 @@ serial_omap_set_termios(struct uart_port *port, struct ktermios *termios,
serial_out(up, UART_LCR, cval);
if (baud > 230400 && baud != 3000000)
- serial_out(up, UART_OMAP_MDR1, UART_OMAP_MDR1_13X_MODE);
+ up->mdr1 = UART_OMAP_MDR1_13X_MODE;
else
- serial_out(up, UART_OMAP_MDR1, UART_OMAP_MDR1_16X_MODE);
+ up->mdr1 = UART_OMAP_MDR1_16X_MODE;
+
+ serial_out(up, UART_OMAP_MDR1, up->mdr1);
/* Hardware Flow Control Configuration */
@@ -1415,15 +1421,18 @@ static void serial_omap_restore_context(struct uart_omap_port *up)
serial_out(up, UART_LCR, 0x0); /* Operational mode */
serial_out(up, UART_IER, 0x0);
serial_out(up, UART_LCR, UART_LCR_CONF_MODE_B); /* Config B mode */
+ serial_out(up, UART_DLL, up->dll);
+ serial_out(up, UART_DLM, up->dlh);
serial_out(up, UART_LCR, 0x0); /* Operational mode */
serial_out(up, UART_IER, up->ier);
serial_out(up, UART_FCR, up->fcr);
serial_out(up, UART_LCR, UART_LCR_CONF_MODE_A);
serial_out(up, UART_MCR, up->mcr);
serial_out(up, UART_LCR, UART_LCR_CONF_MODE_B); /* Config B mode */
+ serial_out(up, UART_OMAP_SCR, up->scr);
serial_out(up, UART_EFR, up->efr);
serial_out(up, UART_LCR, up->lcr);
- serial_out(up, UART_OMAP_MDR1, UART_OMAP_MDR1_16X_MODE);
+ serial_out(up, UART_OMAP_MDR1, up->mdr1);
}
#ifdef CONFIG_PM_RUNTIME
--
1.7.4.1
^ permalink raw reply related [flat|nested] 17+ messages in thread
* [PATCH v7 09/21] OMAP2+: UART: Remove uart reset function.
2011-10-18 15:25 [PATCH v7 00/21] OMAP2+: UART: Runtime adaptation + cleanup Govindraj.R
` (7 preceding siblings ...)
2011-10-18 15:26 ` [PATCH v7 08/21] OMAP2+: UART: Ensure all reg values configured are available from port structure Govindraj.R
@ 2011-10-18 15:26 ` Govindraj.R
2011-10-18 15:26 ` [PATCH v7 10/21] OMAP2+: UART: Get context loss count to context restore Govindraj.R
` (3 subsequent siblings)
12 siblings, 0 replies; 17+ messages in thread
From: Govindraj.R @ 2011-10-18 15:26 UTC (permalink / raw)
To: linux-arm-kernel
Remove the uart reset function which is configuring the
TX empty irq which can now be handled within omap-serial driver.
Signed-off-by: Govindraj.R <govindraj.raja@ti.com>
---
arch/arm/mach-omap2/serial.c | 14 --------------
arch/arm/plat-omap/include/plat/omap-serial.h | 2 ++
drivers/tty/serial/omap-serial.c | 1 +
3 files changed, 3 insertions(+), 14 deletions(-)
diff --git a/arch/arm/mach-omap2/serial.c b/arch/arm/mach-omap2/serial.c
index cfe6055..7dd75f1 100644
--- a/arch/arm/mach-omap2/serial.c
+++ b/arch/arm/mach-omap2/serial.c
@@ -96,19 +96,6 @@ static struct omap_device_pm_latency omap_uart_latency[] = {
},
};
-/*
- * Internal UARTs need to be initialized for the 8250 autoconfig to work
- * properly. Note that the TX watermark initialization may not be needed
- * once the 8250.c watermark handling code is merged.
- */
-
-static inline void __init omap_uart_reset(struct omap_uart_state *uart)
-{
- serial_write_reg(uart, UART_OMAP_MDR1, UART_OMAP_MDR1_DISABLE);
- serial_write_reg(uart, UART_OMAP_SCR, 0x08);
- serial_write_reg(uart, UART_OMAP_MDR1, UART_OMAP_MDR1_16X_MODE);
-}
-
#if defined(CONFIG_PM) && defined(CONFIG_ARCH_OMAP3)
/*
@@ -544,7 +531,6 @@ void __init omap_serial_init_port(struct omap_board_data *bdata)
omap_device_enable(uart->pdev);
omap_uart_idle_init(uart);
- omap_uart_reset(uart);
omap_hwmod_enable_wakeup(uart->oh);
omap_device_idle(uart->pdev);
diff --git a/arch/arm/plat-omap/include/plat/omap-serial.h b/arch/arm/plat-omap/include/plat/omap-serial.h
index 70e7738..5b913c7 100644
--- a/arch/arm/plat-omap/include/plat/omap-serial.h
+++ b/arch/arm/plat-omap/include/plat/omap-serial.h
@@ -33,6 +33,8 @@
#define OMAP_MODE13X_SPEED 230400
+#define OMAP_UART_SCR_TX_EMPTY 0x08
+
/* WER = 0x7F
* Enable module level wakeup in WER reg
*/
diff --git a/drivers/tty/serial/omap-serial.c b/drivers/tty/serial/omap-serial.c
index 192fc8b..a7fdf94 100644
--- a/drivers/tty/serial/omap-serial.c
+++ b/drivers/tty/serial/omap-serial.c
@@ -773,6 +773,7 @@ serial_omap_set_termios(struct uart_port *port, struct ktermios *termios,
serial_out(up, UART_IER, up->ier);
serial_out(up, UART_LCR, cval); /* reset DLAB */
up->lcr = cval;
+ up->scr = OMAP_UART_SCR_TX_EMPTY;
/* FIFOs and DMA Settings */
--
1.7.4.1
^ permalink raw reply related [flat|nested] 17+ messages in thread
* [PATCH v7 10/21] OMAP2+: UART: Get context loss count to context restore
2011-10-18 15:25 [PATCH v7 00/21] OMAP2+: UART: Runtime adaptation + cleanup Govindraj.R
` (8 preceding siblings ...)
2011-10-18 15:26 ` [PATCH v7 09/21] OMAP2+: UART: Remove uart reset function Govindraj.R
@ 2011-10-18 15:26 ` Govindraj.R
2011-10-18 15:26 ` [PATCH v7 11/21] OMAP2+: UART: Move errata handling from serial.c to omap-serial Govindraj.R
` (2 subsequent siblings)
12 siblings, 0 replies; 17+ messages in thread
From: Govindraj.R @ 2011-10-18 15:26 UTC (permalink / raw)
To: linux-arm-kernel
Avoid unconditional context restore every time we gate uart
clocks. Check whether context loss happened based on which
we can context restore uart regs from uart_port structure.
Signed-off-by: Govindraj.R <govindraj.raja@ti.com>
---
arch/arm/mach-omap2/serial.c | 2 ++
arch/arm/plat-omap/include/plat/omap-serial.h | 3 +++
drivers/tty/serial/omap-serial.c | 20 ++++++++++++++++++--
3 files changed, 23 insertions(+), 2 deletions(-)
diff --git a/arch/arm/mach-omap2/serial.c b/arch/arm/mach-omap2/serial.c
index 7dd75f1..f220c84 100644
--- a/arch/arm/mach-omap2/serial.c
+++ b/arch/arm/mach-omap2/serial.c
@@ -33,6 +33,7 @@
#include <plat/dma.h>
#include <plat/omap_hwmod.h>
#include <plat/omap_device.h>
+#include <plat/omap-pm.h>
#include "prm2xxx_3xxx.h"
#include "pm.h"
@@ -500,6 +501,7 @@ void __init omap_serial_init_port(struct omap_board_data *bdata)
omap_up.dma_enabled = uart->dma_enabled;
omap_up.uartclk = OMAP24XX_BASE_BAUD * 16;
omap_up.flags = UPF_BOOT_AUTOCONF;
+ omap_up.get_context_loss_count = omap_pm_get_dev_context_loss_count;
pdata = &omap_up;
pdata_size = sizeof(struct omap_uart_port_info);
diff --git a/arch/arm/plat-omap/include/plat/omap-serial.h b/arch/arm/plat-omap/include/plat/omap-serial.h
index 5b913c7..f265bb9 100644
--- a/arch/arm/plat-omap/include/plat/omap-serial.h
+++ b/arch/arm/plat-omap/include/plat/omap-serial.h
@@ -62,6 +62,8 @@ struct omap_uart_port_info {
bool dma_enabled; /* To specify DMA Mode */
unsigned int uartclk; /* UART clock rate */
upf_t flags; /* UPF_* flags */
+
+ u32 (*get_context_loss_count)(struct device *);
};
struct uart_omap_dma {
@@ -114,6 +116,7 @@ struct uart_omap_port {
unsigned char msr_saved_flags;
char name[20];
unsigned long port_activity;
+ u32 context_loss_cnt;
};
#endif /* __OMAP_SERIAL_H__ */
diff --git a/drivers/tty/serial/omap-serial.c b/drivers/tty/serial/omap-serial.c
index a7fdf94..289fa7b 100644
--- a/drivers/tty/serial/omap-serial.c
+++ b/drivers/tty/serial/omap-serial.c
@@ -1439,15 +1439,31 @@ static void serial_omap_restore_context(struct uart_omap_port *up)
#ifdef CONFIG_PM_RUNTIME
static int serial_omap_runtime_suspend(struct device *dev)
{
+ struct uart_omap_port *up = dev_get_drvdata(dev);
+ struct omap_uart_port_info *pdata = dev->platform_data;
+
+ if (!up)
+ return -EINVAL;
+
+ if (pdata->get_context_loss_count)
+ up->context_loss_cnt = pdata->get_context_loss_count(dev);
+
return 0;
}
static int serial_omap_runtime_resume(struct device *dev)
{
struct uart_omap_port *up = dev_get_drvdata(dev);
+ struct omap_uart_port_info *pdata = dev->platform_data;
- if (up)
- serial_omap_restore_context(up);
+ if (up) {
+ if (pdata->get_context_loss_count) {
+ u32 loss_cnt = pdata->get_context_loss_count(dev);
+
+ if (up->context_loss_cnt != loss_cnt)
+ serial_omap_restore_context(up);
+ }
+ }
return 0;
}
--
1.7.4.1
^ permalink raw reply related [flat|nested] 17+ messages in thread
* [PATCH v7 11/21] OMAP2+: UART: Move errata handling from serial.c to omap-serial
2011-10-18 15:25 [PATCH v7 00/21] OMAP2+: UART: Runtime adaptation + cleanup Govindraj.R
` (9 preceding siblings ...)
2011-10-18 15:26 ` [PATCH v7 10/21] OMAP2+: UART: Get context loss count to context restore Govindraj.R
@ 2011-10-18 15:26 ` Govindraj.R
2011-11-10 23:44 ` Jon Hunter
2011-10-18 15:26 ` [PATCH v7 12/21] OMAP2+: UART: Add wakeup mechanism for omap-uarts Govindraj.R
2011-10-18 15:26 ` [PATCH v7 13/21] OMAP2+: UART: Remove old and unused clocks handling funcs Govindraj.R
12 siblings, 1 reply; 17+ messages in thread
From: Govindraj.R @ 2011-10-18 15:26 UTC (permalink / raw)
To: linux-arm-kernel
Move the errata handling mechanism from serial.c to omap-serial file
and utilise the same func in driver file.
Errata i202, i291 are moved to be handled with omap-serial
Moving the errata macro from serial.c file to driver header file
as from on errata will be handled in driver file itself.
Corrected errata id from chapter reference 2.15 to errata id i291.
Removed errata and dma_enabled feilds from omap_uart_state struct
as they are no more needed with errata handling done within omap-serial.
Acked-by: Alan Cox <alan@linux.intel.com>
Signed-off-by: Govindraj.R <govindraj.raja@ti.com>
---
arch/arm/mach-omap2/serial.c | 97 +++++++------------------
arch/arm/plat-omap/include/plat/omap-serial.h | 6 ++
drivers/tty/serial/omap-serial.c | 66 ++++++++++++++++-
3 files changed, 95 insertions(+), 74 deletions(-)
diff --git a/arch/arm/mach-omap2/serial.c b/arch/arm/mach-omap2/serial.c
index f220c84..8c6dc85 100644
--- a/arch/arm/mach-omap2/serial.c
+++ b/arch/arm/mach-omap2/serial.c
@@ -42,8 +42,6 @@
#include "control.h"
#include "mux.h"
-#define UART_ERRATA_i202_MDR1_ACCESS (0x1 << 1)
-
/*
* NOTE: By default the serial timeout is disabled as it causes lost characters
* over the serial ports. This means that the UART clocks will stay on until
@@ -61,15 +59,12 @@ struct omap_uart_state {
void __iomem *wk_st;
void __iomem *wk_en;
u32 wk_mask;
- u32 dma_enabled;
int clocked;
struct list_head node;
struct omap_hwmod *oh;
struct platform_device *pdev;
-
- u32 errata;
};
static LIST_HEAD(uart_list);
@@ -97,45 +92,6 @@ static struct omap_device_pm_latency omap_uart_latency[] = {
},
};
-#if defined(CONFIG_PM) && defined(CONFIG_ARCH_OMAP3)
-
-/*
- * Work Around for Errata i202 (3430 - 1.12, 3630 - 1.6)
- * The access to uart register after MDR1 Access
- * causes UART to corrupt data.
- *
- * Need a delay =
- * 5 L4 clock cycles + 5 UART functional clock cycle (@48MHz = ~0.2uS)
- * give 10 times as much
- */
-static void omap_uart_mdr1_errataset(struct omap_uart_state *uart, u8 mdr1_val,
- u8 fcr_val)
-{
- u8 timeout = 255;
-
- serial_write_reg(uart, UART_OMAP_MDR1, mdr1_val);
- udelay(2);
- serial_write_reg(uart, UART_FCR, fcr_val | UART_FCR_CLEAR_XMIT |
- UART_FCR_CLEAR_RCVR);
- /*
- * Wait for FIFO to empty: when empty, RX_FIFO_E bit is 0 and
- * TX_FIFO_E bit is 1.
- */
- while (UART_LSR_THRE != (serial_read_reg(uart, UART_LSR) &
- (UART_LSR_THRE | UART_LSR_DR))) {
- timeout--;
- if (!timeout) {
- /* Should *never* happen. we warn and carry on */
- dev_crit(&uart->pdev->dev, "Errata i202: timedout %x\n",
- serial_read_reg(uart, UART_LSR));
- break;
- }
- udelay(1);
- }
-}
-
-#endif /* CONFIG_PM && CONFIG_ARCH_OMAP3 */
-
static inline void omap_uart_enable_clocks(struct omap_uart_state *uart)
{
if (uart->clocked)
@@ -178,27 +134,6 @@ static void omap_uart_disable_wakeup(struct omap_uart_state *uart)
}
}
-static void omap_uart_smart_idle_enable(struct omap_uart_state *uart,
- int enable)
-{
- u8 idlemode;
-
- if (enable) {
- /**
- * Errata 2.15: [UART]:Cannot Acknowledge Idle Requests
- * in Smartidle Mode When Configured for DMA Operations.
- */
- if (uart->dma_enabled)
- idlemode = HWMOD_IDLEMODE_FORCE;
- else
- idlemode = HWMOD_IDLEMODE_SMART;
- } else {
- idlemode = HWMOD_IDLEMODE_NO;
- }
-
- omap_hwmod_set_slave_idlemode(uart->oh, idlemode);
-}
-
static void omap_uart_block_sleep(struct omap_uart_state *uart)
{
omap_uart_enable_clocks(uart);
@@ -289,7 +224,28 @@ static void omap_uart_idle_init(struct omap_uart_state *uart)
}
}
+/*
+ * Errata i291: [UART]:Cannot Acknowledge Idle Requests
+ * in Smartidle Mode When Configured for DMA Operations.
+ * WA: configure uart in force idle mode.
+ */
+static void omap_uart_set_noidle(struct platform_device *pdev)
+{
+ struct omap_device *od = to_omap_device(pdev);
+
+ omap_hwmod_set_slave_idlemode(od->hwmods[0], HWMOD_IDLEMODE_NO);
+}
+
+static void omap_uart_set_forceidle(struct platform_device *pdev)
+{
+ struct omap_device *od = to_omap_device(pdev);
+
+ omap_hwmod_set_slave_idlemode(od->hwmods[0], HWMOD_IDLEMODE_FORCE);
+}
+
#else
+static void omap_uart_set_noidle(struct platform_device *pdev) {}
+static void omap_uart_set_forceidle(struct platform_device *pdev) {}
static void omap_uart_block_sleep(struct omap_uart_state *uart)
{
/* Needed to enable UART clocks when built without CONFIG_PM */
@@ -495,13 +451,18 @@ void __init omap_serial_init_port(struct omap_board_data *bdata)
break;
oh = uart->oh;
- uart->dma_enabled = 0;
name = DRIVER_NAME;
omap_up.dma_enabled = uart->dma_enabled;
omap_up.uartclk = OMAP24XX_BASE_BAUD * 16;
omap_up.flags = UPF_BOOT_AUTOCONF;
omap_up.get_context_loss_count = omap_pm_get_dev_context_loss_count;
+ omap_up.set_forceidle = omap_uart_set_forceidle;
+ omap_up.set_noidle = omap_uart_set_noidle;
+
+ /* Enable the MDR1 errata for OMAP3 */
+ if (cpu_is_omap34xx() && !cpu_is_ti816x())
+ omap_up.errata |= UART_ERRATA_i202_MDR1_ACCESS;
pdata = &omap_up;
pdata_size = sizeof(struct omap_uart_port_info);
@@ -542,10 +503,6 @@ void __init omap_serial_init_port(struct omap_board_data *bdata)
if (((cpu_is_omap34xx() || cpu_is_omap44xx()) && bdata->pads) ||
(pdata->wk_en && pdata->wk_mask))
device_init_wakeup(&pdev->dev, true);
-
- /* Enable the MDR1 errata for OMAP3 */
- if (cpu_is_omap34xx() && !cpu_is_ti816x())
- uart->errata |= UART_ERRATA_i202_MDR1_ACCESS;
}
/**
diff --git a/arch/arm/plat-omap/include/plat/omap-serial.h b/arch/arm/plat-omap/include/plat/omap-serial.h
index f265bb9..f9baf01 100644
--- a/arch/arm/plat-omap/include/plat/omap-serial.h
+++ b/arch/arm/plat-omap/include/plat/omap-serial.h
@@ -58,12 +58,17 @@
#define MSR_SAVE_FLAGS UART_MSR_ANY_DELTA
+#define UART_ERRATA_i202_MDR1_ACCESS (0x1 << 1)
+
struct omap_uart_port_info {
bool dma_enabled; /* To specify DMA Mode */
unsigned int uartclk; /* UART clock rate */
upf_t flags; /* UPF_* flags */
+ u32 errata;
u32 (*get_context_loss_count)(struct device *);
+ void (*set_forceidle)(struct platform_device *);
+ void (*set_noidle)(struct platform_device *);
};
struct uart_omap_dma {
@@ -117,6 +122,7 @@ struct uart_omap_port {
char name[20];
unsigned long port_activity;
u32 context_loss_cnt;
+ u32 errata;
};
#endif /* __OMAP_SERIAL_H__ */
diff --git a/drivers/tty/serial/omap-serial.c b/drivers/tty/serial/omap-serial.c
index 289fa7b..4d020fb 100644
--- a/drivers/tty/serial/omap-serial.c
+++ b/drivers/tty/serial/omap-serial.c
@@ -51,6 +51,7 @@ static struct uart_omap_port *ui[OMAP_MAX_HSUART_PORTS];
static void uart_tx_dma_callback(int lch, u16 ch_status, void *data);
static void serial_omap_rx_timeout(unsigned long uart_no);
static int serial_omap_start_rxdma(struct uart_omap_port *up);
+static void serial_omap_mdr1_errataset(struct uart_omap_port *up, u8 mdr1);
static inline unsigned int serial_in(struct uart_omap_port *up, int offset)
{
@@ -811,7 +812,11 @@ serial_omap_set_termios(struct uart_port *port, struct ktermios *termios,
/* Protocol, Baud Rate, and Interrupt Settings */
- serial_out(up, UART_OMAP_MDR1, up->mdr1);
+ if (up->errata & UART_ERRATA_i202_MDR1_ACCESS)
+ serial_omap_mdr1_errataset(up, up->mdr1);
+ else
+ serial_out(up, UART_OMAP_MDR1, up->mdr1);
+
serial_out(up, UART_LCR, UART_LCR_CONF_MODE_B);
up->efr = serial_in(up, UART_EFR);
@@ -836,7 +841,10 @@ serial_omap_set_termios(struct uart_port *port, struct ktermios *termios,
else
up->mdr1 = UART_OMAP_MDR1_16X_MODE;
- serial_out(up, UART_OMAP_MDR1, up->mdr1);
+ if (up->errata & UART_ERRATA_i202_MDR1_ACCESS)
+ serial_omap_mdr1_errataset(up, up->mdr1);
+ else
+ serial_out(up, UART_OMAP_MDR1, up->mdr1);
/* Hardware Flow Control Configuration */
@@ -1361,6 +1369,7 @@ static int serial_omap_probe(struct platform_device *pdev)
up->port.flags = omap_up_info->flags;
up->port.uartclk = omap_up_info->uartclk;
up->uart_dma.uart_base = mem->start;
+ up->errata = omap_up_info->errata;
if (omap_up_info->dma_enabled) {
up->uart_dma.uart_dma_tx = dma_tx->start;
@@ -1414,9 +1423,47 @@ static int serial_omap_remove(struct platform_device *dev)
return 0;
}
+/*
+ * Work Around for Errata i202 (3430 - 1.12, 3630 - 1.6)
+ * The access to uart register after MDR1 Access
+ * causes UART to corrupt data.
+ *
+ * Need a delay =
+ * 5 L4 clock cycles + 5 UART functional clock cycle (@48MHz = ~0.2uS)
+ * give 10 times as much
+ */
+static void serial_omap_mdr1_errataset(struct uart_omap_port *up, u8 mdr1)
+{
+ u8 timeout = 255;
+
+ serial_out(up, UART_OMAP_MDR1, mdr1);
+ udelay(2);
+ serial_out(up, UART_FCR, up->fcr | UART_FCR_CLEAR_XMIT |
+ UART_FCR_CLEAR_RCVR);
+ /*
+ * Wait for FIFO to empty: when empty, RX_FIFO_E bit is 0 and
+ * TX_FIFO_E bit is 1.
+ */
+ while (UART_LSR_THRE != (serial_in(up, UART_LSR) &
+ (UART_LSR_THRE | UART_LSR_DR))) {
+ timeout--;
+ if (!timeout) {
+ /* Should *never* happen. we warn and carry on */
+ dev_crit(&up->pdev->dev, "Errata i202: timedout %x\n",
+ serial_in(up, UART_LSR));
+ break;
+ }
+ udelay(1);
+ }
+}
+
static void serial_omap_restore_context(struct uart_omap_port *up)
{
- serial_out(up, UART_OMAP_MDR1, UART_OMAP_MDR1_DISABLE);
+ if (up->errata & UART_ERRATA_i202_MDR1_ACCESS)
+ serial_omap_mdr1_errataset(up, UART_OMAP_MDR1_DISABLE);
+ else
+ serial_out(up, UART_OMAP_MDR1, UART_OMAP_MDR1_DISABLE);
+
serial_out(up, UART_LCR, UART_LCR_CONF_MODE_B); /* Config B mode */
serial_out(up, UART_EFR, UART_EFR_ECB);
serial_out(up, UART_LCR, 0x0); /* Operational mode */
@@ -1433,7 +1480,10 @@ static void serial_omap_restore_context(struct uart_omap_port *up)
serial_out(up, UART_OMAP_SCR, up->scr);
serial_out(up, UART_EFR, up->efr);
serial_out(up, UART_LCR, up->lcr);
- serial_out(up, UART_OMAP_MDR1, up->mdr1);
+ if (up->errata & UART_ERRATA_i202_MDR1_ACCESS)
+ serial_omap_mdr1_errataset(up, up->mdr1);
+ else
+ serial_out(up, UART_OMAP_MDR1, up->mdr1);
}
#ifdef CONFIG_PM_RUNTIME
@@ -1448,6 +1498,10 @@ static int serial_omap_runtime_suspend(struct device *dev)
if (pdata->get_context_loss_count)
up->context_loss_cnt = pdata->get_context_loss_count(dev);
+ /* Errata i291 */
+ if (up->use_dma && pdata->set_forceidle)
+ pdata->set_forceidle(up->pdev);
+
return 0;
}
@@ -1463,6 +1517,10 @@ static int serial_omap_runtime_resume(struct device *dev)
if (up->context_loss_cnt != loss_cnt)
serial_omap_restore_context(up);
}
+
+ /* Errata i291 */
+ if (up->use_dma && pdata->set_noidle)
+ pdata->set_noidle(up->pdev);
}
return 0;
--
1.7.4.1
^ permalink raw reply related [flat|nested] 17+ messages in thread
* [PATCH v7 12/21] OMAP2+: UART: Add wakeup mechanism for omap-uarts
2011-10-18 15:25 [PATCH v7 00/21] OMAP2+: UART: Runtime adaptation + cleanup Govindraj.R
` (10 preceding siblings ...)
2011-10-18 15:26 ` [PATCH v7 11/21] OMAP2+: UART: Move errata handling from serial.c to omap-serial Govindraj.R
@ 2011-10-18 15:26 ` Govindraj.R
2011-10-18 15:26 ` [PATCH v7 13/21] OMAP2+: UART: Remove old and unused clocks handling funcs Govindraj.R
12 siblings, 0 replies; 17+ messages in thread
From: Govindraj.R @ 2011-10-18 15:26 UTC (permalink / raw)
To: linux-arm-kernel
^ permalink raw reply [flat|nested] 17+ messages in thread
* [PATCH v7 13/21] OMAP2+: UART: Remove old and unused clocks handling funcs
2011-10-18 15:25 [PATCH v7 00/21] OMAP2+: UART: Runtime adaptation + cleanup Govindraj.R
` (11 preceding siblings ...)
2011-10-18 15:26 ` [PATCH v7 12/21] OMAP2+: UART: Add wakeup mechanism for omap-uarts Govindraj.R
@ 2011-10-18 15:26 ` Govindraj.R
12 siblings, 0 replies; 17+ messages in thread
From: Govindraj.R @ 2011-10-18 15:26 UTC (permalink / raw)
To: linux-arm-kernel
With runtime adaptation done remove clock_enable/disbale API's
Signed-off-by: Govindraj.R <govindraj.raja@ti.com>
---
arch/arm/mach-omap2/serial.c | 36 ------------------------------------
1 files changed, 0 insertions(+), 36 deletions(-)
diff --git a/arch/arm/mach-omap2/serial.c b/arch/arm/mach-omap2/serial.c
index 6b3f0bd..66c8360 100644
--- a/arch/arm/mach-omap2/serial.c
+++ b/arch/arm/mach-omap2/serial.c
@@ -56,8 +56,6 @@ struct omap_uart_state {
int num;
int can_sleep;
- int clocked;
-
struct list_head node;
struct omap_hwmod *oh;
struct platform_device *pdev;
@@ -88,36 +86,8 @@ static struct omap_device_pm_latency omap_uart_latency[] = {
},
};
-static inline void omap_uart_enable_clocks(struct omap_uart_state *uart)
-{
- if (uart->clocked)
- return;
-
- omap_device_enable(uart->pdev);
- uart->clocked = 1;
- omap_uart_restore_context(uart);
-}
-
#ifdef CONFIG_PM
-static inline void omap_uart_disable_clocks(struct omap_uart_state *uart)
-{
- if (!uart->clocked)
- return;
-
- omap_uart_save_context(uart);
- uart->clocked = 0;
- omap_device_idle(uart->pdev);
-}
-
-static void omap_uart_block_sleep(struct omap_uart_state *uart)
-{
- omap_uart_enable_clocks(uart);
-
- omap_uart_smart_idle_enable(uart, 0);
- uart->can_sleep = 0;
-}
-
int omap_uart_can_sleep(void)
{
struct omap_uart_state *uart;
@@ -176,11 +146,6 @@ static void omap_uart_enable_wakeup(struct platform_device *pdev, bool enable)
{}
static void omap_uart_set_noidle(struct platform_device *pdev) {}
static void omap_uart_set_forceidle(struct platform_device *pdev) {}
-static void omap_uart_block_sleep(struct omap_uart_state *uart)
-{
- /* Needed to enable UART clocks when built without CONFIG_PM */
- omap_uart_enable_clocks(uart);
-}
#endif /* CONFIG_PM */
#ifdef CONFIG_OMAP_MUX
@@ -426,7 +391,6 @@ void __init omap_serial_init_port(struct omap_board_data *bdata)
omap_device_enable(uart->pdev);
omap_device_idle(uart->pdev);
- omap_uart_block_sleep(uart);
console_unlock();
if ((cpu_is_omap34xx() || cpu_is_omap44xx()) && bdata->pads)
--
1.7.4.1
^ permalink raw reply related [flat|nested] 17+ messages in thread
* [PATCH v7 11/21] OMAP2+: UART: Move errata handling from serial.c to omap-serial
2011-10-18 15:26 ` [PATCH v7 11/21] OMAP2+: UART: Move errata handling from serial.c to omap-serial Govindraj.R
@ 2011-11-10 23:44 ` Jon Hunter
2011-11-11 6:11 ` Shubhrajyoti
2011-11-11 10:14 ` Govindraj
0 siblings, 2 replies; 17+ messages in thread
From: Jon Hunter @ 2011-11-10 23:44 UTC (permalink / raw)
To: linux-arm-kernel
Hi Govindraj,
On 10/18/2011 10:26, Govindraj.R wrote:
> Move the errata handling mechanism from serial.c to omap-serial file
> and utilise the same func in driver file.
>
> Errata i202, i291 are moved to be handled with omap-serial
> Moving the errata macro from serial.c file to driver header file
> as from on errata will be handled in driver file itself.
> Corrected errata id from chapter reference 2.15 to errata id i291.
>
> Removed errata and dma_enabled feilds from omap_uart_state struct
> as they are no more needed with errata handling done within omap-serial.
>
> Acked-by: Alan Cox<alan@linux.intel.com>
> Signed-off-by: Govindraj.R<govindraj.raja@ti.com>
> ---
> arch/arm/mach-omap2/serial.c | 97 +++++++------------------
> arch/arm/plat-omap/include/plat/omap-serial.h | 6 ++
> drivers/tty/serial/omap-serial.c | 66 ++++++++++++++++-
> 3 files changed, 95 insertions(+), 74 deletions(-)
[snip]
> + /* Enable the MDR1 errata for OMAP3 */
> + if (cpu_is_omap34xx()&& !cpu_is_ti816x())
> + omap_up.errata |= UART_ERRATA_i202_MDR1_ACCESS;
This errata (i202) is applicable to all devices from OMAP2430 to
OMAP4460 (apparently this one is not getting fixed). So could you make
sure this is enabled for 2430, 3430, 3630, 4430 and 4460?
[snip]
> +/*
> + * Work Around for Errata i202 (3430 - 1.12, 3630 - 1.6)
We should update the comment to be "Work Around for Errata i202 (2430,
3430, 3630, 4430 and 4460)". The "1.12" and "1.6" are just the section
references in the errata docs, but I think that you can drop these as
you can just search for the errata ID which is i202.
Cheers
Jon
^ permalink raw reply [flat|nested] 17+ messages in thread
* [PATCH v7 11/21] OMAP2+: UART: Move errata handling from serial.c to omap-serial
2011-11-10 23:44 ` Jon Hunter
@ 2011-11-11 6:11 ` Shubhrajyoti
2011-11-11 10:14 ` Govindraj
1 sibling, 0 replies; 17+ messages in thread
From: Shubhrajyoti @ 2011-11-11 6:11 UTC (permalink / raw)
To: linux-arm-kernel
On Friday 11 November 2011 05:14 AM, Jon Hunter wrote:
> Hi Govindraj,
>
> On 10/18/2011 10:26, Govindraj.R wrote:
>> Move the errata handling mechanism from serial.c to omap-serial file
>> and utilise the same func in driver file.
>>
>> Errata i202, i291 are moved to be handled with omap-serial
>> Moving the errata macro from serial.c file to driver header file
>> as from on errata will be handled in driver file itself.
>> Corrected errata id from chapter reference 2.15 to errata id i291.
>>
>> Removed errata and dma_enabled feilds from omap_uart_state struct
Nitpick.
The field spelling could be corrected.
>> as they are no more needed with errata handling done within omap-serial.
>>
>> Acked-by: Alan Cox<alan@linux.intel.com>
>> Signed-off-by: Govindraj.R<govindraj.raja@ti.com>
>> ---
>> arch/arm/mach-omap2/serial.c | 97
>> +++++++------------------
>> arch/arm/plat-omap/include/plat/omap-serial.h | 6 ++
>> drivers/tty/serial/omap-serial.c | 66 ++++++++++++++++-
>> 3 files changed, 95 insertions(+), 74 deletions(-)
>
> [snip]
>
>> + /* Enable the MDR1 errata for OMAP3 */
>> + if (cpu_is_omap34xx()&& !cpu_is_ti816x())
>> + omap_up.errata |= UART_ERRATA_i202_MDR1_ACCESS;
>
> This errata (i202) is applicable to all devices from OMAP2430 to
> OMAP4460 (apparently this one is not getting fixed). So could you make
> sure this is enabled for 2430, 3430, 3630, 4430 and 4460?
>
Yes good point.
> [snip]
>
>> +/*
>> + * Work Around for Errata i202 (3430 - 1.12, 3630 - 1.6)
>
> We should update the comment to be "Work Around for Errata i202 (2430,
> 3430, 3630, 4430 and 4460)". The "1.12" and "1.6" are just the section
> references in the errata docs, but I think that you can drop these as
> you can just search for the errata ID which is i202.
>
> Cheers
> Jon
>
>
>
> --
> To unsubscribe from this list: send the line "unsubscribe linux-omap" in
> the body of a message to majordomo at vger.kernel.org
> More majordomo info at http://vger.kernel.org/majordomo-info.html
^ permalink raw reply [flat|nested] 17+ messages in thread
* [PATCH v7 11/21] OMAP2+: UART: Move errata handling from serial.c to omap-serial
2011-11-10 23:44 ` Jon Hunter
2011-11-11 6:11 ` Shubhrajyoti
@ 2011-11-11 10:14 ` Govindraj
1 sibling, 0 replies; 17+ messages in thread
From: Govindraj @ 2011-11-11 10:14 UTC (permalink / raw)
To: linux-arm-kernel
Hi Jon,
On Fri, Nov 11, 2011 at 5:14 AM, Jon Hunter <jon-hunter@ti.com> wrote:
> Hi Govindraj,
>
> On 10/18/2011 10:26, Govindraj.R wrote:
>>
>> Move the errata handling mechanism from serial.c to omap-serial file
>> and utilise the same func in driver file.
>>
>> Errata i202, i291 are moved to be handled with omap-serial
>> Moving the errata macro from serial.c file to driver header file
>> as from on errata will be handled in driver file itself.
>> Corrected errata id from chapter reference 2.15 to errata id i291.
>>
>> Removed errata and dma_enabled feilds from omap_uart_state struct
>> as they are no more needed with errata handling done within omap-serial.
>>
>> Acked-by: Alan Cox<alan@linux.intel.com>
>> Signed-off-by: Govindraj.R<govindraj.raja@ti.com>
>> ---
>> ?arch/arm/mach-omap2/serial.c ? ? ? ? ? ? ? ? ?| ? 97
>> +++++++------------------
>> ?arch/arm/plat-omap/include/plat/omap-serial.h | ? ?6 ++
>> ?drivers/tty/serial/omap-serial.c ? ? ? ? ? ? ?| ? 66 ++++++++++++++++-
>> ?3 files changed, 95 insertions(+), 74 deletions(-)
>
> [snip]
>
>> + ? ? ? /* Enable the MDR1 errata for OMAP3 */
>> + ? ? ? if (cpu_is_omap34xx()&& ?!cpu_is_ti816x())
>> + ? ? ? ? ? ? ? omap_up.errata |= UART_ERRATA_i202_MDR1_ACCESS;
>
> This errata (i202) is applicable to all devices from OMAP2430 to OMAP4460
> (apparently this one is not getting fixed). So could you make sure this is
> enabled for 2430, 3430, 3630, 4430 and 4460?
>
> [snip]
Thanks for the info, Have posted a updated the patch [1]
>
>> +/*
>> + * Work Around for Errata i202 (3430 - 1.12, 3630 - 1.6)
>
> We should update the comment to be "Work Around for Errata i202 (2430, 3430,
> 3630, 4430 and 4460)". The "1.12" and "1.6" are just the section references
> in the errata docs, but I think that you can drop these as you can just
> search for the errata ID which is i202.
>
yes corrected [1]
--
Thanks,
Govindraj.R
[1]:
http://www.spinics.net/lists/linux-serial/msg04841.html
^ permalink raw reply [flat|nested] 17+ messages in thread
end of thread, other threads:[~2011-11-11 10:14 UTC | newest]
Thread overview: 17+ messages (download: mbox.gz follow: Atom feed
-- links below jump to the message on this page --
2011-10-18 15:25 [PATCH v7 00/21] OMAP2+: UART: Runtime adaptation + cleanup Govindraj.R
2011-10-18 15:25 ` [PATCH v7 01/21] OMAP2+: UART: cleanup + remove uart pm specific API Govindraj.R
2011-10-18 15:25 ` [PATCH v7 02/21] OMAP2+: UART: cleanup 8250 console driver support Govindraj.R
2011-10-18 15:25 ` [PATCH v7 03/21] OMAP2+: UART: Cleanup part of clock gating mechanism for uart Govindraj.R
2011-10-18 15:25 ` [PATCH v7 04/21] OMAP2+: UART: Add default mux for all uarts Govindraj.R
2011-10-18 15:26 ` [PATCH v7 05/21] OMAP2+: UART: Remove mapbase/membase fields from pdata Govindraj.R
2011-10-18 15:26 ` [PATCH v7 06/21] OMAP2+: UART: Add runtime pm support for omap-serial driver Govindraj.R
2011-10-18 15:26 ` [PATCH v7 07/21] OMAP2+: UART: Remove context_save and move context restore to driver Govindraj.R
2011-10-18 15:26 ` [PATCH v7 08/21] OMAP2+: UART: Ensure all reg values configured are available from port structure Govindraj.R
2011-10-18 15:26 ` [PATCH v7 09/21] OMAP2+: UART: Remove uart reset function Govindraj.R
2011-10-18 15:26 ` [PATCH v7 10/21] OMAP2+: UART: Get context loss count to context restore Govindraj.R
2011-10-18 15:26 ` [PATCH v7 11/21] OMAP2+: UART: Move errata handling from serial.c to omap-serial Govindraj.R
2011-11-10 23:44 ` Jon Hunter
2011-11-11 6:11 ` Shubhrajyoti
2011-11-11 10:14 ` Govindraj
2011-10-18 15:26 ` [PATCH v7 12/21] OMAP2+: UART: Add wakeup mechanism for omap-uarts Govindraj.R
2011-10-18 15:26 ` [PATCH v7 13/21] OMAP2+: UART: Remove old and unused clocks handling funcs Govindraj.R
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).