diff options
225 files changed, 18848 insertions, 5068 deletions
diff --git a/Documentation/hwspinlock.txt b/Documentation/hwspinlock.txt new file mode 100644 index 00000000000..7dcd1a4e726 --- /dev/null +++ b/Documentation/hwspinlock.txt @@ -0,0 +1,293 @@ +Hardware Spinlock Framework + +1. Introduction + +Hardware spinlock modules provide hardware assistance for synchronization +and mutual exclusion between heterogeneous processors and those not operating +under a single, shared operating system. + +For example, OMAP4 has dual Cortex-A9, dual Cortex-M3 and a C64x+ DSP, +each of which is running a different Operating System (the master, A9, +is usually running Linux and the slave processors, the M3 and the DSP, +are running some flavor of RTOS). + +A generic hwspinlock framework allows platform-independent drivers to use +the hwspinlock device in order to access data structures that are shared +between remote processors, that otherwise have no alternative mechanism +to accomplish synchronization and mutual exclusion operations. + +This is necessary, for example, for Inter-processor communications: +on OMAP4, cpu-intensive multimedia tasks are offloaded by the host to the +remote M3 and/or C64x+ slave processors (by an IPC subsystem called Syslink). + +To achieve fast message-based communications, a minimal kernel support +is needed to deliver messages arriving from a remote processor to the +appropriate user process. + +This communication is based on simple data structures that is shared between +the remote processors, and access to it is synchronized using the hwspinlock +module (remote processor directly places new messages in this shared data +structure). + +A common hwspinlock interface makes it possible to have generic, platform- +independent, drivers. + +2. User API + + struct hwspinlock *hwspin_lock_request(void); + - dynamically assign an hwspinlock and return its address, or NULL + in case an unused hwspinlock isn't available. Users of this + API will usually want to communicate the lock's id to the remote core + before it can be used to achieve synchronization. + Can be called from an atomic context (this function will not sleep) but + not from within interrupt context. + + struct hwspinlock *hwspin_lock_request_specific(unsigned int id); + - assign a specific hwspinlock id and return its address, or NULL + if that hwspinlock is already in use. Usually board code will + be calling this function in order to reserve specific hwspinlock + ids for predefined purposes. + Can be called from an atomic context (this function will not sleep) but + not from within interrupt context. + + int hwspin_lock_free(struct hwspinlock *hwlock); + - free a previously-assigned hwspinlock; returns 0 on success, or an + appropriate error code on failure (e.g. -EINVAL if the hwspinlock + is already free). + Can be called from an atomic context (this function will not sleep) but + not from within interrupt context. + + int hwspin_lock_timeout(struct hwspinlock *hwlock, unsigned int timeout); + - lock a previously-assigned hwspinlock with a timeout limit (specified in + msecs). If the hwspinlock is already taken, the function will busy loop + waiting for it to be released, but give up when the timeout elapses. + Upon a successful return from this function, preemption is disabled so + the caller must not sleep, and is advised to release the hwspinlock as + soon as possible, in order to minimize remote cores polling on the + hardware interconnect. + Returns 0 when successful and an appropriate error code otherwise (most + notably -ETIMEDOUT if the hwspinlock is still busy after timeout msecs). + The function will never sleep. + + int hwspin_lock_timeout_irq(struct hwspinlock *hwlock, unsigned int timeout); + - lock a previously-assigned hwspinlock with a timeout limit (specified in + msecs). If the hwspinlock is already taken, the function will busy loop + waiting for it to be released, but give up when the timeout elapses. + Upon a successful return from this function, preemption and the local + interrupts are disabled, so the caller must not sleep, and is advised to + release the hwspinlock as soon as possible. + Returns 0 when successful and an appropriate error code otherwise (most + notably -ETIMEDOUT if the hwspinlock is still busy after timeout msecs). + The function will never sleep. + + int hwspin_lock_timeout_irqsave(struct hwspinlock *hwlock, unsigned int to, + unsigned long *flags); + - lock a previously-assigned hwspinlock with a timeout limit (specified in + msecs). If the hwspinlock is already taken, the function will busy loop + waiting for it to be released, but give up when the timeout elapses. + Upon a successful return from this function, preemption is disabled, + local interrupts are disabled and their previous state is saved at the + given flags placeholder. The caller must not sleep, and is advised to + release the hwspinlock as soon as possible. + Returns 0 when successful and an appropriate error code otherwise (most + notably -ETIMEDOUT if the hwspinlock is still busy after timeout msecs). + The function will never sleep. + + int hwspin_trylock(struct hwspinlock *hwlock); + - attempt to lock a previously-assigned hwspinlock, but immediately fail if + it is already taken. + Upon a successful return from this function, preemption is disabled so + caller must not sleep, and is advised to release the hwspinlock as soon as + possible, in order to minimize remote cores polling on the hardware + interconnect. + Returns 0 on success and an appropriate error code otherwise (most + notably -EBUSY if the hwspinlock was already taken). + The function will never sleep. + + int hwspin_trylock_irq(struct hwspinlock *hwlock); + - attempt to lock a previously-assigned hwspinlock, but immediately fail if + it is already taken. + Upon a successful return from this function, preemption and the local + interrupts are disabled so caller must not sleep, and is advised to + release the hwspinlock as soon as possible. + Returns 0 on success and an appropriate error code otherwise (most + notably -EBUSY if the hwspinlock was already taken). + The function will never sleep. + + int hwspin_trylock_irqsave(struct hwspinlock *hwlock, unsigned long *flags); + - attempt to lock a previously-assigned hwspinlock, but immediately fail if + it is already taken. + Upon a successful return from this function, preemption is disabled, + the local interrupts are disabled and their previous state is saved + at the given flags placeholder. The caller must not sleep, and is advised + to release the hwspinlock as soon as possible. + Returns 0 on success and an appropriate error code otherwise (most + notably -EBUSY if the hwspinlock was already taken). + The function will never sleep. + + void hwspin_unlock(struct hwspinlock *hwlock); + - unlock a previously-locked hwspinlock. Always succeed, and can be called + from any context (the function never sleeps). Note: code should _never_ + unlock an hwspinlock which is already unlocked (there is no protection + against this). + + void hwspin_unlock_irq(struct hwspinlock *hwlock); + - unlock a previously-locked hwspinlock and enable local interrupts. + The caller should _never_ unlock an hwspinlock which is already unlocked. + Doing so is considered a bug (there is no protection against this). + Upon a successful return from this function, preemption and local + interrupts are enabled. This function will never sleep. + + void + hwspin_unlock_irqrestore(struct hwspinlock *hwlock, unsigned long *flags); + - unlock a previously-locked hwspinlock. + The caller should _never_ unlock an hwspinlock which is already unlocked. + Doing so is considered a bug (there is no protection against this). + Upon a successful return from this function, preemption is reenabled, + and the state of the local interrupts is restored to the state saved at + the given flags. This function will never sleep. + + int hwspin_lock_get_id(struct hwspinlock *hwlock); + - retrieve id number of a given hwspinlock. This is needed when an + hwspinlock is dynamically assigned: before it can be used to achieve + mutual exclusion with a remote cpu, the id number should be communicated + to the remote task with which we want to synchronize. + Returns the hwspinlock id number, or -EINVAL if hwlock is null. + +3. Typical usage + +#include <linux/hwspinlock.h> +#include <linux/err.h> + +int hwspinlock_example1(void) +{ + struct hwspinlock *hwlock; + int ret; + + /* dynamically assign a hwspinlock */ + hwlock = hwspin_lock_request(); + if (!hwlock) + ... + + id = hwspin_lock_get_id(hwlock); + /* probably need to communicate id to a remote processor now */ + + /* take the lock, spin for 1 sec if it's already taken */ + ret = hwspin_lock_timeout(hwlock, 1000); + if (ret) + ... + + /* + * we took the lock, do our thing now, but do NOT sleep + */ + + /* release the lock */ + hwspin_unlock(hwlock); + + /* free the lock */ + ret = hwspin_lock_free(hwlock); + if (ret) + ... + + return ret; +} + +int hwspinlock_example2(void) +{ + struct hwspinlock *hwlock; + int ret; + + /* + * assign a specific hwspinlock id - this should be called early + * by board init code. + */ + hwlock = hwspin_lock_request_specific(PREDEFINED_LOCK_ID); + if (!hwlock) + ... + + /* try to take it, but don't spin on it */ + ret = hwspin_trylock(hwlock); + if (!ret) { + pr_info("lock is already taken\n"); + return -EBUSY; + } + + /* + * we took the lock, do our thing now, but do NOT sleep + */ + + /* release the lock */ + hwspin_unlock(hwlock); + + /* free the lock */ + ret = hwspin_lock_free(hwlock); + if (ret) + ... + + return ret; +} + + +4. API for implementors + + int hwspin_lock_register(struct hwspinlock *hwlock); + - to be called from the underlying platform-specific implementation, in + order to register a new hwspinlock instance. Can be called from an atomic + context (this function will not sleep) but not from within interrupt + context. Returns 0 on success, or appropriate error code on failure. + + struct hwspinlock *hwspin_lock_unregister(unsigned int id); + - to be called from the underlying vendor-specific implementation, in order + to unregister an existing (and unused) hwspinlock instance. + Can be called from an atomic context (will not sleep) but not from + within interrupt context. + Returns the address of hwspinlock on success, or NULL on error (e.g. + if the hwspinlock is sill in use). + +5. struct hwspinlock + +This struct represents an hwspinlock instance. It is registered by the +underlying hwspinlock implementation using the hwspin_lock_register() API. + +/** + * struct hwspinlock - vendor-specific hwspinlock implementation + * + * @dev: underlying device, will be used with runtime PM api + * @ops: vendor-specific hwspinlock handlers + * @id: a global, unique, system-wide, index of the lock. + * @lock: initialized and used by hwspinlock core + * @owner: underlying implementation module, used to maintain module ref count + */ +struct hwspinlock { + struct device *dev; + const struct hwspinlock_ops *ops; + int id; + spinlock_t lock; + struct module *owner; +}; + +The underlying implementation is responsible to assign the dev, ops, id and +owner members. The lock member, OTOH, is initialized and used by the hwspinlock +core. + +6. Implementation callbacks + +There are three possible callbacks defined in 'struct hwspinlock_ops': + +struct hwspinlock_ops { + int (*trylock)(struct hwspinlock *lock); + void (*unlock)(struct hwspinlock *lock); + void (*relax)(struct hwspinlock *lock); +}; + +The first two callbacks are mandatory: + +The ->trylock() callback should make a single attempt to take the lock, and +return 0 on failure and 1 on success. This callback may _not_ sleep. + +The ->unlock() callback releases the lock. It always succeed, and it, too, +may _not_ sleep. + +The ->relax() callback is optional. It is called by hwspinlock core while +spinning on a lock, and can be used by the underlying implementation to force +a delay between two successive invocations of ->trylock(). It may _not_ sleep. diff --git a/MAINTAINERS b/MAINTAINERS index 391d57eec00..6e696bd37cf 100644 --- a/MAINTAINERS +++ b/MAINTAINERS @@ -4510,11 +4510,21 @@ S: Maintained F: arch/arm/*omap*/*clock* OMAP POWER MANAGEMENT SUPPORT -M: Kevin Hilman <khilman@deeprootsystems.com> +M: Kevin Hilman <khilman@ti.com> L: linux-omap@vger.kernel.org S: Maintained F: arch/arm/*omap*/*pm* +OMAP POWERDOMAIN/CLOCKDOMAIN SOC ADAPTATION LAYER SUPPORT +M: Rajendra Nayak <rnayak@ti.com> +M: Paul Walmsley <paul@pwsan.com> +L: linux-omap@vger.kernel.org +S: Maintained +F: arch/arm/mach-omap2/powerdomain2xxx_3xxx.c +F: arch/arm/mach-omap2/powerdomain44xx.c +F: arch/arm/mach-omap2/clockdomain2xxx_3xxx.c +F: arch/arm/mach-omap2/clockdomain44xx.c + OMAP AUDIO SUPPORT M: Jarkko Nikula <jhnikula@gmail.com> L: alsa-devel@alsa-project.org (subscribers-only) diff --git a/arch/arm/configs/omap2plus_defconfig b/arch/arm/configs/omap2plus_defconfig index ae890caa17a..019fb7c67dc 100644 --- a/arch/arm/configs/omap2plus_defconfig +++ b/arch/arm/configs/omap2plus_defconfig @@ -58,6 +58,7 @@ CONFIG_ARM_ERRATA_411920=y CONFIG_NO_HZ=y CONFIG_HIGH_RES_TIMERS=y CONFIG_SMP=y +CONFIG_NR_CPUS=2 # CONFIG_LOCAL_TIMERS is not set CONFIG_AEABI=y CONFIG_LEDS=y diff --git a/arch/arm/mach-omap1/Makefile b/arch/arm/mach-omap1/Makefile index ba6009f2767..af98117043d 100644 --- a/arch/arm/mach-omap1/Makefile +++ b/arch/arm/mach-omap1/Makefile @@ -4,7 +4,7 @@ # Common support obj-y := io.o id.o sram.o time.o irq.o mux.o flash.o serial.o devices.o dma.o -obj-y += clock.o clock_data.o opp_data.o +obj-y += clock.o clock_data.o opp_data.o reset.o obj-$(CONFIG_OMAP_MCBSP) += mcbsp.o diff --git a/arch/arm/mach-omap1/board-ams-delta.c b/arch/arm/mach-omap1/board-ams-delta.c index 22cc8c8df6c..de88c9297b6 100644 --- a/arch/arm/mach-omap1/board-ams-delta.c +++ b/arch/arm/mach-omap1/board-ams-delta.c @@ -165,7 +165,7 @@ static struct map_desc ams_delta_io_desc[] __initdata = { } }; -static struct omap_lcd_config ams_delta_lcd_config __initdata = { +static struct omap_lcd_config ams_delta_lcd_config = { .ctrl_name = "internal", }; @@ -175,7 +175,7 @@ static struct omap_usb_config ams_delta_usb_config __initdata = { .pins[0] = 2, }; -static struct omap_board_config_kernel ams_delta_config[] = { +static struct omap_board_config_kernel ams_delta_config[] __initdata = { { OMAP_TAG_LCD, &ams_delta_lcd_config }, }; @@ -208,14 +208,14 @@ static const struct matrix_keymap_data ams_delta_keymap_data = { .keymap_size = ARRAY_SIZE(ams_delta_keymap), }; -static struct omap_kp_platform_data ams_delta_kp_data = { +static struct omap_kp_platform_data ams_delta_kp_data __initdata = { .rows = 8, .cols = 8, .keymap_data = &ams_delta_keymap_data, .delay = 9, }; -static struct platform_device ams_delta_kp_device = { +static struct platform_device ams_delta_kp_device __initdata = { .name = "omap-keypad", .id = -1, .dev = { @@ -225,12 +225,12 @@ static struct platform_device ams_delta_kp_device = { .resource = ams_delta_kp_resources, }; -static struct platform_device ams_delta_lcd_device = { +static struct platform_device ams_delta_lcd_device __initdata = { .name = "lcd_ams_delta", .id = -1, }; -static struct platform_device ams_delta_led_device = { +static struct platform_device ams_delta_led_device __initdata = { .name = "ams-delta-led", .id = -1 }; @@ -259,7 +259,7 @@ static int ams_delta_camera_power(struct device *dev, int power) #define ams_delta_camera_power NULL #endif -static struct soc_camera_link __initdata ams_delta_iclink = { +static struct soc_camera_link ams_delta_iclink = { .bus_id = 0, /* OMAP1 SoC camera bus */ .i2c_adapter_id = 1, .board_info = &ams_delta_camera_board_info[0], @@ -267,7 +267,7 @@ static struct soc_camera_link __initdata ams_delta_iclink = { .power = ams_delta_camera_power, }; -static struct platform_device ams_delta_camera_device = { +static struct platform_device ams_delta_camera_device __initdata = { .name = "soc-camera-pdrv", .id = 0, .dev = { diff --git a/arch/arm/mach-omap1/board-fsample.c b/arch/arm/mach-omap1/board-fsample.c index 0efb9dbae44..87f173d9355 100644 --- a/arch/arm/mach-omap1/board-fsample.c +++ b/arch/arm/mach-omap1/board-fsample.c @@ -287,11 +287,11 @@ static struct platform_device *devices[] __initdata = { &lcd_device, }; -static struct omap_lcd_config fsample_lcd_config __initdata = { +static struct omap_lcd_config fsample_lcd_config = { .ctrl_name = "internal", }; -static struct omap_board_config_kernel fsample_config[] = { +static struct omap_board_config_kernel fsample_config[] __initdata = { { OMAP_TAG_LCD, &fsample_lcd_config }, }; diff --git a/arch/arm/mach-omap1/board-h2.c b/arch/arm/mach-omap1/board-h2.c index 28b84aa9bdb..ba3bd09c475 100644 --- a/arch/arm/mach-omap1/board-h2.c +++ b/arch/arm/mach-omap1/board-h2.c @@ -202,7 +202,7 @@ static int h2_nand_dev_ready(struct mtd_info *mtd) static const char *h2_part_probes[] = { "cmdlinepart", NULL }; -struct platform_nand_data h2_nand_platdata = { +static struct platform_nand_data h2_nand_platdata = { .chip = { .nr_chips = 1, .chip_offset = 0, diff --git a/arch/arm/mach-omap1/board-h3.c b/arch/arm/mach-omap1/board-h3.c index dbc8b8d882b..ac48677672e 100644 --- a/arch/arm/mach-omap1/board-h3.c +++ b/arch/arm/mach-omap1/board-h3.c @@ -204,7 +204,7 @@ static int nand_dev_ready(struct mtd_info *mtd) static const char *part_probes[] = { "cmdlinepart", NULL }; -struct platform_nand_data nand_platdata = { +static struct platform_nand_data nand_platdata = { .chip = { .nr_chips = 1, .chip_offset = 0, diff --git a/arch/arm/mach-omap1/board-htcherald.c b/arch/arm/mach-omap1/board-htcherald.c index f2c5c585bc8..ba05a51f940 100644 --- a/arch/arm/mach-omap1/board-htcherald.c +++ b/arch/arm/mach-omap1/board-htcherald.c @@ -331,7 +331,7 @@ static struct resource htcpld_resources[] = { }, }; -struct htcpld_chip_platform_data htcpld_chips[] = { +static struct htcpld_chip_platform_data htcpld_chips[] = { [0] = { .addr = 0x03, .reset = 0x04, @@ -366,7 +366,7 @@ struct htcpld_chip_platform_data htcpld_chips[] = { }, }; -struct htcpld_core_platform_data htcpld_pfdata = { +static struct htcpld_core_platform_data htcpld_pfdata = { .int_reset_gpio_hi = HTCPLD_GPIO_INT_RESET_HI, .int_reset_gpio_lo = HTCPLD_GPIO_INT_RESET_LO, .i2c_adapter_id = 1, diff --git a/arch/arm/mach-omap1/board-innovator.c b/arch/arm/mach-omap1/board-innovator.c index a36e6742bf9..2d9b8cbd7a1 100644 --- a/arch/arm/mach-omap1/board-innovator.c +++ b/arch/arm/mach-omap1/board-innovator.c @@ -365,7 +365,7 @@ static struct omap_mmc_platform_data mmc1_data = { static struct omap_mmc_platform_data *mmc_data[OMAP16XX_NR_MMC]; -void __init innovator_mmc_init(void) +static void __init innovator_mmc_init(void) { mmc_data[0] = &mmc1_data; omap1_init_mmc(mmc_data, OMAP15XX_NR_MMC); diff --git a/arch/arm/mach-omap1/board-nokia770.c b/arch/arm/mach-omap1/board-nokia770.c index d21f09dc78f..cfd08492614 100644 --- a/arch/arm/mach-omap1/board-nokia770.c +++ b/arch/arm/mach-omap1/board-nokia770.c @@ -115,7 +115,7 @@ static struct mipid_platform_data nokia770_mipid_platform_data = { .shutdown = mipid_shutdown, }; -static void mipid_dev_init(void) +static void __init mipid_dev_init(void) { const struct omap_lcd_config *conf; @@ -126,7 +126,7 @@ static void mipid_dev_init(void) } } -static void ads7846_dev_init(void) +static void __init ads7846_dev_init(void) { if (gpio_request(ADS7846_PENDOWN_GPIO, "ADS7846 pendown") < 0) printk(KERN_ERR "can't get ads7846 pen down GPIO\n"); @@ -170,7 +170,7 @@ static struct hwa742_platform_data nokia770_hwa742_platform_data = { .te_connected = 1, }; -static void hwa742_dev_init(void) +static void __init hwa742_dev_init(void) { clk_add_alias("hwa_sys_ck", NULL, "bclk", NULL); omapfb_set_ctrl_platform_data(&nokia770_hwa742_platform_data); diff --git a/arch/arm/mach-omap1/board-palmte.c b/arch/arm/mach-omap1/board-palmte.c index fb51ce6123d..c9d38f47845 100644 --- a/arch/arm/mach-omap1/board-palmte.c +++ b/arch/arm/mach-omap1/board-palmte.c @@ -230,19 +230,6 @@ static struct spi_board_info palmte_spi_info[] __initdata = { }, }; -static void palmte_headphones_detect(void *data, int state) -{ - if (state) { - /* Headphones connected, disable speaker */ - gpio_set_value(PALMTE_SPEAKER_GPIO, 0); - printk(KERN_INFO "PM: speaker off\n"); - } else { - /* Headphones unplugged, re-enable speaker */ - gpio_set_value(PALMTE_SPEAKER_GPIO, 1); - printk(KERN_INFO "PM: speaker on\n"); - } -} - static void __init palmte_misc_gpio_setup(void) { /* Set TSC2102 PINTDAV pin as input (used by TSC2102 driver) */ diff --git a/arch/arm/mach-omap1/board-voiceblue.c b/arch/arm/mach-omap1/board-voiceblue.c index 815a69ce821..bdc0ac8dc21 100644 --- a/arch/arm/mach-omap1/board-voiceblue.c +++ b/arch/arm/mach-omap1/board-voiceblue.c @@ -26,10 +26,12 @@ #include <linux/smc91x.h> #include <mach/hardware.h> +#include <mach/system.h> #include <asm/mach-types.h> #include <asm/mach/arch.h> #include <asm/mach/map.h> +#include <plat/board-voiceblue.h> #include <plat/common.h> #include <mach/gpio.h> #include <plat/flash.h> @@ -163,52 +165,6 @@ static void __init voiceblue_init_irq(void) omap_init_irq(); } -static void __init voiceblue_init(void) -{ - /* mux pins for uarts */ - omap_cfg_reg(UART1_TX); - omap_cfg_reg(UART1_RTS); - omap_cfg_reg(UART2_TX); - omap_cfg_reg(UART2_RTS); - omap_cfg_reg(UART3_TX); - omap_cfg_reg(UART3_RX); - - /* Watchdog */ - gpio_request(0, "Watchdog"); - /* smc91x reset */ - gpio_request(7, "SMC91x reset"); - gpio_direction_output(7, 1); - udelay(2); /* wait at least 100ns */ - gpio_set_value(7, 0); - mdelay(50); /* 50ms until PHY ready */ - /* smc91x interrupt pin */ - gpio_request(8, "SMC91x irq"); - /* 16C554 reset*/ - gpio_request(6, "16C554 reset"); - gpio_direction_output(6, 0); - /* 16C554 interrupt pins */ - gpio_request(12, "16C554 irq"); - gpio_request(13, "16C554 irq"); - gpio_request(14, "16C554 irq"); - gpio_request(15, "16C554 irq"); - set_irq_type(gpio_to_irq(12), IRQ_TYPE_EDGE_RISING); - set_irq_type(gpio_to_irq(13), IRQ_TYPE_EDGE_RISING); - set_irq_type(gpio_to_irq(14), IRQ_TYPE_EDGE_RISING); - set_irq_type(gpio_to_irq(15), IRQ_TYPE_EDGE_RISING); - - platform_add_devices(voiceblue_devices, ARRAY_SIZE(voiceblue_devices)); - omap_board_config = voiceblue_config; - omap_board_config_size = ARRAY_SIZE(voiceblue_config); - omap_serial_init(); - omap1_usb_init(&voiceblue_usb_config); - omap_register_i2c_bus(1, 100, NULL, 0); - - /* There is a good chance board is going up, so enable power LED - * (it is connected through invertor) */ - omap_writeb(0x00, OMAP_LPG1_LCR); - omap_writeb(0x00, OMAP_LPG1_PMR); /* Disable clock */ -} - static void __init voiceblue_map_io(void) { omap1_map_common_io(); @@ -275,8 +231,17 @@ void voiceblue_wdt_ping(void) gpio_set_value(0, wdt_gpio_state); } -void voiceblue_reset(void) +static void voiceblue_reset(char mode, const char *cmd) { + /* + * Workaround for 5912/1611b bug mentioned in sprz209d.pdf p. 28 + * "Global Software Reset Affects Traffic Controller Frequency". + */ + if (cpu_is_omap5912()) { + omap_writew(omap_readw(DPLL_CTL) & ~(1 << 4), DPLL_CTL); + omap_writew(0x8, ARM_RSTCT1); + } + set_bit(MACHINE_REBOOT, &machine_state); voiceblue_wdt_enable(); while (1) ; @@ -286,6 +251,54 @@ EXPORT_SYMBOL(voiceblue_wdt_enable); EXPORT_SYMBOL(voiceblue_wdt_disable); EXPORT_SYMBOL(voiceblue_wdt_ping); +static void __init voiceblue_init(void) +{ + /* mux pins for uarts */ + omap_cfg_reg(UART1_TX); + omap_cfg_reg(UART1_RTS); + omap_cfg_reg(UART2_TX); + omap_cfg_reg(UART2_RTS); + omap_cfg_reg(UART3_TX); + omap_cfg_reg(UART3_RX); + + /* Watchdog */ + gpio_request(0, "Watchdog"); + /* smc91x reset */ + gpio_request(7, "SMC91x reset"); + gpio_direction_output(7, 1); + udelay(2); /* wait at least 100ns */ + gpio_set_value(7, 0); + mdelay(50); /* 50ms until PHY ready */ + /* smc91x interrupt pin */ + gpio_request(8, "SMC91x irq"); + /* 16C554 reset*/ + gpio_request(6, "16C554 reset"); + gpio_direction_output(6, 0); + /* 16C554 interrupt pins */ + gpio_request(12, "16C554 irq"); + gpio_request(13, "16C554 irq"); + gpio_request(14, "16C554 irq"); + gpio_request(15, "16C554 irq"); + set_irq_type(gpio_to_irq(12), IRQ_TYPE_EDGE_RISING); + set_irq_type(gpio_to_irq(13), IRQ_TYPE_EDGE_RISING); + set_irq_type(gpio_to_irq(14), IRQ_TYPE_EDGE_RISING); + set_irq_type(gpio_to_irq(15), IRQ_TYPE_EDGE_RISING); + + platform_add_devices(voiceblue_devices, ARRAY_SIZE(voiceblue_devices)); + omap_board_config = voiceblue_config; + omap_board_config_size = ARRAY_SIZE(voiceblue_config); + omap_serial_init(); + omap1_usb_init(&voiceblue_usb_config); + omap_register_i2c_bus(1, 100, NULL, 0); + + /* There is a good chance board is going up, so enable power LED + * (it is connected through invertor) */ + omap_writeb(0x00, OMAP_LPG1_LCR); + omap_writeb(0x00, OMAP_LPG1_PMR); /* Disable clock */ + + arch_reset = voiceblue_reset; +} + MACHINE_START(VOICEBLUE, "VoiceBlue OMAP5910") /* Maintainer: Ladislav Michl <michl@2n.cz> */ .boot_params = 0x10000100, diff --git a/arch/arm/mach-omap1/mcbsp.c b/arch/arm/mach-omap1/mcbsp.c index 820973666f3..d9af9811ded 100644 --- a/arch/arm/mach-omap1/mcbsp.c +++ b/arch/arm/mach-omap1/mcbsp.c @@ -10,6 +10,7 @@ * * Multichannel mode not supported. */ +#include <linux/ioport.h> #include <linux/module.h> #include <linux/init.h> #include <linux/clk.h> @@ -78,100 +79,294 @@ static struct omap_mcbsp_ops omap1_mcbsp_ops = { }; #if defined(CONFIG_ARCH_OMAP730) || defined(CONFIG_ARCH_OMAP850) +struct resource omap7xx_mcbsp_res[][6] = { + { + { + .start = OMAP7XX_MCBSP1_BASE, + .end = OMAP7XX_MCBSP1_BASE + SZ_256, + .flags = IORESOURCE_MEM, + }, + { + .name = "rx", + .start = INT_7XX_McBSP1RX, + .flags = IORESOURCE_IRQ, + }, + { + .name = "tx", + .start = INT_7XX_McBSP1TX, + .flags = IORESOURCE_IRQ, + }, + { + .name = "rx", + .start = OMAP_DMA_MCBSP1_RX, + .flags = IORESOURCE_DMA, + }, + { + .name = "tx", + .start = OMAP_DMA_MCBSP1_TX, + .flags = IORESOURCE_DMA, + }, + }, + { + { + .start = OMAP7XX_MCBSP2_BASE, + .end = OMAP7XX_MCBSP2_BASE + SZ_256, + .flags = IORESOURCE_MEM, + }, + { + .name = "rx", + .start = INT_7XX_McBSP2RX, + .flags = IORESOURCE_IRQ, + }, + { + .name = "tx", + .start = INT_7XX_McBSP2TX, + .flags = IORESOURCE_IRQ, + }, + { + .name = "rx", + .start = OMAP_DMA_MCBSP3_RX, + .flags = IORESOURCE_DMA, + }, + { + .name = "tx", + .start = OMAP_DMA_MCBSP3_TX, + .flags = IORESOURCE_DMA, + }, + }, +}; + +#define omap7xx_mcbsp_res_0 omap7xx_mcbsp_res[0] + static struct omap_mcbsp_platform_data omap7xx_mcbsp_pdata[] = { { - .phys_base = OMAP7XX_MCBSP1_BASE, - .dma_rx_sync = OMAP_DMA_MCBSP1_RX, - .dma_tx_sync = OMAP_DMA_MCBSP1_TX, - .rx_irq = INT_7XX_McBSP1RX, - .tx_irq = INT_7XX_McBSP1TX, .ops = &omap1_mcbsp_ops, }, { - .phys_base = OMAP7XX_MCBSP2_BASE, - .dma_rx_sync = OMAP_DMA_MCBSP3_RX, - .dma_tx_sync = OMAP_DMA_MCBSP3_TX, - .rx_irq = INT_7XX_McBSP2RX, - .tx_irq = INT_7XX_McBSP2TX, .ops = &omap1_mcbsp_ops, }, }; -#define OMAP7XX_MCBSP_PDATA_SZ ARRAY_SIZE(omap7xx_mcbsp_pdata) -#define OMAP7XX_MCBSP_REG_NUM (OMAP_MCBSP_REG_XCERH / sizeof(u16) + 1) +#define OMAP7XX_MCBSP_RES_SZ ARRAY_SIZE(omap7xx_mcbsp_res[1]) +#define OMAP7XX_MCBSP_COUNT ARRAY_SIZE(omap7xx_mcbsp_res) #else +#define omap7xx_mcbsp_res_0 NULL #define omap7xx_mcbsp_pdata NULL -#define OMAP7XX_MCBSP_PDATA_SZ 0 -#define OMAP7XX_MCBSP_REG_NUM 0 +#define OMAP7XX_MCBSP_RES_SZ 0 +#define OMAP7XX_MCBSP_COUNT 0 #endif #ifdef CONFIG_ARCH_OMAP15XX +struct resource omap15xx_mcbsp_res[][6] = { + { + { + .start = OMAP1510_MCBSP1_BASE, + .end = OMAP1510_MCBSP1_BASE + SZ_256, + .flags = IORESOURCE_MEM, + }, + { + .name = "rx", + .start = INT_McBSP1RX, + .flags = IORESOURCE_IRQ, + }, + { + .name = "tx", + .start = INT_McBSP1TX, + .flags = IORESOURCE_IRQ, + }, + { + .name = "rx", + .start = OMAP_DMA_MCBSP1_RX, + .flags = IORESOURCE_DMA, + }, + { + .name = "tx", + .start = OMAP_DMA_MCBSP1_TX, + .flags = IORESOURCE_DMA, + }, + }, + { + { + .start = OMAP1510_MCBSP2_BASE, + .end = OMAP1510_MCBSP2_BASE + SZ_256, + .flags = IORESOURCE_MEM, + }, + { + .name = "rx", + .start = INT_1510_SPI_RX, + .flags = IORESOURCE_IRQ, + }, + { + .name = "tx", + .start = INT_1510_SPI_TX, + .flags = IORESOURCE_IRQ, + }, + { + .name = "rx", + .start = OMAP_DMA_MCBSP2_RX, + .flags = IORESOURCE_DMA, + }, + { + .name = "tx", + .start = OMAP_DMA_MCBSP2_TX, + .flags = IORESOURCE_DMA, + }, + }, + { + { + .start = OMAP1510_MCBSP3_BASE, + .end = OMAP1510_MCBSP3_BASE + SZ_256, + .flags = IORESOURCE_MEM, + }, + { + .name = "rx", + .start = INT_McBSP3RX, + .flags = IORESOURCE_IRQ, + }, + { + .name = "tx", + .start = INT_McBSP3TX, + .flags = IORESOURCE_IRQ, + }, + { + .name = "rx", + .start = OMAP_DMA_MCBSP3_RX, + .flags = IORESOURCE_DMA, + }, + { + .name = "tx", + .start = OMAP_DMA_MCBSP3_TX, + .flags = IORESOURCE_DMA, + }, + }, +}; + +#define omap15xx_mcbsp_res_0 omap15xx_mcbsp_res[0] + static struct omap_mcbsp_platform_data omap15xx_mcbsp_pdata[] = { { - .phys_base = OMAP1510_MCBSP1_BASE, - .dma_rx_sync = OMAP_DMA_MCBSP1_RX, - .dma_tx_sync = OMAP_DMA_MCBSP1_TX, - .rx_irq = INT_McBSP1RX, - .tx_irq = INT_McBSP1TX, .ops = &omap1_mcbsp_ops, }, { - .phys_base = OMAP1510_MCBSP2_BASE, - .dma_rx_sync = OMAP_DMA_MCBSP2_RX, - .dma_tx_sync = OMAP_DMA_MCBSP2_TX, - .rx_irq = INT_1510_SPI_RX, - .tx_irq = INT_1510_SPI_TX, .ops = &omap1_mcbsp_ops, }, { - .phys_base = OMAP1510_MCBSP3_BASE, - .dma_rx_sync = OMAP_DMA_MCBSP3_RX, - .dma_tx_sync = OMAP_DMA_MCBSP3_TX, - .rx_irq = INT_McBSP3RX, - .tx_irq = INT_McBSP3TX, .ops = &omap1_mcbsp_ops, }, }; -#define OMAP15XX_MCBSP_PDATA_SZ ARRAY_SIZE(omap15xx_mcbsp_pdata) -#define OMAP15XX_MCBSP_REG_NUM (OMAP_MCBSP_REG_XCERH / sizeof(u16) + 1) +#define OMAP15XX_MCBSP_RES_SZ ARRAY_SIZE(omap15xx_mcbsp_res[1]) +#define OMAP15XX_MCBSP_COUNT ARRAY_SIZE(omap15xx_mcbsp_res) #else +#define omap15xx_mcbsp_res_0 NULL #define omap15xx_mcbsp_pdata NULL -#define OMAP15XX_MCBSP_PDATA_SZ 0 -#define OMAP15XX_MCBSP_REG_NUM 0 +#define OMAP15XX_MCBSP_RES_SZ 0 +#define OMAP15XX_MCBSP_COUNT 0 #endif #ifdef CONFIG_ARCH_OMAP16XX +struct resource omap16xx_mcbsp_res[][6] = { + { + { + .start = OMAP1610_MCBSP1_BASE, + .end = OMAP1610_MCBSP1_BASE + SZ_256, + .flags = IORESOURCE_MEM, + }, + { + .name = "rx", + .start = INT_McBSP1RX, + .flags = IORESOURCE_IRQ, + }, + { + .name = "tx", + .start = INT_McBSP1TX, + .flags = IORESOURCE_IRQ, + }, + { + .name = "rx", + .start = OMAP_DMA_MCBSP1_RX, + .flags = IORESOURCE_DMA, + }, + { + .name = "tx", + .start = OMAP_DMA_MCBSP1_TX, + .flags = IORESOURCE_DMA, + }, + }, + { + { + .start = OMAP1610_MCBSP2_BASE, + .end = OMAP1610_MCBSP2_BASE + SZ_256, + .flags = IORESOURCE_MEM, + }, + { + .name = "rx", + .start = INT_1610_McBSP2_RX, + .flags = IORESOURCE_IRQ, + }, + { + .name = "tx", + .start = INT_1610_McBSP2_TX, + .flags = IORESOURCE_IRQ, + }, + { + .name = "rx", + .start = OMAP_DMA_MCBSP2_RX, + .flags = IORESOURCE_DMA, + }, + { + .name = "tx", + .start = OMAP_DMA_MCBSP2_TX, + .flags = IORESOURCE_DMA, + }, + }, + { + { + .start = OMAP1610_MCBSP3_BASE, + .end = OMAP1610_MCBSP3_BASE + SZ_256, + .flags = IORESOURCE_MEM, + }, + { + .name = "rx", + .start = INT_McBSP3RX, + .flags = IORESOURCE_IRQ, + }, + { + .name = "tx", + .start = INT_McBSP3TX, + .flags = IORESOURCE_IRQ, + }, + { + .name = "rx", + .start = OMAP_DMA_MCBSP3_RX, + .flags = IORESOURCE_DMA, + }, + { + .name = "tx", + .start = OMAP_DMA_MCBSP3_TX, + .flags = IORESOURCE_DMA, + }, + }, +}; + +#define omap16xx_mcbsp_res_0 omap16xx_mcbsp_res[0] + static struct omap_mcbsp_platform_data omap16xx_mcbsp_pdata[] = { { - .phys_base = OMAP1610_MCBSP1_BASE, - .dma_rx_sync = OMAP_DMA_MCBSP1_RX, - .dma_tx_sync = OMAP_DMA_MCBSP1_TX, - .rx_irq = INT_McBSP1RX, - .tx_irq = INT_McBSP1TX, .ops = &omap1_mcbsp_ops, }, { - .phys_base = OMAP1610_MCBSP2_BASE, - .dma_rx_sync = OMAP_DMA_MCBSP2_RX, - .dma_tx_sync = OMAP_DMA_MCBSP2_TX, - .rx_irq = INT_1610_McBSP2_RX, - .tx_irq = INT_1610_McBSP2_TX, .ops = &omap1_mcbsp_ops, }, { - .phys_base = OMAP1610_MCBSP3_BASE, - .dma_rx_sync = OMAP_DMA_MCBSP3_RX, - .dma_tx_sync = OMAP_DMA_MCBSP3_TX, - .rx_irq = INT_McBSP3RX, - .tx_irq = INT_McBSP3TX, .ops = &omap1_mcbsp_ops, }, }; -#define OMAP16XX_MCBSP_PDATA_SZ ARRAY_SIZE(omap16xx_mcbsp_pdata) -#define OMAP16XX_MCBSP_REG_NUM (OMAP_MCBSP_REG_XCERH / sizeof(u16) + 1) +#define OMAP16XX_MCBSP_RES_SZ ARRAY_SIZE(omap16xx_mcbsp_res[1]) +#define OMAP16XX_MCBSP_COUNT ARRAY_SIZE(omap16xx_mcbsp_res) #else +#define omap16xx_mcbsp_res_0 NULL #define omap16xx_mcbsp_pdata NULL -#define OMAP16XX_MCBSP_PDATA_SZ 0 -#define OMAP16XX_MCBSP_REG_NUM 0 +#define OMAP16XX_MCBSP_RES_SZ 0 +#define OMAP16XX_MCBSP_COUNT 0 #endif static int __init omap1_mcbsp_init(void) @@ -179,16 +374,12 @@ static int __init omap1_mcbsp_init(void) if (!cpu_class_is_omap1()) return -ENODEV; - if (cpu_is_omap7xx()) { - omap_mcbsp_count = OMAP7XX_MCBSP_PDATA_SZ; - omap_mcbsp_cache_size = OMAP7XX_MCBSP_REG_NUM * sizeof(u16); - } else if (cpu_is_omap15xx()) { - omap_mcbsp_count = OMAP15XX_MCBSP_PDATA_SZ; - omap_mcbsp_cache_size = OMAP15XX_MCBSP_REG_NUM * sizeof(u16); - } else if (cpu_is_omap16xx()) { - omap_mcbsp_count = OMAP16XX_MCBSP_PDATA_SZ; - omap_mcbsp_cache_size = OMAP16XX_MCBSP_REG_NUM * sizeof(u16); - } + if (cpu_is_omap7xx()) + omap_mcbsp_count = OMAP7XX_MCBSP_COUNT; + else if (cpu_is_omap15xx()) + omap_mcbsp_count = OMAP15XX_MCBSP_COUNT; + else if (cpu_is_omap16xx()) + omap_mcbsp_count = OMAP16XX_MCBSP_COUNT; mcbsp_ptr = kzalloc(omap_mcbsp_count * sizeof(struct omap_mcbsp *), GFP_KERNEL); @@ -196,16 +387,22 @@ static int __init omap1_mcbsp_init(void) return -ENOMEM; if (cpu_is_omap7xx()) - omap_mcbsp_register_board_cfg(omap7xx_mcbsp_pdata, - OMAP7XX_MCBSP_PDATA_SZ); + omap_mcbsp_register_board_cfg(omap7xx_mcbsp_res_0, + OMAP7XX_MCBSP_RES_SZ, + omap7xx_mcbsp_pdata, + OMAP7XX_MCBSP_COUNT); if (cpu_is_omap15xx()) - omap_mcbsp_register_board_cfg(omap15xx_mcbsp_pdata, - OMAP15XX_MCBSP_PDATA_SZ); + omap_mcbsp_register_board_cfg(omap15xx_mcbsp_res_0, + OMAP15XX_MCBSP_RES_SZ, + omap15xx_mcbsp_pdata, + OMAP15XX_MCBSP_COUNT); if (cpu_is_omap16xx()) - omap_mcbsp_register_board_cfg(omap16xx_mcbsp_pdata, - OMAP16XX_MCBSP_PDATA_SZ); + omap_mcbsp_register_board_cfg(omap16xx_mcbsp_res_0, + OMAP16XX_MCBSP_RES_SZ, + omap16xx_mcbsp_pdata, + OMAP16XX_MCBSP_COUNT); return omap_mcbsp_init(); } diff --git a/arch/arm/mach-omap1/reset.c b/arch/arm/mach-omap1/reset.c new file mode 100644 index 00000000000..ad951ee6920 --- /dev/null +++ b/arch/arm/mach-omap1/reset.c @@ -0,0 +1,25 @@ +/* + * OMAP1 reset support + */ +#include <linux/kernel.h> +#include <linux/io.h> + +#include <mach/hardware.h> +#include <mach/system.h> +#include <plat/prcm.h> + +void omap1_arch_reset(char mode, const char *cmd) +{ + /* + * Workaround for 5912/1611b bug mentioned in sprz209d.pdf p. 28 + * "Global Software Reset Affects Traffic Controller Frequency". + */ + if (cpu_is_omap5912()) { + omap_writew(omap_readw(DPLL_CTL) & ~(1 << 4), DPLL_CTL); + omap_writew(0x8, ARM_RSTCT1); + } + + omap_writew(1, ARM_RSTCT1); +} + +void (*arch_reset)(char, const char *) = omap1_arch_reset; diff --git a/arch/arm/mach-omap2/Kconfig b/arch/arm/mach-omap2/Kconfig index b69fa0a0299..eeab35dea07 100644 --- a/arch/arm/mach-omap2/Kconfig +++ b/arch/arm/mach-omap2/Kconfig @@ -54,25 +54,30 @@ config ARCH_OMAP4 comment "OMAP Core Type" depends on ARCH_OMAP2 -config ARCH_OMAP2420 +config SOC_OMAP2420 bool "OMAP2420 support" depends on ARCH_OMAP2 default y select OMAP_DM_TIMER select ARCH_OMAP_OTG -config ARCH_OMAP2430 +config SOC_OMAP2430 bool "OMAP2430 support" depends on ARCH_OMAP2 default y select ARCH_OMAP_OTG -config ARCH_OMAP3430 +config SOC_OMAP3430 bool "OMAP3430 support" depends on ARCH_OMAP3 default y select ARCH_OMAP_OTG +config SOC_OMAPTI816X + bool "TI816X support" + depends on ARCH_OMAP3 + default y + config OMAP_PACKAGE_ZAF bool @@ -107,25 +112,25 @@ config MACH_OMAP_GENERIC config MACH_OMAP2_TUSB6010 bool - depends on ARCH_OMAP2 && ARCH_OMAP2420 + depends on ARCH_OMAP2 && SOC_OMAP2420 default y if MACH_NOKIA_N8X0 config MACH_OMAP_H4 bool "OMAP 2420 H4 board" - depends on ARCH_OMAP2420 + depends on SOC_OMAP2420 default y select OMAP_PACKAGE_ZAF select OMAP_DEBUG_DEVICES config MACH_OMAP_APOLLON bool "OMAP 2420 Apollon board" - depends on ARCH_OMAP2420 + depends on SOC_OMAP2420 default y select OMAP_PACKAGE_ZAC config MACH_OMAP_2430SDP bool "OMAP 2430 SDP board" - depends on ARCH_OMAP2430 + depends on SOC_OMAP2430 default y select OMAP_PACKAGE_ZAC @@ -220,7 +225,7 @@ config MACH_NOKIA_N810_WIMAX config MACH_NOKIA_N8X0 bool "Nokia N800/N810" - depends on ARCH_OMAP2420 + depends on SOC_OMAP2420 default y select OMAP_PACKAGE_ZAC select MACH_NOKIA_N800 @@ -295,12 +300,18 @@ config MACH_OMAP_3630SDP default y select OMAP_PACKAGE_CBP +config MACH_TI8168EVM + bool "TI8168 Evaluation Module" + depends on SOC_OMAPTI816X + default y + config MACH_OMAP_4430SDP bool "OMAP 4430 SDP board" default y depends on ARCH_OMAP4 select OMAP_PACKAGE_CBL select OMAP_PACKAGE_CBS + select REGULATOR_FIXED_VOLTAGE config MACH_OMAP4_PANDA bool "OMAP4 Panda Board" @@ -308,6 +319,7 @@ config MACH_OMAP4_PANDA depends on ARCH_OMAP4 select OMAP_PACKAGE_CBL select OMAP_PACKAGE_CBS + select REGULATOR_FIXED_VOLTAGE config OMAP3_EMU bool "OMAP3 debugging peripherals" diff --git a/arch/arm/mach-omap2/Makefile b/arch/arm/mach-omap2/Makefile index 64dc4176407..a45cd640968 100644 --- a/arch/arm/mach-omap2/Makefile +++ b/arch/arm/mach-omap2/Makefile @@ -31,8 +31,8 @@ AFLAGS_omap-headsmp.o :=-Wa,-march=armv7-a$(plus_sec) AFLAGS_omap44xx-smc.o :=-Wa,-march=armv7-a$(plus_sec) # Functions loaded to SRAM -obj-$(CONFIG_ARCH_OMAP2420) += sram242x.o -obj-$(CONFIG_ARCH_OMAP2430) += sram243x.o +obj-$(CONFIG_SOC_OMAP2420) += sram242x.o +obj-$(CONFIG_SOC_OMAP2430) += sram243x.o obj-$(CONFIG_ARCH_OMAP3) += sram34xx.o AFLAGS_sram242x.o :=-Wa,-march=armv6 @@ -40,8 +40,8 @@ AFLAGS_sram243x.o :=-Wa,-march=armv6 AFLAGS_sram34xx.o :=-Wa,-march=armv7-a # Pin multiplexing -obj-$(CONFIG_ARCH_OMAP2420) += mux2420.o -obj-$(CONFIG_ARCH_OMAP2430) += mux2430.o +obj-$(CONFIG_SOC_OMAP2420) += mux2420.o +obj-$(CONFIG_SOC_OMAP2430) += mux2430.o obj-$(CONFIG_ARCH_OMAP3) += mux34xx.o obj-$(CONFIG_ARCH_OMAP4) += mux44xx.o @@ -59,10 +59,10 @@ endif # Power Management ifeq ($(CONFIG_PM),y) obj-$(CONFIG_ARCH_OMAP2) += pm24xx.o -obj-$(CONFIG_ARCH_OMAP2) += sleep24xx.o pm_bus.o voltage.o -obj-$(CONFIG_ARCH_OMAP3) += pm34xx.o sleep34xx.o voltage.o \ +obj-$(CONFIG_ARCH_OMAP2) += sleep24xx.o pm_bus.o +obj-$(CONFIG_ARCH_OMAP3) += pm34xx.o sleep34xx.o \ cpuidle34xx.o pm_bus.o -obj-$(CONFIG_ARCH_OMAP4) += pm44xx.o voltage.o pm_bus.o +obj-$(CONFIG_ARCH_OMAP4) += pm44xx.o pm_bus.o obj-$(CONFIG_PM_DEBUG) += pm-debug.o obj-$(CONFIG_OMAP_SMARTREFLEX) += sr_device.o smartreflex.o obj-$(CONFIG_OMAP_SMARTREFLEX_CLASS3) += smartreflex-class3.o @@ -78,13 +78,25 @@ endif # PRCM obj-$(CONFIG_ARCH_OMAP2) += prcm.o cm2xxx_3xxx.o prm2xxx_3xxx.o -obj-$(CONFIG_ARCH_OMAP3) += prcm.o cm2xxx_3xxx.o prm2xxx_3xxx.o +obj-$(CONFIG_ARCH_OMAP3) += prcm.o cm2xxx_3xxx.o prm2xxx_3xxx.o \ + vc3xxx_data.o vp3xxx_data.o # XXX The presence of cm2xxx_3xxx.o on the line below is temporary and # will be removed once the OMAP4 part of the codebase is converted to # use OMAP4-specific PRCM functions. obj-$(CONFIG_ARCH_OMAP4) += prcm.o cm2xxx_3xxx.o cminst44xx.o \ cm44xx.o prcm_mpu44xx.o \ - prminst44xx.o + prminst44xx.o vc44xx_data.o \ + vp44xx_data.o + +# OMAP voltage domains +ifeq ($(CONFIG_PM),y) +voltagedomain-common := voltage.o +obj-$(CONFIG_ARCH_OMAP2) += $(voltagedomain-common) +obj-$(CONFIG_ARCH_OMAP3) += $(voltagedomain-common) \ + voltagedomains3xxx_data.o +obj-$(CONFIG_ARCH_OMAP4) += $(voltagedomain-common) \ + voltagedomains44xx_data.o +endif # OMAP powerdomain framework powerdomain-common += powerdomain.o powerdomain-common.o @@ -102,39 +114,49 @@ obj-$(CONFIG_ARCH_OMAP4) += $(powerdomain-common) \ # PRCM clockdomain control obj-$(CONFIG_ARCH_OMAP2) += clockdomain.o \ + clockdomain2xxx_3xxx.o \ clockdomains2xxx_3xxx_data.o obj-$(CONFIG_ARCH_OMAP3) += clockdomain.o \ + clockdomain2xxx_3xxx.o \ clockdomains2xxx_3xxx_data.o obj-$(CONFIG_ARCH_OMAP4) += clockdomain.o \ + clockdomain44xx.o \ clockdomains44xx_data.o + # Clock framework obj-$(CONFIG_ARCH_OMAP2) += $(clock-common) clock2xxx.o \ clkt2xxx_sys.o \ clkt2xxx_dpllcore.o \ clkt2xxx_virt_prcm_set.o \ - clkt2xxx_apll.o clkt2xxx_osc.o -obj-$(CONFIG_ARCH_OMAP2420) += clock2420_data.o -obj-$(CONFIG_ARCH_OMAP2430) += clock2430.o clock2430_data.o + clkt2xxx_apll.o clkt2xxx_osc.o \ + clkt2xxx_dpll.o clkt_iclk.o +obj-$(CONFIG_SOC_OMAP2420) += clock2420_data.o +obj-$(CONFIG_SOC_OMAP2430) += clock2430.o clock2430_data.o obj-$(CONFIG_ARCH_OMAP3) += $(clock-common) clock3xxx.o \ clock34xx.o clkt34xx_dpll3m2.o \ clock3517.o clock36xx.o \ - dpll3xxx.o clock3xxx_data.o + dpll3xxx.o clock3xxx_data.o \ + clkt_iclk.o obj-$(CONFIG_ARCH_OMAP4) += $(clock-common) clock44xx_data.o \ - dpll3xxx.o + dpll3xxx.o dpll44xx.o # OMAP2 clock rate set data (old "OPP" data) -obj-$(CONFIG_ARCH_OMAP2420) += opp2420_data.o -obj-$(CONFIG_ARCH_OMAP2430) += opp2430_data.o +obj-$(CONFIG_SOC_OMAP2420) += opp2420_data.o +obj-$(CONFIG_SOC_OMAP2430) += opp2430_data.o # hwmod data -obj-$(CONFIG_ARCH_OMAP2420) += omap_hwmod_2420_data.o -obj-$(CONFIG_ARCH_OMAP2430) += omap_hwmod_2430_data.o +obj-$(CONFIG_SOC_OMAP2420) += omap_hwmod_2420_data.o +obj-$(CONFIG_SOC_OMAP2430) += omap_hwmod_2430_data.o obj-$(CONFIG_ARCH_OMAP3) += omap_hwmod_3xxx_data.o obj-$(CONFIG_ARCH_OMAP4) += omap_hwmod_44xx_data.o # EMU peripherals obj-$(CONFIG_OMAP3_EMU) += emu.o +# L3 interconnect +obj-$(CONFIG_ARCH_OMAP3) += omap_l3_smx.o +obj-$(CONFIG_ARCH_OMAP4) += omap_l3_noc.o + obj-$(CONFIG_OMAP_MBOX_FWK) += mailbox_mach.o mailbox_mach-objs := mailbox.o @@ -218,12 +240,14 @@ obj-$(CONFIG_MACH_OMAP4_PANDA) += board-omap4panda.o \ hsmmc.o \ omap_phy_internal.o -obj-$(CONFIG_MACH_OMAP3517EVM) += board-am3517evm.o +obj-$(CONFIG_MACH_OMAP3517EVM) += board-am3517evm.o \ + omap_phy_internal.o \ obj-$(CONFIG_MACH_CRANEBOARD) += board-am3517crane.o obj-$(CONFIG_MACH_SBC3530) += board-omap3stalker.o \ hsmmc.o +obj-$(CONFIG_MACH_TI8168EVM) += board-ti8168evm.o # Platform specific device init code usbfs-$(CONFIG_ARCH_OMAP_OTG) := usb-fs.o obj-y += $(usbfs-m) $(usbfs-y) @@ -242,3 +266,7 @@ obj-y += $(smc91x-m) $(smc91x-y) smsc911x-$(CONFIG_SMSC911X) := gpmc-smsc911x.o obj-y += $(smsc911x-m) $(smsc911x-y) +obj-$(CONFIG_ARCH_OMAP4) += hwspinlock.o + +disp-$(CONFIG_OMAP2_DSS) := display.o +obj-y += $(disp-m) $(disp-y) diff --git a/arch/arm/mach-omap2/board-2430sdp.c b/arch/arm/mach-omap2/board-2430sdp.c index e0661777f59..1fa6bb896f4 100644 --- a/arch/arm/mach-omap2/board-2430sdp.c +++ b/arch/arm/mach-omap2/board-2430sdp.c @@ -22,6 +22,7 @@ #include <linux/mmc/host.h> #include <linux/delay.h> #include <linux/i2c/twl.h> +#include <linux/regulator/machine.h> #include <linux/err.h> #include <linux/clk.h> #include <linux/io.h> @@ -139,15 +140,31 @@ static struct omap_board_config_kernel sdp2430_config[] __initdata = { {OMAP_TAG_LCD, &sdp2430_lcd_config}, }; -static void __init omap_2430sdp_init_irq(void) +static void __init omap_2430sdp_init_early(void) { - omap_board_config = sdp2430_config; - omap_board_config_size = ARRAY_SIZE(sdp2430_config); omap2_init_common_infrastructure(); omap2_init_common_devices(NULL, NULL); - omap_init_irq(); } +static struct regulator_consumer_supply sdp2430_vmmc1_supplies[] = { + REGULATOR_SUPPLY("vmmc", "omap_hsmmc.0"), +}; + +/* VMMC1 for OMAP VDD_MMC1 (i/o) and MMC1 card */ +static struct regulator_init_data sdp2430_vmmc1 = { + .constraints = { + .min_uV = 1850000, + .max_uV = 3150000, + .valid_modes_mask = REGULATOR_MODE_NORMAL + | REGULATOR_MODE_STANDBY, + .valid_ops_mask = REGULATOR_CHANGE_VOLTAGE + | REGULATOR_CHANGE_MODE + | REGULATOR_CHANGE_STATUS, + }, + .num_consumer_supplies = ARRAY_SIZE(sdp2430_vmmc1_supplies), + .consumer_supplies = &sdp2430_vmmc1_supplies[0], +}; + static struct twl4030_gpio_platform_data sdp2430_gpio_data = { .gpio_base = OMAP_MAX_GPIO_LINES, .irq_base = TWL4030_GPIO_IRQ_BASE, @@ -160,6 +177,7 @@ static struct twl4030_platform_data sdp2430_twldata = { /* platform_data for children goes here */ .gpio = &sdp2430_gpio_data, + .vmmc1 = &sdp2430_vmmc1, }; static struct i2c_board_info __initdata sdp2430_i2c_boardinfo[] = { @@ -226,6 +244,9 @@ static void __init omap_2430sdp_init(void) omap2430_mux_init(board_mux, OMAP_PACKAGE_ZAC); + omap_board_config = sdp2430_config; + omap_board_config_size = ARRAY_SIZE(sdp2430_config); + omap2430_i2c_init(); platform_add_devices(sdp2430_devices, ARRAY_SIZE(sdp2430_devices)); @@ -253,9 +274,10 @@ static void __init omap_2430sdp_map_io(void) MACHINE_START(OMAP_2430SDP, "OMAP2430 sdp2430 board") /* Maintainer: Syed Khasim - Texas Instruments Inc */ .boot_params = 0x80000100, - .map_io = omap_2430sdp_map_io, .reserve = omap_reserve, - .init_irq = omap_2430sdp_init_irq, + .map_io = omap_2430sdp_map_io, + .init_early = omap_2430sdp_init_early, + .init_irq = omap_init_irq, .init_machine = omap_2430sdp_init, .timer = &omap_timer, MACHINE_END diff --git a/arch/arm/mach-omap2/board-3430sdp.c b/arch/arm/mach-omap2/board-3430sdp.c index 7542ba59f2b..c06eb423c4e 100644 --- a/arch/arm/mach-omap2/board-3430sdp.c +++ b/arch/arm/mach-omap2/board-3430sdp.c @@ -307,34 +307,16 @@ static struct omap_dss_board_info sdp3430_dss_data = { .default_device = &sdp3430_lcd_device, }; -static struct platform_device sdp3430_dss_device = { - .name = "omapdss", - .id = -1, - .dev = { - .platform_data = &sdp3430_dss_data, - }, -}; - -static struct regulator_consumer_supply sdp3430_vdda_dac_supply = { - .supply = "vdda_dac", - .dev = &sdp3430_dss_device.dev, -}; - -static struct platform_device *sdp3430_devices[] __initdata = { - &sdp3430_dss_device, -}; +static struct regulator_consumer_supply sdp3430_vdda_dac_supply = + REGULATOR_SUPPLY("vdda_dac", "omapdss"); static struct omap_board_config_kernel sdp3430_config[] __initdata = { }; -static void __init omap_3430sdp_init_irq(void) +static void __init omap_3430sdp_init_early(void) { - omap_board_config = sdp3430_config; - omap_board_config_size = ARRAY_SIZE(sdp3430_config); - omap3_pm_init_cpuidle(omap3_cpuidle_params_table); omap2_init_common_infrastructure(); omap2_init_common_devices(hyb18m512160af6_sdrc_params, NULL); - omap_init_irq(); } static int sdp3430_batt_table[] = { @@ -370,18 +352,6 @@ static struct omap2_hsmmc_info mmc[] = { {} /* Terminator */ }; -static struct regulator_consumer_supply sdp3430_vmmc1_supply = { - .supply = "vmmc", -}; - -static struct regulator_consumer_supply sdp3430_vsim_supply = { - .supply = "vmmc_aux", -}; - -static struct regulator_consumer_supply sdp3430_vmmc2_supply = { - .supply = "vmmc", -}; - static int sdp3430_twl_gpio_setup(struct device *dev, unsigned gpio, unsigned ngpio) { @@ -392,13 +362,6 @@ static int sdp3430_twl_gpio_setup(struct device *dev, mmc[1].gpio_cd = gpio + 1; omap2_hsmmc_init(mmc); - /* link regulators to MMC adapters ... we "know" the - * regulators will be set up only *after* we return. - */ - sdp3430_vmmc1_supply.dev = mmc[0].dev; - sdp3430_vsim_supply.dev = mmc[0].dev; - sdp3430_vmmc2_supply.dev = mmc[1].dev; - /* gpio + 7 is "sub_lcd_en_bkl" (output/PWM1) */ gpio_request(gpio + 7, "sub_lcd_en_bkl"); gpio_direction_output(gpio + 7, 0); @@ -427,6 +390,34 @@ static struct twl4030_madc_platform_data sdp3430_madc_data = { .irq_line = 1, }; +/* regulator consumer mappings */ + +/* ads7846 on SPI */ +static struct regulator_consumer_supply sdp3430_vaux3_supplies[] = { + REGULATOR_SUPPLY("vcc", "spi1.0"), +}; + +static struct regulator_consumer_supply sdp3430_vdda_dac_supplies[] = { + REGULATOR_SUPPLY("vdda_dac", "omapdss"), +}; + +/* VPLL2 for digital video outputs */ +static struct regulator_consumer_supply sdp3430_vpll2_supplies[] = { + REGULATOR_SUPPLY("vdds_dsi", "omapdss"), +}; + +static struct regulator_consumer_supply sdp3430_vmmc1_supplies[] = { + REGULATOR_SUPPLY("vmmc", "omap_hsmmc.0"), +}; + +static struct regulator_consumer_supply sdp3430_vsim_supplies[] = { + REGULATOR_SUPPLY("vmmc_aux", "omap_hsmmc.0"), +}; + +static struct regulator_consumer_supply sdp3430_vmmc2_supplies[] = { + REGULATOR_SUPPLY("vmmc", "omap_hsmmc.1"), +}; + /* * Apply all the fixed voltages since most versions of U-Boot * don't bother with that initialization. @@ -469,6 +460,8 @@ static struct regulator_init_data sdp3430_vaux3 = { .valid_ops_mask = REGULATOR_CHANGE_MODE | REGULATOR_CHANGE_STATUS, }, + .num_consumer_supplies = ARRAY_SIZE(sdp3430_vaux3_supplies), + .consumer_supplies = sdp3430_vaux3_supplies, }; /* VAUX4 for OMAP VDD_CSI2 (camera) */ @@ -495,8 +488,8 @@ static struct regulator_init_data sdp3430_vmmc1 = { | REGULATOR_CHANGE_MODE | REGULATOR_CHANGE_STATUS, }, - .num_consumer_supplies = 1, - .consumer_supplies = &sdp3430_vmmc1_supply, + .num_consumer_supplies = ARRAY_SIZE(sdp3430_vmmc1_supplies), + .consumer_supplies = sdp3430_vmmc1_supplies, }; /* VMMC2 for MMC2 card */ @@ -510,8 +503,8 @@ static struct regulator_init_data sdp3430_vmmc2 = { .valid_ops_mask = REGULATOR_CHANGE_MODE | REGULATOR_CHANGE_STATUS, }, - .num_consumer_supplies = 1, - .consumer_supplies = &sdp3430_vmmc2_supply, + .num_consumer_supplies = ARRAY_SIZE(sdp3430_vmmc2_supplies), + .consumer_supplies = sdp3430_vmmc2_supplies, }; /* VSIM for OMAP VDD_MMC1A (i/o for DAT4..DAT7) */ @@ -525,8 +518,8 @@ static struct regulator_init_data sdp3430_vsim = { | REGULATOR_CHANGE_MODE | REGULATOR_CHANGE_STATUS, }, - .num_consumer_supplies = 1, - .consumer_supplies = &sdp3430_vsim_supply, + .num_consumer_supplies = ARRAY_SIZE(sdp3430_vsim_supplies), + .consumer_supplies = sdp3430_vsim_supplies, }; /* VDAC for DSS driving S-Video */ @@ -540,16 +533,8 @@ static struct regulator_init_data sdp3430_vdac = { .valid_ops_mask = REGULATOR_CHANGE_MODE | REGULATOR_CHANGE_STATUS, }, - .num_consumer_supplies = 1, - .consumer_supplies = &sdp3430_vdda_dac_supply, -}; - -/* VPLL2 for digital video outputs */ -static struct regulator_consumer_supply sdp3430_vpll2_supplies[] = { - { - .supply = "vdds_dsi", - .dev = &sdp3430_dss_device.dev, - } + .num_consumer_supplies = ARRAY_SIZE(sdp3430_vdda_dac_supplies), + .consumer_supplies = sdp3430_vdda_dac_supplies, }; static struct regulator_init_data sdp3430_vpll2 = { @@ -567,9 +552,7 @@ static struct regulator_init_data sdp3430_vpll2 = { .consumer_supplies = sdp3430_vpll2_supplies, }; -static struct twl4030_codec_audio_data sdp3430_audio = { - .audio_mclk = 26000000, -}; +static struct twl4030_codec_audio_data sdp3430_audio; static struct twl4030_codec_data sdp3430_codec = { .audio_mclk = 26000000, @@ -669,6 +652,106 @@ 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 = { + .id = 0, + .pads = serial1_pads, + .pads_cnt = ARRAY_SIZE(serial1_pads), +}; + +static struct omap_board_data serial2_data = { + .id = 1, + .pads = serial2_pads, + .pads_cnt = ARRAY_SIZE(serial2_pads), +}; + +static struct omap_board_data serial3_data = { + .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 /* @@ -800,8 +883,11 @@ static struct omap_musb_board_data musb_board_data = { static void __init omap_3430sdp_init(void) { omap3_mux_init(board_mux, OMAP_PACKAGE_CBB); + omap_board_config = sdp3430_config; + omap_board_config_size = ARRAY_SIZE(sdp3430_config); + omap3_pm_init_cpuidle(omap3_cpuidle_params_table); omap3430_i2c_init(); - platform_add_devices(sdp3430_devices, ARRAY_SIZE(sdp3430_devices)); + omap_display_init(&sdp3430_dss_data); if (omap_rev() > OMAP3430_REV_ES1_0) ts_gpio = SDP3430_TS_GPIO_IRQ_SDPV2; else @@ -810,10 +896,10 @@ static void __init omap_3430sdp_init(void) spi_register_board_info(sdp3430_spi_board_info, ARRAY_SIZE(sdp3430_spi_board_info)); ads7846_dev_init(); - omap_serial_init(); + board_serial_init(); usb_musb_init(&musb_board_data); board_smc91x_init(); - board_flash_init(sdp_flash_partitions, chip_sel_3430); + board_flash_init(sdp_flash_partitions, chip_sel_3430, 0); sdp3430_display_init(); enable_board_wakeup_source(); usbhs_init(&usbhs_bdata); @@ -822,9 +908,10 @@ static void __init omap_3430sdp_init(void) MACHINE_START(OMAP_3430SDP, "OMAP3430 3430SDP board") /* Maintainer: Syed Khasim - Texas Instruments Inc */ .boot_params = 0x80000100, - .map_io = omap3_map_io, .reserve = omap_reserve, - .init_irq = omap_3430sdp_init_irq, + .map_io = omap3_map_io, + .init_early = omap_3430sdp_init_early, + .init_irq = omap_init_irq, .init_machine = omap_3430sdp_init, .timer = &omap_timer, MACHINE_END diff --git a/arch/arm/mach-omap2/board-3630sdp.c b/arch/arm/mach-omap2/board-3630sdp.c index deed2db32c5..a5933cc15ca 100644 --- a/arch/arm/mach-omap2/board-3630sdp.c +++ b/arch/arm/mach-omap2/board-3630sdp.c @@ -11,6 +11,7 @@ #include <linux/platform_device.h> #include <linux/input.h> #include <linux/gpio.h> +#include <linux/mtd/nand.h> #include <asm/mach-types.h> #include <asm/mach/arch.h> @@ -69,14 +70,11 @@ static const struct usbhs_omap_board_data usbhs_bdata __initconst = { static struct omap_board_config_kernel sdp_config[] __initdata = { }; -static void __init omap_sdp_init_irq(void) +static void __init omap_sdp_init_early(void) { - omap_board_config = sdp_config; - omap_board_config_size = ARRAY_SIZE(sdp_config); omap2_init_common_infrastructure(); omap2_init_common_devices(h8mbx00u0mer0em_sdrc_params, h8mbx00u0mer0em_sdrc_params); - omap_init_irq(); } #ifdef CONFIG_OMAP_MUX @@ -206,19 +204,22 @@ static struct flash_partitions sdp_flash_partitions[] = { static void __init omap_sdp_init(void) { omap3_mux_init(board_mux, OMAP_PACKAGE_CBP); + omap_board_config = sdp_config; + omap_board_config_size = ARRAY_SIZE(sdp_config); zoom_peripherals_init(); zoom_display_init(); board_smc91x_init(); - board_flash_init(sdp_flash_partitions, chip_sel_sdp); + board_flash_init(sdp_flash_partitions, chip_sel_sdp, NAND_BUSWIDTH_16); enable_board_wakeup_source(); usbhs_init(&usbhs_bdata); } MACHINE_START(OMAP_3630SDP, "OMAP 3630SDP board") .boot_params = 0x80000100, - .map_io = omap3_map_io, .reserve = omap_reserve, - .init_irq = omap_sdp_init_irq, + .map_io = omap3_map_io, + .init_early = omap_sdp_init_early, + .init_irq = omap_init_irq, .init_machine = omap_sdp_init, .timer = &omap_timer, MACHINE_END diff --git a/arch/arm/mach-omap2/board-4430sdp.c b/arch/arm/mach-omap2/board-4430sdp.c index f603f3b04cb..333ceb2c8fb 100644 --- a/arch/arm/mach-omap2/board-4430sdp.c +++ b/arch/arm/mach-omap2/board-4430sdp.c @@ -35,6 +35,7 @@ #include <plat/common.h> #include <plat/usb.h> #include <plat/mmc.h> +#include <plat/omap4-keypad.h> #include "mux.h" #include "hsmmc.h" @@ -47,6 +48,90 @@ #define OMAP4_SFH7741_SENSOR_OUTPUT_GPIO 184 #define OMAP4_SFH7741_ENABLE_GPIO 188 +static const int sdp4430_keymap[] = { + KEY(0, 0, KEY_E), + KEY(0, 1, KEY_R), + KEY(0, 2, KEY_T), + KEY(0, 3, KEY_HOME), + KEY(0, 4, KEY_F5), + KEY(0, 5, KEY_UNKNOWN), + KEY(0, 6, KEY_I), + KEY(0, 7, KEY_LEFTSHIFT), + + KEY(1, 0, KEY_D), + KEY(1, 1, KEY_F), + KEY(1, 2, KEY_G), + KEY(1, 3, KEY_SEND), + KEY(1, 4, KEY_F6), + KEY(1, 5, KEY_UNKNOWN), + KEY(1, 6, KEY_K), + KEY(1, 7, KEY_ENTER), + + KEY(2, 0, KEY_X), + KEY(2, 1, KEY_C), + KEY(2, 2, KEY_V), + KEY(2, 3, KEY_END), + KEY(2, 4, KEY_F7), + KEY(2, 5, KEY_UNKNOWN), + KEY(2, 6, KEY_DOT), + KEY(2, 7, KEY_CAPSLOCK), + + KEY(3, 0, KEY_Z), + KEY(3, 1, KEY_KPPLUS), + KEY(3, 2, KEY_B), + KEY(3, 3, KEY_F1), + KEY(3, 4, KEY_F8), + KEY(3, 5, KEY_UNKNOWN), + KEY(3, 6, KEY_O), + KEY(3, 7, KEY_SPACE), + + KEY(4, 0, KEY_W), + KEY(4, 1, KEY_Y), + KEY(4, 2, KEY_U), + KEY(4, 3, KEY_F2), + KEY(4, 4, KEY_VOLUMEUP), + KEY(4, 5, KEY_UNKNOWN), + KEY(4, 6, KEY_L), + KEY(4, 7, KEY_LEFT), + + KEY(5, 0, KEY_S), + KEY(5, 1, KEY_H), + KEY(5, 2, KEY_J), + KEY(5, 3, KEY_F3), + KEY(5, 4, KEY_F9), + KEY(5, 5, KEY_VOLUMEDOWN), + KEY(5, 6, KEY_M), + KEY(5, 7, KEY_RIGHT), + + KEY(6, 0, KEY_Q), + KEY(6, 1, KEY_A), + KEY(6, 2, KEY_N), + KEY(6, 3, KEY_BACK), + KEY(6, 4, KEY_BACKSPACE), + KEY(6, 5, KEY_UNKNOWN), + KEY(6, 6, KEY_P), + KEY(6, 7, KEY_UP), + + KEY(7, 0, KEY_PROG1), + KEY(7, 1, KEY_PROG2), + KEY(7, 2, KEY_PROG3), + KEY(7, 3, KEY_PROG4), + KEY(7, 4, KEY_F4), + KEY(7, 5, KEY_UNKNOWN), + KEY(7, 6, KEY_OK), + KEY(7, 7, KEY_DOWN), +}; + +static struct matrix_keymap_data sdp4430_keymap_data = { + .keymap = sdp4430_keymap, + .keymap_size = ARRAY_SIZE(sdp4430_keymap), +}; + +static struct omap4_keypad_platform_data sdp4430_keypad_data = { + .keymap_data = &sdp4430_keymap_data, + .rows = 8, + .cols = 8, +}; static struct gpio_led sdp4430_gpio_leds[] = { { .name = "omap4:green:debug0", @@ -238,16 +323,13 @@ static struct omap_board_config_kernel sdp4430_config[] __initdata = { { OMAP_TAG_LCD, &sdp4430_lcd_config }, }; -static void __init omap_4430sdp_init_irq(void) +static void __init omap_4430sdp_init_early(void) { - omap_board_config = sdp4430_config; - omap_board_config_size = ARRAY_SIZE(sdp4430_config); omap2_init_common_infrastructure(); omap2_init_common_devices(NULL, NULL); #ifdef CONFIG_OMAP_32K_TIMER omap2_gp_clockevent_set_gptimer(1); #endif - gic_init_irq(); } static struct omap_musb_board_data musb_board_data = { @@ -266,11 +348,6 @@ static struct twl4030_usb_data omap4_usbphy_data = { static struct omap2_hsmmc_info mmc[] = { { - .mmc = 1, - .caps = MMC_CAP_4_BIT_DATA | MMC_CAP_8_BIT_DATA, - .gpio_wp = -EINVAL, - }, - { .mmc = 2, .caps = MMC_CAP_4_BIT_DATA | MMC_CAP_8_BIT_DATA, .gpio_cd = -EINVAL, @@ -278,19 +355,24 @@ static struct omap2_hsmmc_info mmc[] = { .nonremovable = true, .ocr_mask = MMC_VDD_29_30, }, + { + .mmc = 1, + .caps = MMC_CAP_4_BIT_DATA | MMC_CAP_8_BIT_DATA, + .gpio_wp = -EINVAL, + }, {} /* Terminator */ }; static struct regulator_consumer_supply sdp4430_vaux_supply[] = { { .supply = "vmmc", - .dev_name = "mmci-omap-hs.1", + .dev_name = "omap_hsmmc.1", }, }; static struct regulator_consumer_supply sdp4430_vmmc_supply[] = { { .supply = "vmmc", - .dev_name = "mmci-omap-hs.0", + .dev_name = "omap_hsmmc.0", }, }; @@ -424,7 +506,6 @@ static struct regulator_init_data sdp4430_vana = { .constraints = { .min_uV = 2100000, .max_uV = 2100000, - .apply_uV = true, .valid_modes_mask = REGULATOR_MODE_NORMAL | REGULATOR_MODE_STANDBY, .valid_ops_mask = REGULATOR_CHANGE_MODE @@ -436,7 +517,6 @@ static struct regulator_init_data sdp4430_vcxio = { .constraints = { .min_uV = 1800000, .max_uV = 1800000, - .apply_uV = true, .valid_modes_mask = REGULATOR_MODE_NORMAL | REGULATOR_MODE_STANDBY, .valid_ops_mask = REGULATOR_CHANGE_MODE @@ -448,7 +528,6 @@ static struct regulator_init_data sdp4430_vdac = { .constraints = { .min_uV = 1800000, .max_uV = 1800000, - .apply_uV = true, .valid_modes_mask = REGULATOR_MODE_NORMAL | REGULATOR_MODE_STANDBY, .valid_ops_mask = REGULATOR_CHANGE_MODE @@ -547,9 +626,76 @@ static struct omap_board_mux board_mux[] __initdata = { OMAP4_MUX(USBB2_ULPITLL_CLK, OMAP_MUX_MODE4 | OMAP_PIN_OUTPUT), { .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 = { + .id = 1, + .pads = serial2_pads, + .pads_cnt = ARRAY_SIZE(serial2_pads), +}; + +static struct omap_board_data serial3_data = { + .id = 2, + .pads = serial3_pads, + .pads_cnt = ARRAY_SIZE(serial3_pads), +}; + +static struct omap_board_data serial4_data = { + .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 -#endif + +static inline void board_serial_init(void) +{ + omap_serial_init(); +} + #endif static void __init omap_4430sdp_init(void) { @@ -560,10 +706,13 @@ static void __init omap_4430sdp_init(void) package = OMAP_PACKAGE_CBL; omap4_mux_init(board_mux, package); + omap_board_config = sdp4430_config; + omap_board_config_size = ARRAY_SIZE(sdp4430_config); + omap4_i2c_init(); omap_sfh7741prox_init(); platform_add_devices(sdp4430_devices, ARRAY_SIZE(sdp4430_devices)); - omap_serial_init(); + board_serial_init(); omap4_twl6030_hsmmc_init(mmc); usb_musb_init(&musb_board_data); @@ -576,6 +725,10 @@ static void __init omap_4430sdp_init(void) spi_register_board_info(sdp4430_spi_board_info, ARRAY_SIZE(sdp4430_spi_board_info)); } + + status = omap4_keyboard_init(&sdp4430_keypad_data); + if (status) + pr_err("Keypad initialization failed: %d\n", status); } static void __init omap_4430sdp_map_io(void) @@ -587,9 +740,10 @@ static void __init omap_4430sdp_map_io(void) MACHINE_START(OMAP_4430SDP, "OMAP4430 4430SDP board") /* Maintainer: Santosh Shilimkar - Texas Instruments Inc */ .boot_params = 0x80000100, - .map_io = omap_4430sdp_map_io, .reserve = omap_reserve, - .init_irq = omap_4430sdp_init_irq, + .map_io = omap_4430sdp_map_io, + .init_early = omap_4430sdp_init_early, + .init_irq = gic_init_irq, .init_machine = omap_4430sdp_init, .timer = &omap_timer, MACHINE_END diff --git a/arch/arm/mach-omap2/board-am3517crane.c b/arch/arm/mach-omap2/board-am3517crane.c index e3a194f6b13..a890d244fec 100644 --- a/arch/arm/mach-omap2/board-am3517crane.c +++ b/arch/arm/mach-omap2/board-am3517crane.c @@ -49,14 +49,10 @@ static struct omap_board_mux board_mux[] __initdata = { #define board_mux NULL #endif -static void __init am3517_crane_init_irq(void) +static void __init am3517_crane_init_early(void) { - omap_board_config = am3517_crane_config; - omap_board_config_size = ARRAY_SIZE(am3517_crane_config); - omap2_init_common_infrastructure(); omap2_init_common_devices(NULL, NULL); - omap_init_irq(); } static struct usbhs_omap_board_data usbhs_bdata __initdata = { @@ -77,6 +73,9 @@ static void __init am3517_crane_init(void) omap3_mux_init(board_mux, OMAP_PACKAGE_CBB); omap_serial_init(); + omap_board_config = am3517_crane_config; + omap_board_config_size = ARRAY_SIZE(am3517_crane_config); + /* Configure GPIO for EHCI port */ if (omap_mux_init_gpio(GPIO_USB_NRESET, OMAP_PIN_OUTPUT)) { pr_err("Can not configure mux for GPIO_USB_NRESET %d\n", @@ -108,9 +107,10 @@ static void __init am3517_crane_init(void) MACHINE_START(CRANEBOARD, "AM3517/05 CRANEBOARD") .boot_params = 0x80000100, - .map_io = omap3_map_io, .reserve = omap_reserve, - .init_irq = am3517_crane_init_irq, + .map_io = omap3_map_io, + .init_early = am3517_crane_init_early, + .init_irq = omap_init_irq, .init_machine = am3517_crane_init, .timer = &omap_timer, MACHINE_END diff --git a/arch/arm/mach-omap2/board-am3517evm.c b/arch/arm/mach-omap2/board-am3517evm.c index 913538ad17d..ce7d5e6e415 100644 --- a/arch/arm/mach-omap2/board-am3517evm.c +++ b/arch/arm/mach-omap2/board-am3517evm.c @@ -200,6 +200,9 @@ static struct pca953x_platform_data am3517evm_gpio_expander_info_0 = { }; static struct i2c_board_info __initdata am3517evm_i2c2_boardinfo[] = { { + I2C_BOARD_INFO("tlv320aic23", 0x1A), + }, + { I2C_BOARD_INFO("tca6416", 0x21), .platform_data = &am3517evm_gpio_expander_info_0, }, @@ -378,37 +381,23 @@ static struct omap_dss_board_info am3517_evm_dss_data = { .default_device = &am3517_evm_lcd_device, }; -static struct platform_device am3517_evm_dss_device = { - .name = "omapdss", - .id = -1, - .dev = { - .platform_data = &am3517_evm_dss_data, - }, -}; - /* * Board initialization */ -static struct omap_board_config_kernel am3517_evm_config[] __initdata = { -}; - -static struct platform_device *am3517_evm_devices[] __initdata = { - &am3517_evm_dss_device, -}; - -static void __init am3517_evm_init_irq(void) +static void __init am3517_evm_init_early(void) { - omap_board_config = am3517_evm_config; - omap_board_config_size = ARRAY_SIZE(am3517_evm_config); omap2_init_common_infrastructure(); omap2_init_common_devices(NULL, NULL); - omap_init_irq(); } static struct omap_musb_board_data musb_board_data = { .interface_type = MUSB_INTERFACE_ULPI, .mode = MUSB_OTG, .power = 500, + .set_phy_power = am35x_musb_phy_power, + .clear_irq = am35x_musb_clear_irq, + .set_mode = am35x_musb_set_mode, + .reset = am35x_musb_reset, }; static __init void am3517_evm_musb_init(void) @@ -490,14 +479,17 @@ static void am3517_evm_hecc_init(struct ti_hecc_platform_data *pdata) platform_device_register(&am3517_hecc_device); } +static struct omap_board_config_kernel am3517_evm_config[] __initdata = { +}; + static void __init am3517_evm_init(void) { + omap_board_config = am3517_evm_config; + omap_board_config_size = ARRAY_SIZE(am3517_evm_config); omap3_mux_init(board_mux, OMAP_PACKAGE_CBB); am3517_evm_i2c_init(); - platform_add_devices(am3517_evm_devices, - ARRAY_SIZE(am3517_evm_devices)); - + omap_display_init(&am3517_evm_dss_data); omap_serial_init(); /* Configure GPIO for EHCI port */ @@ -521,9 +513,10 @@ static void __init am3517_evm_init(void) MACHINE_START(OMAP3517EVM, "OMAP3517/AM3517 EVM") .boot_params = 0x80000100, - .map_io = omap3_map_io, .reserve = omap_reserve, - .init_irq = am3517_evm_init_irq, + .map_io = omap3_map_io, + .init_early = am3517_evm_init_early, + .init_irq = omap_init_irq, .init_machine = am3517_evm_init, .timer = &omap_timer, MACHINE_END diff --git a/arch/arm/mach-omap2/board-apollon.c b/arch/arm/mach-omap2/board-apollon.c index 9f55b68687f..f4f8374a029 100644 --- a/arch/arm/mach-omap2/board-apollon.c +++ b/arch/arm/mach-omap2/board-apollon.c @@ -274,13 +274,10 @@ static struct omap_board_config_kernel apollon_config[] __initdata = { { OMAP_TAG_LCD, &apollon_lcd_config }, }; -static void __init omap_apollon_init_irq(void) +static void __init omap_apollon_init_early(void) { - omap_board_config = apollon_config; - omap_board_config_size = ARRAY_SIZE(apollon_config); omap2_init_common_infrastructure(); omap2_init_common_devices(NULL, NULL); - omap_init_irq(); } static void __init apollon_led_init(void) @@ -320,6 +317,8 @@ static void __init omap_apollon_init(void) u32 v; omap2420_mux_init(board_mux, OMAP_PACKAGE_ZAC); + omap_board_config = apollon_config; + omap_board_config_size = ARRAY_SIZE(apollon_config); apollon_init_smc91x(); apollon_led_init(); @@ -355,9 +354,10 @@ static void __init omap_apollon_map_io(void) MACHINE_START(OMAP_APOLLON, "OMAP24xx Apollon") /* Maintainer: Kyungmin Park <kyungmin.park@samsung.com> */ .boot_params = 0x80000100, - .map_io = omap_apollon_map_io, .reserve = omap_reserve, - .init_irq = omap_apollon_init_irq, + .map_io = omap_apollon_map_io, + .init_early = omap_apollon_init_early, + .init_irq = omap_init_irq, .init_machine = omap_apollon_init, .timer = &omap_timer, MACHINE_END diff --git a/arch/arm/mach-omap2/board-cm-t35.c b/arch/arm/mach-omap2/board-cm-t35.c index 9be7289cbb5..7b5647954c1 100644 --- a/arch/arm/mach-omap2/board-cm-t35.c +++ b/arch/arm/mach-omap2/board-cm-t35.c @@ -401,14 +401,6 @@ static struct omap_dss_board_info cm_t35_dss_data = { .default_device = &cm_t35_dvi_device, }; -static struct platform_device cm_t35_dss_device = { - .name = "omapdss", - .id = -1, - .dev = { - .platform_data = &cm_t35_dss_data, - }, -}; - static struct omap2_mcspi_device_config tdo24m_mcspi_config = { .turbo_mode = 0, .single_channel = 1, /* 0: slave, 1: master */ @@ -468,7 +460,7 @@ static void __init cm_t35_init_display(void) msleep(50); gpio_set_value(lcd_en_gpio, 1); - err = platform_device_register(&cm_t35_dss_device); + err = omap_display_init(&cm_t35_dss_data); if (err) { pr_err("CM-T35: failed to register DSS device\n"); goto err_dev_reg; @@ -495,15 +487,11 @@ static struct regulator_consumer_supply cm_t35_vsim_supply = { .supply = "vmmc_aux", }; -static struct regulator_consumer_supply cm_t35_vdac_supply = { - .supply = "vdda_dac", - .dev = &cm_t35_dss_device.dev, -}; +static struct regulator_consumer_supply cm_t35_vdac_supply = + REGULATOR_SUPPLY("vdda_dac", "omapdss"); -static struct regulator_consumer_supply cm_t35_vdvi_supply = { - .supply = "vdvi", - .dev = &cm_t35_dss_device.dev, -}; +static struct regulator_consumer_supply cm_t35_vdvi_supply = + REGULATOR_SUPPLY("vdvi", "omapdss"); /* VMMC1 for MMC1 pins CMD, CLK, DAT0..DAT3 (20 mA, plus card == max 220 mA) */ static struct regulator_init_data cm_t35_vmmc1 = { @@ -680,20 +668,14 @@ static void __init cm_t35_init_i2c(void) ARRAY_SIZE(cm_t35_i2c_boardinfo)); } -static struct omap_board_config_kernel cm_t35_config[] __initdata = { -}; - -static void __init cm_t35_init_irq(void) +static void __init cm_t35_init_early(void) { - omap_board_config = cm_t35_config; - omap_board_config_size = ARRAY_SIZE(cm_t35_config); - omap2_init_common_infrastructure(); omap2_init_common_devices(mt46h32m32lf6_sdrc_params, mt46h32m32lf6_sdrc_params); - omap_init_irq(); } +#ifdef CONFIG_OMAP_MUX static struct omap_board_mux board_mux[] __initdata = { /* nCS and IRQ for CM-T35 ethernet */ OMAP3_MUX(GPMC_NCS5, OMAP_MUX_MODE0), @@ -791,6 +773,7 @@ static struct omap_board_mux board_mux[] __initdata = { { .reg_offset = OMAP_MUX_TERMINATOR }, }; +#endif static struct omap_musb_board_data musb_board_data = { .interface_type = MUSB_INTERFACE_ULPI, @@ -798,8 +781,13 @@ static struct omap_musb_board_data musb_board_data = { .power = 100, }; +static struct omap_board_config_kernel cm_t35_config[] __initdata = { +}; + static void __init cm_t35_init(void) { + omap_board_config = cm_t35_config; + omap_board_config_size = ARRAY_SIZE(cm_t35_config); omap3_mux_init(board_mux, OMAP_PACKAGE_CUS); omap_serial_init(); cm_t35_init_i2c(); @@ -815,9 +803,10 @@ static void __init cm_t35_init(void) MACHINE_START(CM_T35, "Compulab CM-T35") .boot_params = 0x80000100, - .map_io = omap3_map_io, .reserve = omap_reserve, - .init_irq = cm_t35_init_irq, + .map_io = omap3_map_io, + .init_early = cm_t35_init_early, + .init_irq = omap_init_irq, .init_machine = cm_t35_init, .timer = &omap_timer, MACHINE_END diff --git a/arch/arm/mach-omap2/board-cm-t3517.c b/arch/arm/mach-omap2/board-cm-t3517.c index 8e18dc76b11..a27e3eee829 100644 --- a/arch/arm/mach-omap2/board-cm-t3517.c +++ b/arch/arm/mach-omap2/board-cm-t3517.c @@ -254,16 +254,13 @@ static inline void cm_t3517_init_nand(void) {} static struct omap_board_config_kernel cm_t3517_config[] __initdata = { }; -static void __init cm_t3517_init_irq(void) +static void __init cm_t3517_init_early(void) { - omap_board_config = cm_t3517_config; - omap_board_config_size = ARRAY_SIZE(cm_t3517_config); - omap2_init_common_infrastructure(); omap2_init_common_devices(NULL, NULL); - omap_init_irq(); } +#ifdef CONFIG_OMAP_MUX static struct omap_board_mux board_mux[] __initdata = { /* GPIO186 - Green LED */ OMAP3_MUX(SYS_CLKOUT2, OMAP_MUX_MODE4 | OMAP_PIN_OUTPUT), @@ -289,11 +286,14 @@ static struct omap_board_mux board_mux[] __initdata = { { .reg_offset = OMAP_MUX_TERMINATOR }, }; +#endif static void __init cm_t3517_init(void) { omap3_mux_init(board_mux, OMAP_PACKAGE_CBB); omap_serial_init(); + omap_board_config = cm_t3517_config; + omap_board_config_size = ARRAY_SIZE(cm_t3517_config); cm_t3517_init_leds(); cm_t3517_init_nand(); cm_t3517_init_rtc(); @@ -303,9 +303,10 @@ static void __init cm_t3517_init(void) MACHINE_START(CM_T3517, "Compulab CM-T3517") .boot_params = 0x80000100, - .map_io = omap3_map_io, .reserve = omap_reserve, - .init_irq = cm_t3517_init_irq, + .map_io = omap3_map_io, + .init_early = cm_t3517_init_early, + .init_irq = omap_init_irq, .init_machine = cm_t3517_init, .timer = &omap_timer, MACHINE_END diff --git a/arch/arm/mach-omap2/board-devkit8000.c b/arch/arm/mach-omap2/board-devkit8000.c index bc0141b9869..aa27483c493 100644 --- a/arch/arm/mach-omap2/board-devkit8000.c +++ b/arch/arm/mach-omap2/board-devkit8000.c @@ -140,7 +140,7 @@ static void devkit8000_panel_disable_dvi(struct omap_dss_device *dssdev) } static struct regulator_consumer_supply devkit8000_vmmc1_supply = - REGULATOR_SUPPLY("vmmc", "mmci-omap-hs.0"); + REGULATOR_SUPPLY("vmmc", "omap_hsmmc.0"); /* ads7846 on SPI */ @@ -195,14 +195,6 @@ static struct omap_dss_board_info devkit8000_dss_data = { .default_device = &devkit8000_lcd_device, }; -static struct platform_device devkit8000_dss_device = { - .name = "omapdss", - .id = -1, - .dev = { - .platform_data = &devkit8000_dss_data, - }, -}; - static struct regulator_consumer_supply devkit8000_vdda_dac_supply = REGULATOR_SUPPLY("vdda_dac", "omapdss"); @@ -350,9 +342,7 @@ static struct twl4030_usb_data devkit8000_usb_data = { .usb_mode = T2_USB_MODE_ULPI, }; -static struct twl4030_codec_audio_data devkit8000_audio_data = { - .audio_mclk = 26000000, -}; +static struct twl4030_codec_audio_data devkit8000_audio_data; static struct twl4030_codec_data devkit8000_codec_data = { .audio_mclk = 26000000, @@ -456,11 +446,15 @@ static struct platform_device keys_gpio = { }; -static void __init devkit8000_init_irq(void) +static void __init devkit8000_init_early(void) { omap2_init_common_infrastructure(); omap2_init_common_devices(mt46h32m32lf6_sdrc_params, mt46h32m32lf6_sdrc_params); +} + +static void __init devkit8000_init_irq(void) +{ omap_init_irq(); #ifdef CONFIG_OMAP_32K_TIMER omap2_gp_clockevent_set_gptimer(12); @@ -575,7 +569,6 @@ static void __init omap_dm9000_init(void) } static struct platform_device *devkit8000_devices[] __initdata = { - &devkit8000_dss_device, &leds_gpio, &keys_gpio, &omap_dm9000_dev, @@ -632,6 +625,7 @@ static const struct usbhs_omap_board_data usbhs_bdata __initconst = { .reset_gpio_port[2] = -EINVAL }; +#ifdef CONFIG_OMAP_MUX static struct omap_board_mux board_mux[] __initdata = { /* nCS and IRQ for Devkit8000 ethernet */ OMAP3_MUX(GPMC_NCS6, OMAP_MUX_MODE0), @@ -785,6 +779,7 @@ static struct omap_board_mux board_mux[] __initdata = { { .reg_offset = OMAP_MUX_TERMINATOR }, }; +#endif static void __init devkit8000_init(void) { @@ -797,6 +792,7 @@ static void __init devkit8000_init(void) platform_add_devices(devkit8000_devices, ARRAY_SIZE(devkit8000_devices)); + omap_display_init(&devkit8000_dss_data); spi_register_board_info(devkit8000_spi_board_info, ARRAY_SIZE(devkit8000_spi_board_info)); @@ -813,8 +809,9 @@ static void __init devkit8000_init(void) MACHINE_START(DEVKIT8000, "OMAP3 Devkit8000") .boot_params = 0x80000100, - .map_io = omap3_map_io, .reserve = omap_reserve, + .map_io = omap3_map_io, + .init_early = devkit8000_init_early, .init_irq = devkit8000_init_irq, .init_machine = devkit8000_init, .timer = &omap_timer, diff --git a/arch/arm/mach-omap2/board-flash.c b/arch/arm/mach-omap2/board-flash.c index fd38c05bb47..729892fdcf2 100644 --- a/arch/arm/mach-omap2/board-flash.c +++ b/arch/arm/mach-omap2/board-flash.c @@ -1,5 +1,5 @@ /* - * board-sdp-flash.c + * board-flash.c * Modified from mach-omap2/board-3430sdp-flash.c * * Copyright (C) 2009 Nokia Corporation @@ -16,6 +16,7 @@ #include <linux/platform_device.h> #include <linux/mtd/physmap.h> #include <linux/io.h> +#include <plat/irqs.h> #include <plat/gpmc.h> #include <plat/nand.h> @@ -73,11 +74,11 @@ __init board_nor_init(struct mtd_partition *nor_parts, u8 nr_parts, u8 cs) + FLASH_SIZE_SDPV1 - 1; } if (err < 0) { - printk(KERN_ERR "NOR: Can't request GPMC CS\n"); + pr_err("NOR: Can't request GPMC CS\n"); return; } if (platform_device_register(&board_nor_device) < 0) - printk(KERN_ERR "Unable to register NOR device\n"); + pr_err("Unable to register NOR device\n"); } #if defined(CONFIG_MTD_ONENAND_OMAP2) || \ @@ -139,17 +140,21 @@ static struct omap_nand_platform_data board_nand_data = { }; void -__init board_nand_init(struct mtd_partition *nand_parts, u8 nr_parts, u8 cs) +__init board_nand_init(struct mtd_partition *nand_parts, + u8 nr_parts, u8 cs, int nand_type) { board_nand_data.cs = cs; board_nand_data.parts = nand_parts; - board_nand_data.nr_parts = nr_parts; + board_nand_data.nr_parts = nr_parts; + board_nand_data.devsize = nand_type; + board_nand_data.ecc_opt = OMAP_ECC_HAMMING_CODE_DEFAULT; + board_nand_data.gpmc_irq = OMAP_GPMC_IRQ_BASE + cs; gpmc_nand_init(&board_nand_data); } #else void -__init board_nand_init(struct mtd_partition *nand_parts, u8 nr_parts, u8 cs) +__init board_nand_init(struct mtd_partition *nand_parts, u8 nr_parts, u8 cs, int nand_type) { } #endif /* CONFIG_MTD_NAND_OMAP2 || CONFIG_MTD_NAND_OMAP2_MODULE */ @@ -189,12 +194,12 @@ unmap: } /** - * sdp3430_flash_init - Identify devices connected to GPMC and register. + * board_flash_init - Identify devices connected to GPMC and register. * * @return - void. */ void board_flash_init(struct flash_partitions partition_info[], - char chip_sel_board[][GPMC_CS_NUM]) + char chip_sel_board[][GPMC_CS_NUM], int nand_type) { u8 cs = 0; u8 norcs = GPMC_CS_NUM + 1; @@ -208,7 +213,7 @@ void board_flash_init(struct flash_partitions partition_info[], */ idx = get_gpmc0_type(); if (idx >= MAX_SUPPORTED_GPMC_CONFIG) { - printk(KERN_ERR "%s: Invalid chip select: %d\n", __func__, cs); + pr_err("%s: Invalid chip select: %d\n", __func__, cs); return; } config_sel = (unsigned char *)(chip_sel_board[idx]); @@ -232,23 +237,20 @@ void board_flash_init(struct flash_partitions partition_info[], } if (norcs > GPMC_CS_NUM) - printk(KERN_INFO "NOR: Unable to find configuration " - "in GPMC\n"); + pr_err("NOR: Unable to find configuration in GPMC\n"); else board_nor_init(partition_info[0].parts, partition_info[0].nr_parts, norcs); if (onenandcs > GPMC_CS_NUM) - printk(KERN_INFO "OneNAND: Unable to find configuration " - "in GPMC\n"); + pr_err("OneNAND: Unable to find configuration in GPMC\n"); else board_onenand_init(partition_info[1].parts, partition_info[1].nr_parts, onenandcs); if (nandcs > GPMC_CS_NUM) - printk(KERN_INFO "NAND: Unable to find configuration " - "in GPMC\n"); + pr_err("NAND: Unable to find configuration in GPMC\n"); else board_nand_init(partition_info[2].parts, - partition_info[2].nr_parts, nandcs); + partition_info[2].nr_parts, nandcs, nand_type); } diff --git a/arch/arm/mach-omap2/board-flash.h b/arch/arm/mach-omap2/board-flash.h index 69befe00dd2..c240a3f8d16 100644 --- a/arch/arm/mach-omap2/board-flash.h +++ b/arch/arm/mach-omap2/board-flash.h @@ -25,6 +25,6 @@ struct flash_partitions { }; extern void board_flash_init(struct flash_partitions [], - char chip_sel[][GPMC_CS_NUM]); + char chip_sel[][GPMC_CS_NUM], int nand_type); extern void board_nand_init(struct mtd_partition *nand_parts, - u8 nr_parts, u8 cs); + u8 nr_parts, u8 cs, int nand_type); diff --git a/arch/arm/mach-omap2/board-generic.c b/arch/arm/mach-omap2/board-generic.c index 0e3d81e09f8..73e3c31e850 100644 --- a/arch/arm/mach-omap2/board-generic.c +++ b/arch/arm/mach-omap2/board-generic.c @@ -33,18 +33,17 @@ static struct omap_board_config_kernel generic_config[] = { }; -static void __init omap_generic_init_irq(void) +static void __init omap_generic_init_early(void) { - omap_board_config = generic_config; - omap_board_config_size = ARRAY_SIZE(generic_config); omap2_init_common_infrastructure(); omap2_init_common_devices(NULL, NULL); - omap_init_irq(); } static void __init omap_generic_init(void) { omap_serial_init(); + omap_board_config = generic_config; + omap_board_config_size = ARRAY_SIZE(generic_config); } static void __init omap_generic_map_io(void) @@ -68,9 +67,10 @@ static void __init omap_generic_map_io(void) MACHINE_START(OMAP_GENERIC, "Generic OMAP24xx") /* Maintainer: Paul Mundt <paul.mundt@nokia.com> */ .boot_params = 0x80000100, - .map_io = omap_generic_map_io, .reserve = omap_reserve, - .init_irq = omap_generic_init_irq, + .map_io = omap_generic_map_io, + .init_early = omap_generic_init_early, + .init_irq = omap_init_irq, .init_machine = omap_generic_init, .timer = &omap_timer, MACHINE_END diff --git a/arch/arm/mach-omap2/board-h4.c b/arch/arm/mach-omap2/board-h4.c index 25cc9dad4b0..bac7933b8cb 100644 --- a/arch/arm/mach-omap2/board-h4.c +++ b/arch/arm/mach-omap2/board-h4.c @@ -290,14 +290,15 @@ static struct omap_board_config_kernel h4_config[] __initdata = { { OMAP_TAG_LCD, &h4_lcd_config }, }; -static void __init omap_h4_init_irq(void) +static void __init omap_h4_init_early(void) { - omap_board_config = h4_config; - omap_board_config_size = ARRAY_SIZE(h4_config); omap2_init_common_infrastructure(); omap2_init_common_devices(NULL, NULL); +} + +static void __init omap_h4_init_irq(void) +{ omap_init_irq(); - h4_init_flash(); } static struct at24_platform_data m24c01 = { @@ -330,6 +331,9 @@ static void __init omap_h4_init(void) { omap2420_mux_init(board_mux, OMAP_PACKAGE_ZAF); + omap_board_config = h4_config; + omap_board_config_size = ARRAY_SIZE(h4_config); + /* * Make sure the serial ports are muxed on at this point. * You have to mux them off in device drivers later on @@ -367,6 +371,7 @@ static void __init omap_h4_init(void) platform_add_devices(h4_devices, ARRAY_SIZE(h4_devices)); omap2_usbfs_init(&h4_usb_config); omap_serial_init(); + h4_init_flash(); } static void __init omap_h4_map_io(void) @@ -378,8 +383,9 @@ static void __init omap_h4_map_io(void) MACHINE_START(OMAP_H4, "OMAP2420 H4 board") /* Maintainer: Paul Mundt <paul.mundt@nokia.com> */ .boot_params = 0x80000100, - .map_io = omap_h4_map_io, .reserve = omap_reserve, + .map_io = omap_h4_map_io, + .init_early = omap_h4_init_early, .init_irq = omap_h4_init_irq, .init_machine = omap_h4_init, .timer = &omap_timer, diff --git a/arch/arm/mach-omap2/board-igep0020.c b/arch/arm/mach-omap2/board-igep0020.c index f9f53441931..d3199b4ecdb 100644 --- a/arch/arm/mach-omap2/board-igep0020.c +++ b/arch/arm/mach-omap2/board-igep0020.c @@ -250,7 +250,7 @@ static inline void __init igep2_init_smsc911x(void) { } #endif static struct regulator_consumer_supply igep2_vmmc1_supply = - REGULATOR_SUPPLY("vmmc", "mmci-omap-hs.0"); + REGULATOR_SUPPLY("vmmc", "omap_hsmmc.0"); /* VMMC1 for OMAP VDD_MMC1 (i/o) and MMC1 card */ static struct regulator_init_data igep2_vmmc1 = { @@ -268,7 +268,7 @@ static struct regulator_init_data igep2_vmmc1 = { }; static struct regulator_consumer_supply igep2_vio_supply = - REGULATOR_SUPPLY("vmmc_aux", "mmci-omap-hs.1"); + REGULATOR_SUPPLY("vmmc_aux", "omap_hsmmc.1"); static struct regulator_init_data igep2_vio = { .constraints = { @@ -286,7 +286,7 @@ static struct regulator_init_data igep2_vio = { }; static struct regulator_consumer_supply igep2_vmmc2_supply = - REGULATOR_SUPPLY("vmmc", "mmci-omap-hs.1"); + REGULATOR_SUPPLY("vmmc", "omap_hsmmc.1"); static struct regulator_init_data igep2_vmmc2 = { .constraints = { @@ -485,18 +485,8 @@ static struct omap_dss_board_info igep2_dss_data = { .default_device = &igep2_dvi_device, }; -static struct platform_device igep2_dss_device = { - .name = "omapdss", - .id = -1, - .dev = { - .platform_data = &igep2_dss_data, - }, -}; - -static struct regulator_consumer_supply igep2_vpll2_supply = { - .supply = "vdds_dsi", - .dev = &igep2_dss_device.dev, -}; +static struct regulator_consumer_supply igep2_vpll2_supply = + REGULATOR_SUPPLY("vdds_dsi", "omapdss"); static struct regulator_init_data igep2_vpll2 = { .constraints = { @@ -521,21 +511,17 @@ static void __init igep2_display_init(void) } static struct platform_device *igep2_devices[] __initdata = { - &igep2_dss_device, &igep2_vwlan_device, }; -static void __init igep2_init_irq(void) +static void __init igep2_init_early(void) { omap2_init_common_infrastructure(); omap2_init_common_devices(m65kxxxxam_sdrc_params, m65kxxxxam_sdrc_params); - omap_init_irq(); } -static struct twl4030_codec_audio_data igep2_audio_data = { - .audio_mclk = 26000000, -}; +static struct twl4030_codec_audio_data igep2_audio_data; static struct twl4030_codec_data igep2_codec_data = { .audio_mclk = 26000000, @@ -697,6 +683,7 @@ static void __init igep2_init(void) /* Register I2C busses and drivers */ igep2_i2c_init(); platform_add_devices(igep2_devices, ARRAY_SIZE(igep2_devices)); + omap_display_init(&igep2_dss_data); omap_serial_init(); usb_musb_init(&musb_board_data); usbhs_init(&usbhs_bdata); @@ -716,9 +703,10 @@ static void __init igep2_init(void) MACHINE_START(IGEP0020, "IGEP v2 board") .boot_params = 0x80000100, - .map_io = omap3_map_io, .reserve = omap_reserve, - .init_irq = igep2_init_irq, + .map_io = omap3_map_io, + .init_early = igep2_init_early, + .init_irq = omap_init_irq, .init_machine = igep2_init, .timer = &omap_timer, MACHINE_END diff --git a/arch/arm/mach-omap2/board-igep0030.c b/arch/arm/mach-omap2/board-igep0030.c index 579fc2d2525..b10db0e6ee6 100644 --- a/arch/arm/mach-omap2/board-igep0030.c +++ b/arch/arm/mach-omap2/board-igep0030.c @@ -142,7 +142,7 @@ static void __init igep3_flash_init(void) {} #endif static struct regulator_consumer_supply igep3_vmmc1_supply = - REGULATOR_SUPPLY("vmmc", "mmci-omap-hs.0"); + REGULATOR_SUPPLY("vmmc", "omap_hsmmc.0"); /* VMMC1 for OMAP VDD_MMC1 (i/o) and MMC1 card */ static struct regulator_init_data igep3_vmmc1 = { @@ -160,7 +160,7 @@ static struct regulator_init_data igep3_vmmc1 = { }; static struct regulator_consumer_supply igep3_vio_supply = - REGULATOR_SUPPLY("vmmc_aux", "mmci-omap-hs.1"); + REGULATOR_SUPPLY("vmmc_aux", "omap_hsmmc.1"); static struct regulator_init_data igep3_vio = { .constraints = { @@ -178,7 +178,7 @@ static struct regulator_init_data igep3_vio = { }; static struct regulator_consumer_supply igep3_vmmc2_supply = - REGULATOR_SUPPLY("vmmc", "mmci-omap-hs.1"); + REGULATOR_SUPPLY("vmmc", "omap_hsmmc.1"); static struct regulator_init_data igep3_vmmc2 = { .constraints = { @@ -331,12 +331,11 @@ static struct platform_device *igep3_devices[] __initdata = { &igep3_vwlan_device, }; -static void __init igep3_init_irq(void) +static void __init igep3_init_early(void) { omap2_init_common_infrastructure(); omap2_init_common_devices(m65kxxxxam_sdrc_params, m65kxxxxam_sdrc_params); - omap_init_irq(); } static struct twl4030_platform_data igep3_twl4030_pdata = { @@ -452,7 +451,8 @@ MACHINE_START(IGEP0030, "IGEP OMAP3 module") .boot_params = 0x80000100, .reserve = omap_reserve, .map_io = omap3_map_io, - .init_irq = igep3_init_irq, + .init_early = igep3_init_early, + .init_irq = omap_init_irq, .init_machine = igep3_init, .timer = &omap_timer, MACHINE_END diff --git a/arch/arm/mach-omap2/board-ldp.c b/arch/arm/mach-omap2/board-ldp.c index e5dc74875f9..e2ba77957a8 100644 --- a/arch/arm/mach-omap2/board-ldp.c +++ b/arch/arm/mach-omap2/board-ldp.c @@ -288,13 +288,10 @@ static struct omap_board_config_kernel ldp_config[] __initdata = { { OMAP_TAG_LCD, &ldp_lcd_config }, }; -static void __init omap_ldp_init_irq(void) +static void __init omap_ldp_init_early(void) { - omap_board_config = ldp_config; - omap_board_config_size = ARRAY_SIZE(ldp_config); omap2_init_common_infrastructure(); omap2_init_common_devices(NULL, NULL); - omap_init_irq(); } static struct twl4030_usb_data ldp_usb_data = { @@ -330,6 +327,26 @@ static struct regulator_init_data ldp_vmmc1 = { .consumer_supplies = &ldp_vmmc1_supply, }; +/* ads7846 on SPI */ +static struct regulator_consumer_supply ldp_vaux1_supplies[] = { + REGULATOR_SUPPLY("vcc", "spi1.0"), +}; + +/* VAUX1 */ +static struct regulator_init_data ldp_vaux1 = { + .constraints = { + .min_uV = 3000000, + .max_uV = 3000000, + .apply_uV = true, + .valid_modes_mask = REGULATOR_MODE_NORMAL + | REGULATOR_MODE_STANDBY, + .valid_ops_mask = REGULATOR_CHANGE_MODE + | REGULATOR_CHANGE_STATUS, + }, + .num_consumer_supplies = ARRAY_SIZE(ldp_vaux1_supplies), + .consumer_supplies = ldp_vaux1_supplies, +}; + static struct twl4030_platform_data ldp_twldata = { .irq_base = TWL4030_IRQ_BASE, .irq_end = TWL4030_IRQ_END, @@ -338,6 +355,7 @@ static struct twl4030_platform_data ldp_twldata = { .madc = &ldp_madc_data, .usb = &ldp_usb_data, .vmmc1 = &ldp_vmmc1, + .vaux1 = &ldp_vaux1, .gpio = &ldp_gpio_data, .keypad = &ldp_kp_twl4030_data, }; @@ -423,6 +441,8 @@ static struct mtd_partition ldp_nand_partitions[] = { static void __init omap_ldp_init(void) { omap3_mux_init(board_mux, OMAP_PACKAGE_CBB); + omap_board_config = ldp_config; + omap_board_config_size = ARRAY_SIZE(ldp_config); ldp_init_smsc911x(); omap_i2c_init(); platform_add_devices(ldp_devices, ARRAY_SIZE(ldp_devices)); @@ -434,7 +454,7 @@ static void __init omap_ldp_init(void) omap_serial_init(); usb_musb_init(&musb_board_data); board_nand_init(ldp_nand_partitions, - ARRAY_SIZE(ldp_nand_partitions), ZOOM_NAND_CS); + ARRAY_SIZE(ldp_nand_partitions), ZOOM_NAND_CS, 0); omap2_hsmmc_init(mmc); /* link regulators to MMC adapters */ @@ -443,9 +463,10 @@ static void __init omap_ldp_init(void) MACHINE_START(OMAP_LDP, "OMAP LDP board") .boot_params = 0x80000100, - .map_io = omap3_map_io, .reserve = omap_reserve, - .init_irq = omap_ldp_init_irq, + .map_io = omap3_map_io, + .init_early = omap_ldp_init_early, + .init_irq = omap_init_irq, .init_machine = omap_ldp_init, .timer = &omap_timer, MACHINE_END diff --git a/arch/arm/mach-omap2/board-n8x0.c b/arch/arm/mach-omap2/board-n8x0.c index f396756872b..e710cd9e079 100644 --- a/arch/arm/mach-omap2/board-n8x0.c +++ b/arch/arm/mach-omap2/board-n8x0.c @@ -536,7 +536,7 @@ static void __init n8x0_mmc_init(void) } mmc_data[0] = &mmc1_data; - omap2_init_mmc(mmc_data, OMAP24XX_NR_MMC); + omap242x_init_mmc(mmc_data); } #else @@ -628,11 +628,10 @@ static void __init n8x0_map_io(void) omap242x_map_common_io(); } -static void __init n8x0_init_irq(void) +static void __init n8x0_init_early(void) { omap2_init_common_infrastructure(); omap2_init_common_devices(NULL, NULL); - omap_init_irq(); } #ifdef CONFIG_OMAP_MUX @@ -703,27 +702,30 @@ static void __init n8x0_init_machine(void) MACHINE_START(NOKIA_N800, "Nokia N800") .boot_params = 0x80000100, - .map_io = n8x0_map_io, .reserve = omap_reserve, - .init_irq = n8x0_init_irq, + .map_io = n8x0_map_io, + .init_early = n8x0_init_early, + .init_irq = omap_init_irq, .init_machine = n8x0_init_machine, .timer = &omap_timer, MACHINE_END MACHINE_START(NOKIA_N810, "Nokia N810") .boot_params = 0x80000100, - .map_io = n8x0_map_io, .reserve = omap_reserve, - .init_irq = n8x0_init_irq, + .map_io = n8x0_map_io, + .init_early = n8x0_init_early, + .init_irq = omap_init_irq, .init_machine = n8x0_init_machine, .timer = &omap_timer, MACHINE_END MACHINE_START(NOKIA_N810_WIMAX, "Nokia N810 WiMAX") .boot_params = 0x80000100, - .map_io = n8x0_map_io, .reserve = omap_reserve, - .init_irq = n8x0_init_irq, + .map_io = n8x0_map_io, + .init_early = n8x0_init_early, + .init_irq = omap_init_irq, .init_machine = n8x0_init_machine, .timer = &omap_timer, MACHINE_END diff --git a/arch/arm/mach-omap2/board-omap3beagle.c b/arch/arm/mach-omap2/board-omap3beagle.c index f0963b6e462..7640c054f43 100644 --- a/arch/arm/mach-omap2/board-omap3beagle.c +++ b/arch/arm/mach-omap2/board-omap3beagle.c @@ -23,6 +23,7 @@ #include <linux/gpio.h> #include <linux/input.h> #include <linux/gpio_keys.h> +#include <linux/opp.h> #include <linux/mtd/mtd.h> #include <linux/mtd/partitions.h> @@ -45,10 +46,12 @@ #include <plat/gpmc.h> #include <plat/nand.h> #include <plat/usb.h> +#include <plat/omap_device.h> #include "mux.h" #include "hsmmc.h" #include "timer-gp.h" +#include "pm.h" #define NAND_BLOCK_SIZE SZ_128K @@ -228,14 +231,6 @@ static struct omap_dss_board_info beagle_dss_data = { .default_device = &beagle_dvi_device, }; -static struct platform_device beagle_dss_device = { - .name = "omapdss", - .id = -1, - .dev = { - .platform_data = &beagle_dss_data, - }, -}; - static struct regulator_consumer_supply beagle_vdac_supply = REGULATOR_SUPPLY("vdda_dac", "omapdss"); @@ -435,9 +430,7 @@ static struct twl4030_usb_data beagle_usb_data = { .usb_mode = T2_USB_MODE_ULPI, }; -static struct twl4030_codec_audio_data beagle_audio_data = { - .audio_mclk = 26000000, -}; +static struct twl4030_codec_audio_data beagle_audio_data; static struct twl4030_codec_data beagle_codec_data = { .audio_mclk = 26000000, @@ -536,11 +529,15 @@ static struct platform_device keys_gpio = { }, }; -static void __init omap3_beagle_init_irq(void) +static void __init omap3_beagle_init_early(void) { omap2_init_common_infrastructure(); omap2_init_common_devices(mt46h32m32lf6_sdrc_params, mt46h32m32lf6_sdrc_params); +} + +static void __init omap3_beagle_init_irq(void) +{ omap_init_irq(); #ifdef CONFIG_OMAP_32K_TIMER omap2_gp_clockevent_set_gptimer(12); @@ -550,7 +547,6 @@ static void __init omap3_beagle_init_irq(void) static struct platform_device *omap3_beagle_devices[] __initdata = { &leds_gpio, &keys_gpio, - &beagle_dss_device, }; static void __init omap3beagle_flash_init(void) @@ -610,6 +606,52 @@ static struct omap_musb_board_data musb_board_data = { .power = 100, }; +static void __init beagle_opp_init(void) +{ + int r = 0; + + /* Initialize the omap3 opp table */ + if (omap3_opp_init()) { + pr_err("%s: opp default init failed\n", __func__); + return; + } + + /* Custom OPP enabled for XM */ + if (omap3_beagle_get_rev() == OMAP3BEAGLE_BOARD_XM) { + struct omap_hwmod *mh = omap_hwmod_lookup("mpu"); + struct omap_hwmod *dh = omap_hwmod_lookup("iva"); + struct device *dev; + + if (!mh || !dh) { + pr_err("%s: Aiee.. no mpu/dsp devices? %p %p\n", + __func__, mh, dh); + return; + } + /* Enable MPU 1GHz and lower opps */ + dev = &mh->od->pdev.dev; + r = opp_enable(dev, 800000000); + /* TODO: MPU 1GHz needs SR and ABB */ + + /* Enable IVA 800MHz and lower opps */ + dev = &dh->od->pdev.dev; + r |= opp_enable(dev, 660000000); + /* TODO: DSP 800MHz needs SR and ABB */ + if (r) { + pr_err("%s: failed to enable higher opp %d\n", + __func__, r); + /* + * Cleanup - disable the higher freqs - we dont care + * about the results + */ + dev = &mh->od->pdev.dev; + opp_disable(dev, 800000000); + dev = &dh->od->pdev.dev; + opp_disable(dev, 660000000); + } + } + return; +} + static void __init omap3_beagle_init(void) { omap3_mux_init(board_mux, OMAP_PACKAGE_CBB); @@ -617,6 +659,7 @@ static void __init omap3_beagle_init(void) omap3_beagle_i2c_init(); platform_add_devices(omap3_beagle_devices, ARRAY_SIZE(omap3_beagle_devices)); + omap_display_init(&beagle_dss_data); omap_serial_init(); omap_mux_init_gpio(170, OMAP_PIN_INPUT); @@ -633,13 +676,15 @@ static void __init omap3_beagle_init(void) omap_mux_init_signal("sdrc_cke1", OMAP_PIN_OUTPUT); beagle_display_init(); + beagle_opp_init(); } MACHINE_START(OMAP3_BEAGLE, "OMAP3 Beagle Board") /* Maintainer: Syed Mohammed Khasim - http://beagleboard.org */ .boot_params = 0x80000100, - .map_io = omap3_map_io, .reserve = omap_reserve, + .map_io = omap3_map_io, + .init_early = omap3_beagle_init_early, .init_irq = omap3_beagle_init_irq, .init_machine = omap3_beagle_init, .timer = &omap_timer, diff --git a/arch/arm/mach-omap2/board-omap3evm.c b/arch/arm/mach-omap2/board-omap3evm.c index 38a2d91790c..0fa2c7b208b 100644 --- a/arch/arm/mach-omap2/board-omap3evm.c +++ b/arch/arm/mach-omap2/board-omap3evm.c @@ -30,6 +30,8 @@ #include <linux/usb/otg.h> #include <linux/smsc911x.h> +#include <linux/wl12xx.h> +#include <linux/regulator/fixed.h> #include <linux/regulator/machine.h> #include <linux/mmc/host.h> @@ -58,6 +60,13 @@ #define OMAP3EVM_ETHR_ID_REV 0x50 #define OMAP3EVM_ETHR_GPIO_IRQ 176 #define OMAP3EVM_SMSC911X_CS 5 +/* + * Eth Reset signal + * 64 = Generation 1 (<=RevD) + * 7 = Generation 2 (>=RevE) + */ +#define OMAP3EVM_GEN1_ETHR_GPIO_RST 64 +#define OMAP3EVM_GEN2_ETHR_GPIO_RST 7 static u8 omap3_evm_version; @@ -124,10 +133,15 @@ static struct platform_device omap3evm_smsc911x_device = { static inline void __init omap3evm_init_smsc911x(void) { - int eth_cs; + int eth_cs, eth_rst; struct clk *l3ck; unsigned int rate; + if (get_omap3_evm_rev() == OMAP3EVM_BOARD_GEN_1) + eth_rst = OMAP3EVM_GEN1_ETHR_GPIO_RST; + else + eth_rst = OMAP3EVM_GEN2_ETHR_GPIO_RST; + eth_cs = OMAP3EVM_SMSC911X_CS; l3ck = clk_get(NULL, "l3_ck"); @@ -136,6 +150,27 @@ static inline void __init omap3evm_init_smsc911x(void) else rate = clk_get_rate(l3ck); + /* Configure ethernet controller reset gpio */ + if (cpu_is_omap3430()) { + if (gpio_request(eth_rst, "SMSC911x gpio") < 0) { + pr_err(KERN_ERR "Failed to request %d for smsc911x\n", + eth_rst); + return; + } + + if (gpio_direction_output(eth_rst, 1) < 0) { + pr_err(KERN_ERR "Failed to set direction of %d for" \ + " smsc911x\n", eth_rst); + return; + } + /* reset pulse to ethernet controller*/ + usleep_range(150, 220); + gpio_set_value(eth_rst, 0); + usleep_range(150, 220); + gpio_set_value(eth_rst, 1); + usleep_range(1, 2); + } + if (gpio_request(OMAP3EVM_ETHR_GPIO_IRQ, "SMSC911x irq") < 0) { printk(KERN_ERR "Failed to request GPIO%d for smsc911x IRQ\n", OMAP3EVM_ETHR_GPIO_IRQ); @@ -235,9 +270,9 @@ static int omap3_evm_enable_lcd(struct omap_dss_device *dssdev) gpio_set_value(OMAP3EVM_LCD_PANEL_ENVDD, 0); if (get_omap3_evm_rev() >= OMAP3EVM_BOARD_GEN_2) - gpio_set_value(OMAP3EVM_LCD_PANEL_BKLIGHT_GPIO, 0); + gpio_set_value_cansleep(OMAP3EVM_LCD_PANEL_BKLIGHT_GPIO, 0); else - gpio_set_value(OMAP3EVM_LCD_PANEL_BKLIGHT_GPIO, 1); + gpio_set_value_cansleep(OMAP3EVM_LCD_PANEL_BKLIGHT_GPIO, 1); lcd_enabled = 1; return 0; @@ -248,9 +283,9 @@ static void omap3_evm_disable_lcd(struct omap_dss_device *dssdev) gpio_set_value(OMAP3EVM_LCD_PANEL_ENVDD, 1); if (get_omap3_evm_rev() >= OMAP3EVM_BOARD_GEN_2) - gpio_set_value(OMAP3EVM_LCD_PANEL_BKLIGHT_GPIO, 1); + gpio_set_value_cansleep(OMAP3EVM_LCD_PANEL_BKLIGHT_GPIO, 1); else - gpio_set_value(OMAP3EVM_LCD_PANEL_BKLIGHT_GPIO, 0); + gpio_set_value_cansleep(OMAP3EVM_LCD_PANEL_BKLIGHT_GPIO, 0); lcd_enabled = 0; } @@ -289,7 +324,7 @@ static int omap3_evm_enable_dvi(struct omap_dss_device *dssdev) return -EINVAL; } - gpio_set_value(OMAP3EVM_DVI_PANEL_EN_GPIO, 1); + gpio_set_value_cansleep(OMAP3EVM_DVI_PANEL_EN_GPIO, 1); dvi_enabled = 1; return 0; @@ -297,7 +332,7 @@ static int omap3_evm_enable_dvi(struct omap_dss_device *dssdev) static void omap3_evm_disable_dvi(struct omap_dss_device *dssdev) { - gpio_set_value(OMAP3EVM_DVI_PANEL_EN_GPIO, 0); + gpio_set_value_cansleep(OMAP3EVM_DVI_PANEL_EN_GPIO, 0); dvi_enabled = 0; } @@ -328,14 +363,6 @@ static struct omap_dss_board_info omap3_evm_dss_data = { .default_device = &omap3_evm_lcd_device, }; -static struct platform_device omap3_evm_dss_device = { - .name = "omapdss", - .id = -1, - .dev = { - .platform_data = &omap3_evm_dss_data, - }, -}; - static struct regulator_consumer_supply omap3evm_vmmc1_supply = { .supply = "vmmc", }; @@ -381,6 +408,16 @@ static struct omap2_hsmmc_info mmc[] = { .gpio_cd = -EINVAL, .gpio_wp = 63, }, +#ifdef CONFIG_WL12XX_PLATFORM_DATA + { + .name = "wl1271", + .mmc = 2, + .caps = MMC_CAP_4_BIT_DATA | MMC_CAP_POWER_OFF_CARD, + .gpio_wp = -EINVAL, + .gpio_cd = -EINVAL, + .nonremovable = true, + }, +#endif {} /* Terminator */ }; @@ -411,6 +448,8 @@ static struct platform_device leds_gpio = { static int omap3evm_twl_gpio_setup(struct device *dev, unsigned gpio, unsigned ngpio) { + int r; + /* gpio + 0 is "mmc0_cd" (input/IRQ) */ omap_mux_init_gpio(63, OMAP_PIN_INPUT); mmc[0].gpio_cd = gpio + 0; @@ -426,8 +465,12 @@ static int omap3evm_twl_gpio_setup(struct device *dev, */ /* TWL4030_GPIO_MAX + 0 == ledA, LCD Backlight control */ - gpio_request(gpio + TWL4030_GPIO_MAX, "EN_LCD_BKL"); - gpio_direction_output(gpio + TWL4030_GPIO_MAX, 0); + r = gpio_request(gpio + TWL4030_GPIO_MAX, "EN_LCD_BKL"); + if (!r) + r = gpio_direction_output(gpio + TWL4030_GPIO_MAX, + (get_omap3_evm_rev() >= OMAP3EVM_BOARD_GEN_2) ? 1 : 0); + if (r) + printk(KERN_ERR "failed to get/set lcd_bkl gpio\n"); /* gpio + 7 == DVI Enable */ gpio_request(gpio + 7, "EN_DVI"); @@ -491,19 +534,15 @@ static struct twl4030_madc_platform_data omap3evm_madc_data = { .irq_line = 1, }; -static struct twl4030_codec_audio_data omap3evm_audio_data = { - .audio_mclk = 26000000, -}; +static struct twl4030_codec_audio_data omap3evm_audio_data; static struct twl4030_codec_data omap3evm_codec_data = { .audio_mclk = 26000000, .audio = &omap3evm_audio_data, }; -static struct regulator_consumer_supply omap3_evm_vdda_dac_supply = { - .supply = "vdda_dac", - .dev = &omap3_evm_dss_device.dev, -}; +static struct regulator_consumer_supply omap3_evm_vdda_dac_supply = + REGULATOR_SUPPLY("vdda_dac", "omapdss"); /* VDAC for DSS driving S-Video */ static struct regulator_init_data omap3_evm_vdac = { @@ -538,6 +577,66 @@ static struct regulator_init_data omap3_evm_vpll2 = { .consumer_supplies = &omap3_evm_vpll2_supply, }; +/* ads7846 on SPI */ +static struct regulator_consumer_supply omap3evm_vio_supply = + REGULATOR_SUPPLY("vcc", "spi1.0"); + +/* VIO for ads7846 */ +static struct regulator_init_data omap3evm_vio = { + .constraints = { + .min_uV = 1800000, + .max_uV = 1800000, + .apply_uV = true, + .valid_modes_mask = REGULATOR_MODE_NORMAL + | REGULATOR_MODE_STANDBY, + .valid_ops_mask = REGULATOR_CHANGE_MODE + | REGULATOR_CHANGE_STATUS, + }, + .num_consumer_supplies = 1, + .consumer_supplies = &omap3evm_vio_supply, +}; + +#ifdef CONFIG_WL12XX_PLATFORM_DATA + +#define OMAP3EVM_WLAN_PMENA_GPIO (150) +#define OMAP3EVM_WLAN_IRQ_GPIO (149) + +static struct regulator_consumer_supply omap3evm_vmmc2_supply = + REGULATOR_SUPPLY("vmmc", "omap_hsmmc.1"); + +/* VMMC2 for driving the WL12xx module */ +static struct regulator_init_data omap3evm_vmmc2 = { + .constraints = { + .valid_ops_mask = REGULATOR_CHANGE_STATUS, + }, + .num_consumer_supplies = 1, + .consumer_supplies = &omap3evm_vmmc2_supply, +}; + +static struct fixed_voltage_config omap3evm_vwlan = { + .supply_name = "vwl1271", + .microvolts = 1800000, /* 1.80V */ + .gpio = OMAP3EVM_WLAN_PMENA_GPIO, + .startup_delay = 70000, /* 70ms */ + .enable_high = 1, + .enabled_at_boot = 0, + .init_data = &omap3evm_vmmc2, +}; + +static struct platform_device omap3evm_wlan_regulator = { + .name = "reg-fixed-voltage", + .id = 1, + .dev = { + .platform_data = &omap3evm_vwlan, + }, +}; + +struct wl12xx_platform_data omap3evm_wlan_data __initdata = { + .irq = OMAP_GPIO_IRQ(OMAP3EVM_WLAN_IRQ_GPIO), + .board_ref_clock = WL12XX_REFCLOCK_38, /* 38.4 MHz */ +}; +#endif + static struct twl4030_platform_data omap3evm_twldata = { .irq_base = TWL4030_IRQ_BASE, .irq_end = TWL4030_IRQ_END, @@ -550,6 +649,7 @@ static struct twl4030_platform_data omap3evm_twldata = { .codec = &omap3evm_codec_data, .vdac = &omap3_evm_vdac, .vpll2 = &omap3_evm_vpll2, + .vio = &omap3evm_vio, }; static struct i2c_board_info __initdata omap3evm_i2c_boardinfo[] = { @@ -625,19 +725,12 @@ static struct spi_board_info omap3evm_spi_board_info[] = { static struct omap_board_config_kernel omap3_evm_config[] __initdata = { }; -static void __init omap3_evm_init_irq(void) +static void __init omap3_evm_init_early(void) { - omap_board_config = omap3_evm_config; - omap_board_config_size = ARRAY_SIZE(omap3_evm_config); omap2_init_common_infrastructure(); omap2_init_common_devices(mt46h32m32lf6_sdrc_params, NULL); - omap_init_irq(); } -static struct platform_device *omap3_evm_devices[] __initdata = { - &omap3_evm_dss_device, -}; - static struct usbhs_omap_board_data usbhs_bdata __initdata = { .port_mode[0] = OMAP_USBHS_PORT_MODE_UNUSED, @@ -652,14 +745,76 @@ static struct usbhs_omap_board_data usbhs_bdata __initdata = { }; #ifdef CONFIG_OMAP_MUX -static struct omap_board_mux board_mux[] __initdata = { +static struct omap_board_mux omap35x_board_mux[] __initdata = { + OMAP3_MUX(SYS_NIRQ, OMAP_MUX_MODE0 | OMAP_PIN_INPUT_PULLUP | + OMAP_PIN_OFF_INPUT_PULLUP | OMAP_PIN_OFF_OUTPUT_LOW | + OMAP_PIN_OFF_WAKEUPENABLE), + OMAP3_MUX(MCSPI1_CS1, OMAP_MUX_MODE4 | OMAP_PIN_INPUT_PULLUP | + OMAP_PIN_OFF_INPUT_PULLUP | OMAP_PIN_OFF_OUTPUT_LOW | + OMAP_PIN_OFF_WAKEUPENABLE), + OMAP3_MUX(SYS_BOOT5, OMAP_MUX_MODE4 | OMAP_PIN_INPUT_PULLUP | + OMAP_PIN_OFF_NONE), + OMAP3_MUX(GPMC_WAIT2, OMAP_MUX_MODE4 | OMAP_PIN_INPUT_PULLUP | + OMAP_PIN_OFF_NONE), +#ifdef CONFIG_WL12XX_PLATFORM_DATA + /* WLAN IRQ - GPIO 149 */ + OMAP3_MUX(UART1_RTS, OMAP_MUX_MODE4 | OMAP_PIN_INPUT), + + /* WLAN POWER ENABLE - GPIO 150 */ + OMAP3_MUX(UART1_CTS, OMAP_MUX_MODE4 | OMAP_PIN_OUTPUT), + + /* MMC2 SDIO pin muxes for WL12xx */ + OMAP3_MUX(SDMMC2_CLK, OMAP_MUX_MODE0 | OMAP_PIN_INPUT_PULLUP), + OMAP3_MUX(SDMMC2_CMD, OMAP_MUX_MODE0 | OMAP_PIN_INPUT_PULLUP), + OMAP3_MUX(SDMMC2_DAT0, OMAP_MUX_MODE0 | OMAP_PIN_INPUT_PULLUP), + OMAP3_MUX(SDMMC2_DAT1, OMAP_MUX_MODE0 | OMAP_PIN_INPUT_PULLUP), + OMAP3_MUX(SDMMC2_DAT2, OMAP_MUX_MODE0 | OMAP_PIN_INPUT_PULLUP), + OMAP3_MUX(SDMMC2_DAT3, OMAP_MUX_MODE0 | OMAP_PIN_INPUT_PULLUP), +#endif + { .reg_offset = OMAP_MUX_TERMINATOR }, +}; + +static struct omap_board_mux omap36x_board_mux[] __initdata = { OMAP3_MUX(SYS_NIRQ, OMAP_MUX_MODE0 | OMAP_PIN_INPUT_PULLUP | OMAP_PIN_OFF_INPUT_PULLUP | OMAP_PIN_OFF_OUTPUT_LOW | OMAP_PIN_OFF_WAKEUPENABLE), OMAP3_MUX(MCSPI1_CS1, OMAP_MUX_MODE4 | OMAP_PIN_INPUT_PULLUP | - OMAP_PIN_OFF_INPUT_PULLUP | OMAP_PIN_OFF_OUTPUT_LOW), + OMAP_PIN_OFF_INPUT_PULLUP | OMAP_PIN_OFF_OUTPUT_LOW | + OMAP_PIN_OFF_WAKEUPENABLE), + /* AM/DM37x EVM: DSS data bus muxed with sys_boot */ + OMAP3_MUX(DSS_DATA18, OMAP_MUX_MODE3 | OMAP_PIN_OFF_NONE), + OMAP3_MUX(DSS_DATA19, OMAP_MUX_MODE3 | OMAP_PIN_OFF_NONE), + OMAP3_MUX(DSS_DATA22, OMAP_MUX_MODE3 | OMAP_PIN_OFF_NONE), + OMAP3_MUX(DSS_DATA21, OMAP_MUX_MODE3 | OMAP_PIN_OFF_NONE), + OMAP3_MUX(DSS_DATA22, OMAP_MUX_MODE3 | OMAP_PIN_OFF_NONE), + OMAP3_MUX(DSS_DATA23, OMAP_MUX_MODE3 | OMAP_PIN_OFF_NONE), + OMAP3_MUX(SYS_BOOT0, OMAP_MUX_MODE3 | OMAP_PIN_OFF_NONE), + OMAP3_MUX(SYS_BOOT1, OMAP_MUX_MODE3 | OMAP_PIN_OFF_NONE), + OMAP3_MUX(SYS_BOOT3, OMAP_MUX_MODE3 | OMAP_PIN_OFF_NONE), + OMAP3_MUX(SYS_BOOT4, OMAP_MUX_MODE3 | OMAP_PIN_OFF_NONE), + OMAP3_MUX(SYS_BOOT5, OMAP_MUX_MODE3 | OMAP_PIN_OFF_NONE), + OMAP3_MUX(SYS_BOOT6, OMAP_MUX_MODE3 | OMAP_PIN_OFF_NONE), +#ifdef CONFIG_WL12XX_PLATFORM_DATA + /* WLAN IRQ - GPIO 149 */ + OMAP3_MUX(UART1_RTS, OMAP_MUX_MODE4 | OMAP_PIN_INPUT), + + /* WLAN POWER ENABLE - GPIO 150 */ + OMAP3_MUX(UART1_CTS, OMAP_MUX_MODE4 | OMAP_PIN_OUTPUT), + + /* MMC2 SDIO pin muxes for WL12xx */ + OMAP3_MUX(SDMMC2_CLK, OMAP_MUX_MODE0 | OMAP_PIN_INPUT_PULLUP), + OMAP3_MUX(SDMMC2_CMD, OMAP_MUX_MODE0 | OMAP_PIN_INPUT_PULLUP), + OMAP3_MUX(SDMMC2_DAT0, OMAP_MUX_MODE0 | OMAP_PIN_INPUT_PULLUP), + OMAP3_MUX(SDMMC2_DAT1, OMAP_MUX_MODE0 | OMAP_PIN_INPUT_PULLUP), + OMAP3_MUX(SDMMC2_DAT2, OMAP_MUX_MODE0 | OMAP_PIN_INPUT_PULLUP), + OMAP3_MUX(SDMMC2_DAT3, OMAP_MUX_MODE0 | OMAP_PIN_INPUT_PULLUP), +#endif + { .reg_offset = OMAP_MUX_TERMINATOR }, }; +#else +#define omap35x_board_mux NULL +#define omap36x_board_mux NULL #endif static struct omap_musb_board_data musb_board_data = { @@ -671,11 +826,18 @@ static struct omap_musb_board_data musb_board_data = { static void __init omap3_evm_init(void) { omap3_evm_get_revision(); - omap3_mux_init(board_mux, OMAP_PACKAGE_CBB); + + if (cpu_is_omap3630()) + omap3_mux_init(omap36x_board_mux, OMAP_PACKAGE_CBB); + else + omap3_mux_init(omap35x_board_mux, OMAP_PACKAGE_CBB); + + omap_board_config = omap3_evm_config; + omap_board_config_size = ARRAY_SIZE(omap3_evm_config); omap3_evm_i2c_init(); - platform_add_devices(omap3_evm_devices, ARRAY_SIZE(omap3_evm_devices)); + omap_display_init(&omap3_evm_dss_data); spi_register_board_info(omap3evm_spi_board_info, ARRAY_SIZE(omap3evm_spi_board_info)); @@ -715,14 +877,22 @@ static void __init omap3_evm_init(void) ads7846_dev_init(); omap3evm_init_smsc911x(); omap3_evm_display_init(); + +#ifdef CONFIG_WL12XX_PLATFORM_DATA + /* WL12xx WLAN Init */ + if (wl12xx_set_platform_data(&omap3evm_wlan_data)) + pr_err("error setting wl12xx data\n"); + platform_device_register(&omap3evm_wlan_regulator); +#endif } MACHINE_START(OMAP3EVM, "OMAP3 EVM") /* Maintainer: Syed Mohammed Khasim - Texas Instruments */ .boot_params = 0x80000100, - .map_io = omap3_map_io, .reserve = omap_reserve, - .init_irq = omap3_evm_init_irq, + .map_io = omap3_map_io, + .init_early = omap3_evm_init_early, + .init_irq = omap_init_irq, .init_machine = omap3_evm_init, .timer = &omap_timer, MACHINE_END diff --git a/arch/arm/mach-omap2/board-omap3logic.c b/arch/arm/mach-omap2/board-omap3logic.c index 15e4b08e99b..b726943d7c9 100644 --- a/arch/arm/mach-omap2/board-omap3logic.c +++ b/arch/arm/mach-omap2/board-omap3logic.c @@ -195,11 +195,10 @@ static inline void __init board_smsc911x_init(void) gpmc_smsc911x_init(&board_smsc911x_data); } -static void __init omap3logic_init_irq(void) +static void __init omap3logic_init_early(void) { omap2_init_common_infrastructure(); omap2_init_common_devices(NULL, NULL); - omap_init_irq(); } #ifdef CONFIG_OMAP_MUX @@ -225,7 +224,8 @@ static void __init omap3logic_init(void) MACHINE_START(OMAP3_TORPEDO, "Logic OMAP3 Torpedo board") .boot_params = 0x80000100, .map_io = omap3_map_io, - .init_irq = omap3logic_init_irq, + .init_early = omap3logic_init_early, + .init_irq = omap_init_irq, .init_machine = omap3logic_init, .timer = &omap_timer, MACHINE_END @@ -233,7 +233,8 @@ MACHINE_END MACHINE_START(OMAP3530_LV_SOM, "OMAP Logic 3530 LV SOM board") .boot_params = 0x80000100, .map_io = omap3_map_io, - .init_irq = omap3logic_init_irq, + .init_early = omap3logic_init_early, + .init_irq = omap_init_irq, .init_machine = omap3logic_init, .timer = &omap_timer, MACHINE_END diff --git a/arch/arm/mach-omap2/board-omap3pandora.c b/arch/arm/mach-omap2/board-omap3pandora.c index aa05f2e46a6..2e5dc21e347 100644 --- a/arch/arm/mach-omap2/board-omap3pandora.c +++ b/arch/arm/mach-omap2/board-omap3pandora.c @@ -253,14 +253,6 @@ static struct omap_dss_board_info pandora_dss_data = { .default_device = &pandora_lcd_device, }; -static struct platform_device pandora_dss_device = { - .name = "omapdss", - .id = -1, - .dev = { - .platform_data = &pandora_dss_data, - }, -}; - static void pandora_wl1251_init_card(struct mmc_card *card) { /* @@ -341,13 +333,13 @@ static struct twl4030_gpio_platform_data omap3pandora_gpio_data = { }; static struct regulator_consumer_supply pandora_vmmc1_supply = - REGULATOR_SUPPLY("vmmc", "mmci-omap-hs.0"); + REGULATOR_SUPPLY("vmmc", "omap_hsmmc.0"); static struct regulator_consumer_supply pandora_vmmc2_supply = - REGULATOR_SUPPLY("vmmc", "mmci-omap-hs.1"); + REGULATOR_SUPPLY("vmmc", "omap_hsmmc.1"); static struct regulator_consumer_supply pandora_vmmc3_supply = - REGULATOR_SUPPLY("vmmc", "mmci-omap-hs.2"); + REGULATOR_SUPPLY("vmmc", "omap_hsmmc.2"); static struct regulator_consumer_supply pandora_vdda_dac_supply = REGULATOR_SUPPLY("vdda_dac", "omapdss"); @@ -524,9 +516,7 @@ static struct twl4030_usb_data omap3pandora_usb_data = { .usb_mode = T2_USB_MODE_ULPI, }; -static struct twl4030_codec_audio_data omap3pandora_audio_data = { - .audio_mclk = 26000000, -}; +static struct twl4030_codec_audio_data omap3pandora_audio_data; static struct twl4030_codec_data omap3pandora_codec_data = { .audio_mclk = 26000000, @@ -634,12 +624,11 @@ static struct spi_board_info omap3pandora_spi_board_info[] __initdata = { } }; -static void __init omap3pandora_init_irq(void) +static void __init omap3pandora_init_early(void) { omap2_init_common_infrastructure(); omap2_init_common_devices(mt46h32m32lf6_sdrc_params, mt46h32m32lf6_sdrc_params); - omap_init_irq(); } static void __init pandora_wl1251_init(void) @@ -677,7 +666,6 @@ fail: static struct platform_device *omap3pandora_devices[] __initdata = { &pandora_leds_gpio, &pandora_keys_gpio, - &pandora_dss_device, &pandora_vwlan_device, }; @@ -712,6 +700,7 @@ static void __init omap3pandora_init(void) pandora_wl1251_init(); platform_add_devices(omap3pandora_devices, ARRAY_SIZE(omap3pandora_devices)); + omap_display_init(&pandora_dss_data); omap_serial_init(); spi_register_board_info(omap3pandora_spi_board_info, ARRAY_SIZE(omap3pandora_spi_board_info)); @@ -727,9 +716,10 @@ static void __init omap3pandora_init(void) MACHINE_START(OMAP3_PANDORA, "Pandora Handheld Console") .boot_params = 0x80000100, - .map_io = omap3_map_io, .reserve = omap_reserve, - .init_irq = omap3pandora_init_irq, + .map_io = omap3_map_io, + .init_early = omap3pandora_init_early, + .init_irq = omap_init_irq, .init_machine = omap3pandora_init, .timer = &omap_timer, MACHINE_END diff --git a/arch/arm/mach-omap2/board-omap3stalker.c b/arch/arm/mach-omap2/board-omap3stalker.c index f6c87787cd4..8ebdbc38b9d 100644 --- a/arch/arm/mach-omap2/board-omap3stalker.c +++ b/arch/arm/mach-omap2/board-omap3stalker.c @@ -240,14 +240,6 @@ static struct omap_dss_board_info omap3_stalker_dss_data = { .default_device = &omap3_stalker_dvi_device, }; -static struct platform_device omap3_stalker_dss_device = { - .name = "omapdss", - .id = -1, - .dev = { - .platform_data = &omap3_stalker_dss_data, - }, -}; - static struct regulator_consumer_supply omap3stalker_vmmc1_supply = { .supply = "vmmc", }; @@ -439,19 +431,15 @@ static struct twl4030_madc_platform_data omap3stalker_madc_data = { .irq_line = 1, }; -static struct twl4030_codec_audio_data omap3stalker_audio_data = { - .audio_mclk = 26000000, -}; +static struct twl4030_codec_audio_data omap3stalker_audio_data; static struct twl4030_codec_data omap3stalker_codec_data = { .audio_mclk = 26000000, .audio = &omap3stalker_audio_data, }; -static struct regulator_consumer_supply omap3_stalker_vdda_dac_supply = { - .supply = "vdda_dac", - .dev = &omap3_stalker_dss_device.dev, -}; +static struct regulator_consumer_supply omap3_stalker_vdda_dac_supply = + REGULATOR_SUPPLY("vdda_dac", "omapdss"); /* VDAC for DSS driving S-Video */ static struct regulator_init_data omap3_stalker_vdac = { @@ -469,10 +457,8 @@ static struct regulator_init_data omap3_stalker_vdac = { }; /* VPLL2 for digital video outputs */ -static struct regulator_consumer_supply omap3_stalker_vpll2_supply = { - .supply = "vdds_dsi", - .dev = &omap3_stalker_lcd_device.dev, -}; +static struct regulator_consumer_supply omap3_stalker_vpll2_supply = + REGULATOR_SUPPLY("vdds_dsi", "omapdss"); static struct regulator_init_data omap3_stalker_vpll2 = { .constraints = { @@ -591,12 +577,14 @@ static struct spi_board_info omap3stalker_spi_board_info[] = { static struct omap_board_config_kernel omap3_stalker_config[] __initdata = { }; -static void __init omap3_stalker_init_irq(void) +static void __init omap3_stalker_init_early(void) { - omap_board_config = omap3_stalker_config; - omap_board_config_size = ARRAY_SIZE(omap3_stalker_config); omap2_init_common_infrastructure(); omap2_init_common_devices(mt46h32m32lf6_sdrc_params, NULL); +} + +static void __init omap3_stalker_init_irq(void) +{ omap_init_irq(); #ifdef CONFIG_OMAP_32K_TIMER omap2_gp_clockevent_set_gptimer(12); @@ -604,7 +592,6 @@ static void __init omap3_stalker_init_irq(void) } static struct platform_device *omap3_stalker_devices[] __initdata = { - &omap3_stalker_dss_device, &keys_gpio, }; @@ -638,12 +625,15 @@ static struct omap_musb_board_data musb_board_data = { static void __init omap3_stalker_init(void) { omap3_mux_init(board_mux, OMAP_PACKAGE_CUS); + omap_board_config = omap3_stalker_config; + omap_board_config_size = ARRAY_SIZE(omap3_stalker_config); omap3_stalker_i2c_init(); platform_add_devices(omap3_stalker_devices, ARRAY_SIZE(omap3_stalker_devices)); + omap_display_init(&omap3_stalker_dss_data); spi_register_board_info(omap3stalker_spi_board_info, ARRAY_SIZE(omap3stalker_spi_board_info)); @@ -666,6 +656,7 @@ MACHINE_START(SBC3530, "OMAP3 STALKER") /* Maintainer: Jason Lam -lzg@ema-tech.com */ .boot_params = 0x80000100, .map_io = omap3_map_io, + .init_early = omap3_stalker_init_early, .init_irq = omap3_stalker_init_irq, .init_machine = omap3_stalker_init, .timer = &omap_timer, diff --git a/arch/arm/mach-omap2/board-omap3touchbook.c b/arch/arm/mach-omap2/board-omap3touchbook.c index 84cfddb19a7..127cb1752bd 100644 --- a/arch/arm/mach-omap2/board-omap3touchbook.c +++ b/arch/arm/mach-omap2/board-omap3touchbook.c @@ -252,9 +252,7 @@ static struct twl4030_usb_data touchbook_usb_data = { .usb_mode = T2_USB_MODE_ULPI, }; -static struct twl4030_codec_audio_data touchbook_audio_data = { - .audio_mclk = 26000000, -}; +static struct twl4030_codec_audio_data touchbook_audio_data; static struct twl4030_codec_data touchbook_codec_data = { .audio_mclk = 26000000, @@ -415,14 +413,15 @@ static struct omap_board_mux board_mux[] __initdata = { }; #endif -static void __init omap3_touchbook_init_irq(void) +static void __init omap3_touchbook_init_early(void) { - omap3_mux_init(board_mux, OMAP_PACKAGE_CBB); - omap_board_config = omap3_touchbook_config; - omap_board_config_size = ARRAY_SIZE(omap3_touchbook_config); omap2_init_common_infrastructure(); omap2_init_common_devices(mt46h32m32lf6_sdrc_params, mt46h32m32lf6_sdrc_params); +} + +static void __init omap3_touchbook_init_irq(void) +{ omap_init_irq(); #ifdef CONFIG_OMAP_32K_TIMER omap2_gp_clockevent_set_gptimer(12); @@ -510,6 +509,10 @@ static struct omap_musb_board_data musb_board_data = { static void __init omap3_touchbook_init(void) { + omap3_mux_init(board_mux, OMAP_PACKAGE_CBB); + omap_board_config = omap3_touchbook_config; + omap_board_config_size = ARRAY_SIZE(omap3_touchbook_config); + pm_power_off = omap3_touchbook_poweroff; omap3_touchbook_i2c_init(); @@ -538,8 +541,9 @@ static void __init omap3_touchbook_init(void) MACHINE_START(TOUCHBOOK, "OMAP3 touchbook Board") /* Maintainer: Gregoire Gentil - http://www.alwaysinnovating.com */ .boot_params = 0x80000100, - .map_io = omap3_map_io, .reserve = omap_reserve, + .map_io = omap3_map_io, + .init_early = omap3_touchbook_init_early, .init_irq = omap3_touchbook_init_irq, .init_machine = omap3_touchbook_init, .timer = &omap_timer, diff --git a/arch/arm/mach-omap2/board-omap4panda.c b/arch/arm/mach-omap2/board-omap4panda.c index ed61c1f5d5e..0f4d8a762a7 100644 --- a/arch/arm/mach-omap2/board-omap4panda.c +++ b/arch/arm/mach-omap2/board-omap4panda.c @@ -26,6 +26,8 @@ #include <linux/usb/otg.h> #include <linux/i2c/twl.h> #include <linux/regulator/machine.h> +#include <linux/regulator/fixed.h> +#include <linux/wl12xx.h> #include <mach/hardware.h> #include <mach/omap4-common.h> @@ -45,6 +47,18 @@ #define GPIO_HUB_POWER 1 #define GPIO_HUB_NRESET 62 +#define GPIO_WIFI_PMENA 43 +#define GPIO_WIFI_IRQ 53 + +/* wl127x BT, FM, GPS connectivity chip */ +static int wl1271_gpios[] = {46, -1, -1}; +static struct platform_device wl1271_device = { + .name = "kim", + .id = -1, + .dev = { + .platform_data = &wl1271_gpios, + }, +}; static struct gpio_led gpio_leds[] = { { @@ -74,13 +88,13 @@ static struct platform_device leds_gpio = { static struct platform_device *panda_devices[] __initdata = { &leds_gpio, + &wl1271_device, }; -static void __init omap4_panda_init_irq(void) +static void __init omap4_panda_init_early(void) { omap2_init_common_infrastructure(); omap2_init_common_devices(NULL, NULL); - gic_init_irq(); } static const struct usbhs_omap_board_data usbhs_bdata __initconst = { @@ -163,16 +177,62 @@ static struct omap2_hsmmc_info mmc[] = { .gpio_wp = -EINVAL, .gpio_cd = -EINVAL, }, + { + .name = "wl1271", + .mmc = 5, + .caps = MMC_CAP_4_BIT_DATA | MMC_CAP_POWER_OFF_CARD, + .gpio_wp = -EINVAL, + .gpio_cd = -EINVAL, + .ocr_mask = MMC_VDD_165_195, + .nonremovable = true, + }, {} /* Terminator */ }; static struct regulator_consumer_supply omap4_panda_vmmc_supply[] = { { .supply = "vmmc", - .dev_name = "mmci-omap-hs.0", + .dev_name = "omap_hsmmc.0", }, }; +static struct regulator_consumer_supply omap4_panda_vmmc5_supply = { + .supply = "vmmc", + .dev_name = "omap_hsmmc.4", +}; + +static struct regulator_init_data panda_vmmc5 = { + .constraints = { + .valid_ops_mask = REGULATOR_CHANGE_STATUS, + }, + .num_consumer_supplies = 1, + .consumer_supplies = &omap4_panda_vmmc5_supply, +}; + +static struct fixed_voltage_config panda_vwlan = { + .supply_name = "vwl1271", + .microvolts = 1800000, /* 1.8V */ + .gpio = GPIO_WIFI_PMENA, + .startup_delay = 70000, /* 70msec */ + .enable_high = 1, + .enabled_at_boot = 0, + .init_data = &panda_vmmc5, +}; + +static struct platform_device omap_vwlan_device = { + .name = "reg-fixed-voltage", + .id = 1, + .dev = { + .platform_data = &panda_vwlan, + }, +}; + +struct wl12xx_platform_data omap_panda_wlan_data __initdata = { + .irq = OMAP_GPIO_IRQ(GPIO_WIFI_IRQ), + /* PANDA ref clock is 38.4 MHz */ + .board_ref_clock = 2, +}; + static int omap4_twl6030_hsmmc_late_init(struct device *dev) { int ret = 0; @@ -306,7 +366,6 @@ static struct regulator_init_data omap4_panda_vana = { .constraints = { .min_uV = 2100000, .max_uV = 2100000, - .apply_uV = true, .valid_modes_mask = REGULATOR_MODE_NORMAL | REGULATOR_MODE_STANDBY, .valid_ops_mask = REGULATOR_CHANGE_MODE @@ -318,7 +377,6 @@ static struct regulator_init_data omap4_panda_vcxio = { .constraints = { .min_uV = 1800000, .max_uV = 1800000, - .apply_uV = true, .valid_modes_mask = REGULATOR_MODE_NORMAL | REGULATOR_MODE_STANDBY, .valid_ops_mask = REGULATOR_CHANGE_MODE @@ -330,7 +388,6 @@ static struct regulator_init_data omap4_panda_vdac = { .constraints = { .min_uV = 1800000, .max_uV = 1800000, - .apply_uV = true, .valid_modes_mask = REGULATOR_MODE_NORMAL | REGULATOR_MODE_STANDBY, .valid_ops_mask = REGULATOR_CHANGE_MODE @@ -392,10 +449,90 @@ static int __init omap4_panda_i2c_init(void) #ifdef CONFIG_OMAP_MUX static struct omap_board_mux board_mux[] __initdata = { + /* WLAN IRQ - GPIO 53 */ + OMAP4_MUX(GPMC_NCS3, OMAP_MUX_MODE3 | OMAP_PIN_INPUT), + /* WLAN POWER ENABLE - GPIO 43 */ + OMAP4_MUX(GPMC_A19, OMAP_MUX_MODE3 | OMAP_PIN_OUTPUT), + /* WLAN SDIO: MMC5 CMD */ + OMAP4_MUX(SDMMC5_CMD, OMAP_MUX_MODE0 | OMAP_PIN_INPUT_PULLUP), + /* WLAN SDIO: MMC5 CLK */ + OMAP4_MUX(SDMMC5_CLK, OMAP_MUX_MODE0 | OMAP_PIN_INPUT_PULLUP), + /* WLAN SDIO: MMC5 DAT[0-3] */ + OMAP4_MUX(SDMMC5_DAT0, OMAP_MUX_MODE0 | OMAP_PIN_INPUT_PULLUP), + OMAP4_MUX(SDMMC5_DAT1, OMAP_MUX_MODE0 | OMAP_PIN_INPUT_PULLUP), + OMAP4_MUX(SDMMC5_DAT2, OMAP_MUX_MODE0 | OMAP_PIN_INPUT_PULLUP), + OMAP4_MUX(SDMMC5_DAT3, OMAP_MUX_MODE0 | OMAP_PIN_INPUT_PULLUP), { .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 = { + .id = 1, + .pads = serial2_pads, + .pads_cnt = ARRAY_SIZE(serial2_pads), +}; + +static struct omap_board_data serial3_data = { + .id = 2, + .pads = serial3_pads, + .pads_cnt = ARRAY_SIZE(serial3_pads), +}; + +static struct omap_board_data serial4_data = { + .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 __init omap4_panda_init(void) @@ -406,9 +543,13 @@ static void __init omap4_panda_init(void) package = OMAP_PACKAGE_CBL; omap4_mux_init(board_mux, package); + if (wl12xx_set_platform_data(&omap_panda_wlan_data)) + pr_err("error setting wl12xx data\n"); + omap4_panda_i2c_init(); platform_add_devices(panda_devices, ARRAY_SIZE(panda_devices)); - omap_serial_init(); + platform_device_register(&omap_vwlan_device); + board_serial_init(); omap4_twl6030_hsmmc_init(mmc); omap4_ehci_init(); usb_musb_init(&musb_board_data); @@ -425,7 +566,8 @@ MACHINE_START(OMAP4_PANDA, "OMAP4 Panda board") .boot_params = 0x80000100, .reserve = omap_reserve, .map_io = omap4_panda_map_io, - .init_irq = omap4_panda_init_irq, + .init_early = omap4_panda_init_early, + .init_irq = gic_init_irq, .init_machine = omap4_panda_init, .timer = &omap_timer, MACHINE_END diff --git a/arch/arm/mach-omap2/board-overo.c b/arch/arm/mach-omap2/board-overo.c index 08770ccec0f..d0961945c65 100644 --- a/arch/arm/mach-omap2/board-overo.c +++ b/arch/arm/mach-omap2/board-overo.c @@ -358,9 +358,7 @@ static struct regulator_init_data overo_vmmc1 = { .consumer_supplies = &overo_vmmc1_supply, }; -static struct twl4030_codec_audio_data overo_audio_data = { - .audio_mclk = 26000000, -}; +static struct twl4030_codec_audio_data overo_audio_data; static struct twl4030_codec_data overo_codec_data = { .audio_mclk = 26000000, @@ -409,14 +407,11 @@ static struct omap_board_config_kernel overo_config[] __initdata = { { OMAP_TAG_LCD, &overo_lcd_config }, }; -static void __init overo_init_irq(void) +static void __init overo_init_early(void) { - omap_board_config = overo_config; - omap_board_config_size = ARRAY_SIZE(overo_config); omap2_init_common_infrastructure(); omap2_init_common_devices(mt46h32m32lf6_sdrc_params, mt46h32m32lf6_sdrc_params); - omap_init_irq(); } static struct platform_device *overo_devices[] __initdata = { @@ -449,6 +444,8 @@ static struct omap_musb_board_data musb_board_data = { static void __init overo_init(void) { omap3_mux_init(board_mux, OMAP_PACKAGE_CBB); + omap_board_config = overo_config; + omap_board_config_size = ARRAY_SIZE(overo_config); overo_i2c_init(); platform_add_devices(overo_devices, ARRAY_SIZE(overo_devices)); omap_serial_init(); @@ -501,9 +498,10 @@ static void __init overo_init(void) MACHINE_START(OVERO, "Gumstix Overo") .boot_params = 0x80000100, - .map_io = omap3_map_io, .reserve = omap_reserve, - .init_irq = overo_init_irq, + .map_io = omap3_map_io, + .init_early = overo_init_early, + .init_irq = omap_init_irq, .init_machine = overo_init, .timer = &omap_timer, MACHINE_END diff --git a/arch/arm/mach-omap2/board-rm680.c b/arch/arm/mach-omap2/board-rm680.c index 39a71bb8a30..2af8b05e786 100644 --- a/arch/arm/mach-omap2/board-rm680.c +++ b/arch/arm/mach-omap2/board-rm680.c @@ -33,7 +33,7 @@ #include "sdram-nokia.h" static struct regulator_consumer_supply rm680_vemmc_consumers[] = { - REGULATOR_SUPPLY("vmmc", "mmci-omap-hs.1"), + REGULATOR_SUPPLY("vmmc", "omap_hsmmc.1"), }; /* Fixed regulator for internal eMMC */ @@ -138,14 +138,13 @@ static void __init rm680_peripherals_init(void) omap2_hsmmc_init(mmc); } -static void __init rm680_init_irq(void) +static void __init rm680_init_early(void) { struct omap_sdrc_params *sdrc_params; omap2_init_common_infrastructure(); sdrc_params = nokia_get_sdram_timings(); omap2_init_common_devices(sdrc_params, sdrc_params); - omap_init_irq(); } #ifdef CONFIG_OMAP_MUX @@ -176,9 +175,10 @@ static void __init rm680_map_io(void) MACHINE_START(NOKIA_RM680, "Nokia RM-680 board") .boot_params = 0x80000100, - .map_io = rm680_map_io, .reserve = omap_reserve, - .init_irq = rm680_init_irq, + .map_io = rm680_map_io, + .init_early = rm680_init_early, + .init_irq = omap_init_irq, .init_machine = rm680_init, .timer = &omap_timer, MACHINE_END diff --git a/arch/arm/mach-omap2/board-rx51-peripherals.c b/arch/arm/mach-omap2/board-rx51-peripherals.c index e75e240cad6..5f1900c532e 100644 --- a/arch/arm/mach-omap2/board-rx51-peripherals.c +++ b/arch/arm/mach-omap2/board-rx51-peripherals.c @@ -36,6 +36,8 @@ #include <sound/tlv320aic3x.h> #include <sound/tpa6130a2-plat.h> +#include <media/radio-si4713.h> +#include <media/si4713.h> #include <../drivers/staging/iio/light/tsl2563.h> @@ -47,6 +49,8 @@ #define RX51_WL1251_POWER_GPIO 87 #define RX51_WL1251_IRQ_GPIO 42 +#define RX51_FMTX_RESET_GPIO 163 +#define RX51_FMTX_IRQ 53 /* list all spi devices here */ enum { @@ -331,13 +335,13 @@ static struct omap2_hsmmc_info mmc[] __initdata = { }; static struct regulator_consumer_supply rx51_vmmc1_supply = - REGULATOR_SUPPLY("vmmc", "mmci-omap-hs.0"); + REGULATOR_SUPPLY("vmmc", "omap_hsmmc.0"); static struct regulator_consumer_supply rx51_vaux3_supply = - REGULATOR_SUPPLY("vmmc", "mmci-omap-hs.1"); + REGULATOR_SUPPLY("vmmc", "omap_hsmmc.1"); static struct regulator_consumer_supply rx51_vsim_supply = - REGULATOR_SUPPLY("vmmc_aux", "mmci-omap-hs.1"); + REGULATOR_SUPPLY("vmmc_aux", "omap_hsmmc.1"); static struct regulator_consumer_supply rx51_vmmc2_supplies[] = { /* tlv320aic3x analog supplies */ @@ -348,7 +352,7 @@ static struct regulator_consumer_supply rx51_vmmc2_supplies[] = { /* tpa6130a2 */ REGULATOR_SUPPLY("Vdd", "2-0060"), /* Keep vmmc as last item. It is not iterated for newer boards */ - REGULATOR_SUPPLY("vmmc", "mmci-omap-hs.1"), + REGULATOR_SUPPLY("vmmc", "omap_hsmmc.1"), }; static struct regulator_consumer_supply rx51_vio_supplies[] = { @@ -357,10 +361,14 @@ static struct regulator_consumer_supply rx51_vio_supplies[] = { REGULATOR_SUPPLY("DVDD", "2-0018"), REGULATOR_SUPPLY("IOVDD", "2-0019"), REGULATOR_SUPPLY("DVDD", "2-0019"), + /* Si4713 IO supply */ + REGULATOR_SUPPLY("vio", "2-0063"), }; static struct regulator_consumer_supply rx51_vaux1_consumers[] = { REGULATOR_SUPPLY("vdds_sdi", "omapdss"), + /* Si4713 supply */ + REGULATOR_SUPPLY("vdd", "2-0063"), }; static struct regulator_consumer_supply rx51_vdac_supply[] = { @@ -511,6 +519,41 @@ static struct regulator_init_data rx51_vio = { .consumer_supplies = rx51_vio_supplies, }; +static struct si4713_platform_data rx51_si4713_i2c_data __initdata_or_module = { + .gpio_reset = RX51_FMTX_RESET_GPIO, +}; + +static struct i2c_board_info rx51_si4713_board_info __initdata_or_module = { + I2C_BOARD_INFO("si4713", SI4713_I2C_ADDR_BUSEN_HIGH), + .platform_data = &rx51_si4713_i2c_data, +}; + +static struct radio_si4713_platform_data rx51_si4713_data __initdata_or_module = { + .i2c_bus = 2, + .subdev_board_info = &rx51_si4713_board_info, +}; + +static struct platform_device rx51_si4713_dev __initdata_or_module = { + .name = "radio-si4713", + .id = -1, + .dev = { + .platform_data = &rx51_si4713_data, + }, +}; + +static __init void rx51_init_si4713(void) +{ + int err; + + err = gpio_request_one(RX51_FMTX_IRQ, GPIOF_DIR_IN, "si4713 irq"); + if (err) { + printk(KERN_ERR "Cannot request si4713 irq gpio. %d\n", err); + return; + } + rx51_si4713_board_info.irq = gpio_to_irq(RX51_FMTX_IRQ); + platform_device_register(&rx51_si4713_dev); +} + static int rx51_twlgpio_setup(struct device *dev, unsigned gpio, unsigned n) { /* FIXME this gpio setup is just a placeholder for now */ @@ -699,6 +742,14 @@ static struct twl4030_power_data rx51_t2scripts_data __initdata = { .resource_config = twl4030_rconfig, }; +struct twl4030_codec_vibra_data rx51_vibra_data __initdata = { + .coexist = 0, +}; + +struct twl4030_codec_data rx51_codec_data __initdata = { + .audio_mclk = 26000000, + .vibra = &rx51_vibra_data, +}; static struct twl4030_platform_data rx51_twldata __initdata = { .irq_base = TWL4030_IRQ_BASE, @@ -710,6 +761,7 @@ static struct twl4030_platform_data rx51_twldata __initdata = { .madc = &rx51_madc_data, .usb = &rx51_usb_data, .power = &rx51_t2scripts_data, + .codec = &rx51_codec_data, .vaux1 = &rx51_vaux1, .vaux2 = &rx51_vaux2, @@ -921,6 +973,7 @@ void __init rx51_peripherals_init(void) board_smc91x_init(); rx51_add_gpio_keys(); rx51_init_wl1251(); + rx51_init_si4713(); spi_register_board_info(rx51_peripherals_spi_board_info, ARRAY_SIZE(rx51_peripherals_spi_board_info)); diff --git a/arch/arm/mach-omap2/board-rx51-video.c b/arch/arm/mach-omap2/board-rx51-video.c index acd670054d9..89a66db8b77 100644 --- a/arch/arm/mach-omap2/board-rx51-video.c +++ b/arch/arm/mach-omap2/board-rx51-video.c @@ -66,18 +66,6 @@ static struct omap_dss_board_info rx51_dss_board_info = { .default_device = &rx51_lcd_device, }; -struct platform_device rx51_display_device = { - .name = "omapdss", - .id = -1, - .dev = { - .platform_data = &rx51_dss_board_info, - }, -}; - -static struct platform_device *rx51_video_devices[] __initdata = { - &rx51_display_device, -}; - static int __init rx51_video_init(void) { if (!machine_is_nokia_rx51()) @@ -95,8 +83,7 @@ static int __init rx51_video_init(void) gpio_direction_output(RX51_LCD_RESET_GPIO, 1); - platform_add_devices(rx51_video_devices, - ARRAY_SIZE(rx51_video_devices)); + omap_display_init(&rx51_dss_board_info); return 0; } diff --git a/arch/arm/mach-omap2/board-rx51.c b/arch/arm/mach-omap2/board-rx51.c index f53fc551c58..e964895b80e 100644 --- a/arch/arm/mach-omap2/board-rx51.c +++ b/arch/arm/mach-omap2/board-rx51.c @@ -98,17 +98,13 @@ static struct omap_board_config_kernel rx51_config[] = { { OMAP_TAG_LCD, &rx51_lcd_config }, }; -static void __init rx51_init_irq(void) +static void __init rx51_init_early(void) { struct omap_sdrc_params *sdrc_params; - omap_board_config = rx51_config; - omap_board_config_size = ARRAY_SIZE(rx51_config); - omap3_pm_init_cpuidle(rx51_cpuidle_params); omap2_init_common_infrastructure(); sdrc_params = nokia_get_sdram_timings(); omap2_init_common_devices(sdrc_params, sdrc_params); - omap_init_irq(); } extern void __init rx51_peripherals_init(void); @@ -128,6 +124,9 @@ static struct omap_musb_board_data musb_board_data = { static void __init rx51_init(void) { omap3_mux_init(board_mux, OMAP_PACKAGE_CBB); + omap_board_config = rx51_config; + omap_board_config_size = ARRAY_SIZE(rx51_config); + omap3_pm_init_cpuidle(rx51_cpuidle_params); omap_serial_init(); usb_musb_init(&musb_board_data); rx51_peripherals_init(); @@ -149,9 +148,10 @@ static void __init rx51_map_io(void) MACHINE_START(NOKIA_RX51, "Nokia RX-51 board") /* Maintainer: Lauri Leukkunen <lauri.leukkunen@nokia.com> */ .boot_params = 0x80000100, - .map_io = rx51_map_io, .reserve = omap_reserve, - .init_irq = rx51_init_irq, + .map_io = rx51_map_io, + .init_early = rx51_init_early, + .init_irq = omap_init_irq, .init_machine = rx51_init, .timer = &omap_timer, MACHINE_END diff --git a/arch/arm/mach-omap2/board-ti8168evm.c b/arch/arm/mach-omap2/board-ti8168evm.c new file mode 100644 index 00000000000..09fa7bfff8d --- /dev/null +++ b/arch/arm/mach-omap2/board-ti8168evm.c @@ -0,0 +1,62 @@ +/* + * Code for TI8168 EVM. + * + * Copyright (C) 2010 Texas Instruments, Inc. - http://www.ti.com/ + * + * This program is free software; you can redistribute it and/or + * modify it under the terms of the GNU General Public License as + * published by the Free Software Foundation version 2. + * + * This program is distributed "as is" WITHOUT ANY WARRANTY of any + * kind, whether express or implied; without even the implied warranty + * of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + */ +#include <linux/kernel.h> +#include <linux/init.h> + +#include <mach/hardware.h> +#include <asm/mach-types.h> +#include <asm/mach/arch.h> +#include <asm/mach/map.h> + +#include <plat/irqs.h> +#include <plat/board.h> +#include <plat/common.h> + +static struct omap_board_config_kernel ti8168_evm_config[] __initdata = { +}; + +static void __init ti8168_init_early(void) +{ + omap2_init_common_infrastructure(); + omap2_init_common_devices(NULL, NULL); +} + +static void __init ti8168_evm_init_irq(void) +{ + omap_init_irq(); +} + +static void __init ti8168_evm_init(void) +{ + omap_serial_init(); + omap_board_config = ti8168_evm_config; + omap_board_config_size = ARRAY_SIZE(ti8168_evm_config); +} + +static void __init ti8168_evm_map_io(void) +{ + omap2_set_globals_ti816x(); + omapti816x_map_common_io(); +} + +MACHINE_START(TI8168EVM, "ti8168evm") + /* Maintainer: Texas Instruments */ + .boot_params = 0x80000100, + .map_io = ti8168_evm_map_io, + .init_early = ti8168_init_early, + .init_irq = ti8168_evm_init_irq, + .timer = &omap_timer, + .init_machine = ti8168_evm_init, +MACHINE_END diff --git a/arch/arm/mach-omap2/board-zoom-display.c b/arch/arm/mach-omap2/board-zoom-display.c index 6bcd43657ae..37b84c2b850 100644 --- a/arch/arm/mach-omap2/board-zoom-display.c +++ b/arch/arm/mach-omap2/board-zoom-display.c @@ -130,14 +130,6 @@ static struct omap_dss_board_info zoom_dss_data = { .default_device = &zoom_lcd_device, }; -static struct platform_device zoom_dss_device = { - .name = "omapdss", - .id = -1, - .dev = { - .platform_data = &zoom_dss_data, - }, -}; - static struct omap2_mcspi_device_config dss_lcd_mcspi_config = { .turbo_mode = 1, .single_channel = 1, /* 0: slave, 1: master */ @@ -153,14 +145,9 @@ static struct spi_board_info nec_8048_spi_board_info[] __initdata = { }, }; -static struct platform_device *zoom_display_devices[] __initdata = { - &zoom_dss_device, -}; - void __init zoom_display_init(void) { - platform_add_devices(zoom_display_devices, - ARRAY_SIZE(zoom_display_devices)); + omap_display_init(&zoom_dss_data); spi_register_board_info(nec_8048_spi_board_info, ARRAY_SIZE(nec_8048_spi_board_info)); zoom_lcd_panel_init(); diff --git a/arch/arm/mach-omap2/board-zoom-peripherals.c b/arch/arm/mach-omap2/board-zoom-peripherals.c index e0e040f34c6..448ab60195d 100644 --- a/arch/arm/mach-omap2/board-zoom-peripherals.c +++ b/arch/arm/mach-omap2/board-zoom-peripherals.c @@ -118,7 +118,7 @@ static struct regulator_consumer_supply zoom_vmmc2_supply = { static struct regulator_consumer_supply zoom_vmmc3_supply = { .supply = "vmmc", - .dev_name = "mmci-omap-hs.2", + .dev_name = "omap_hsmmc.2", }; /* VMMC1 for OMAP VDD_MMC1 (i/o) and MMC1 card */ @@ -322,9 +322,7 @@ static struct twl4030_madc_platform_data zoom_madc_data = { .irq_line = 1, }; -static struct twl4030_codec_audio_data zoom_audio_data = { - .audio_mclk = 26000000, -}; +static struct twl4030_codec_audio_data zoom_audio_data; static struct twl4030_codec_data zoom_codec_data = { .audio_mclk = 26000000, diff --git a/arch/arm/mach-omap2/board-zoom.c b/arch/arm/mach-omap2/board-zoom.c index 1dd195afa39..4b133d75c93 100644 --- a/arch/arm/mach-omap2/board-zoom.c +++ b/arch/arm/mach-omap2/board-zoom.c @@ -16,6 +16,7 @@ #include <linux/input.h> #include <linux/gpio.h> #include <linux/i2c/twl.h> +#include <linux/mtd/nand.h> #include <asm/mach-types.h> #include <asm/mach/arch.h> @@ -33,7 +34,7 @@ #define ZOOM3_EHCI_RESET_GPIO 64 -static void __init omap_zoom_init_irq(void) +static void __init omap_zoom_init_early(void) { omap2_init_common_infrastructure(); if (machine_is_omap_zoom2()) @@ -42,14 +43,12 @@ static void __init omap_zoom_init_irq(void) else if (machine_is_omap_zoom3()) omap2_init_common_devices(h8mbx00u0mer0em_sdrc_params, h8mbx00u0mer0em_sdrc_params); - - omap_init_irq(); } #ifdef CONFIG_OMAP_MUX static struct omap_board_mux board_mux[] __initdata = { /* WLAN IRQ - GPIO 162 */ - OMAP3_MUX(MCBSP1_CLKX, OMAP_MUX_MODE4 | OMAP_PIN_INPUT_PULLUP), + OMAP3_MUX(MCBSP1_CLKX, OMAP_MUX_MODE4 | OMAP_PIN_INPUT), /* WLAN POWER ENABLE - GPIO 101 */ OMAP3_MUX(CAM_D2, OMAP_MUX_MODE4 | OMAP_PIN_OUTPUT), /* WLAN SDIO: MMC3 CMD */ @@ -126,8 +125,8 @@ static void __init omap_zoom_init(void) usbhs_init(&usbhs_bdata); } - board_nand_init(zoom_nand_partitions, - ARRAY_SIZE(zoom_nand_partitions), ZOOM_NAND_CS); + board_nand_init(zoom_nand_partitions, ARRAY_SIZE(zoom_nand_partitions), + ZOOM_NAND_CS, NAND_BUSWIDTH_16); zoom_debugboard_init(); zoom_peripherals_init(); zoom_display_init(); @@ -135,18 +134,20 @@ static void __init omap_zoom_init(void) MACHINE_START(OMAP_ZOOM2, "OMAP Zoom2 board") .boot_params = 0x80000100, - .map_io = omap3_map_io, .reserve = omap_reserve, - .init_irq = omap_zoom_init_irq, + .map_io = omap3_map_io, + .init_early = omap_zoom_init_early, + .init_irq = omap_init_irq, .init_machine = omap_zoom_init, .timer = &omap_timer, MACHINE_END MACHINE_START(OMAP_ZOOM3, "OMAP Zoom3 board") .boot_params = 0x80000100, - .map_io = omap3_map_io, .reserve = omap_reserve, - .init_irq = omap_zoom_init_irq, + .map_io = omap3_map_io, + .init_early = omap_zoom_init_early, + .init_irq = omap_init_irq, .init_machine = omap_zoom_init, .timer = &omap_timer, MACHINE_END diff --git a/arch/arm/mach-omap2/clkt2xxx_apll.c b/arch/arm/mach-omap2/clkt2xxx_apll.c index f51cffd1fc5..b19a1f7234a 100644 --- a/arch/arm/mach-omap2/clkt2xxx_apll.c +++ b/arch/arm/mach-omap2/clkt2xxx_apll.c @@ -78,6 +78,26 @@ static int omap2_clk_apll54_enable(struct clk *clk) return omap2_clk_apll_enable(clk, OMAP24XX_ST_54M_APLL_MASK); } +static void _apll96_allow_idle(struct clk *clk) +{ + omap2xxx_cm_set_apll96_auto_low_power_stop(); +} + +static void _apll96_deny_idle(struct clk *clk) +{ + omap2xxx_cm_set_apll96_disable_autoidle(); +} + +static void _apll54_allow_idle(struct clk *clk) +{ + omap2xxx_cm_set_apll54_auto_low_power_stop(); +} + +static void _apll54_deny_idle(struct clk *clk) +{ + omap2xxx_cm_set_apll54_disable_autoidle(); +} + /* Stop APLL */ static void omap2_clk_apll_disable(struct clk *clk) { @@ -93,11 +113,15 @@ static void omap2_clk_apll_disable(struct clk *clk) const struct clkops clkops_apll96 = { .enable = omap2_clk_apll96_enable, .disable = omap2_clk_apll_disable, + .allow_idle = _apll96_allow_idle, + .deny_idle = _apll96_deny_idle, }; const struct clkops clkops_apll54 = { .enable = omap2_clk_apll54_enable, .disable = omap2_clk_apll_disable, + .allow_idle = _apll54_allow_idle, + .deny_idle = _apll54_deny_idle, }; /* Public functions */ diff --git a/arch/arm/mach-omap2/clkt2xxx_dpll.c b/arch/arm/mach-omap2/clkt2xxx_dpll.c new file mode 100644 index 00000000000..1502a7bc20b --- /dev/null +++ b/arch/arm/mach-omap2/clkt2xxx_dpll.c @@ -0,0 +1,63 @@ +/* + * OMAP2-specific DPLL control functions + * + * Copyright (C) 2011 Nokia Corporation + * Paul Walmsley + * + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License version 2 as + * published by the Free Software Foundation. + */ + +#include <linux/kernel.h> +#include <linux/errno.h> +#include <linux/clk.h> +#include <linux/io.h> + +#include <plat/clock.h> + +#include "clock.h" +#include "cm2xxx_3xxx.h" +#include "cm-regbits-24xx.h" + +/* Private functions */ + +/** + * _allow_idle - enable DPLL autoidle bits + * @clk: struct clk * of the DPLL to operate on + * + * Enable DPLL automatic idle control. The DPLL will enter low-power + * stop when its downstream clocks are gated. No return value. + * REVISIT: DPLL can optionally enter low-power bypass by writing 0x1 + * instead. Add some mechanism to optionally enter this mode. + */ +static void _allow_idle(struct clk *clk) +{ + if (!clk || !clk->dpll_data) + return; + + omap2xxx_cm_set_dpll_auto_low_power_stop(); +} + +/** + * _deny_idle - prevent DPLL from automatically idling + * @clk: struct clk * of the DPLL to operate on + * + * Disable DPLL automatic idle control. No return value. + */ +static void _deny_idle(struct clk *clk) +{ + if (!clk || !clk->dpll_data) + return; + + omap2xxx_cm_set_dpll_disable_autoidle(); +} + + +/* Public data */ + +const struct clkops clkops_omap2xxx_dpll_ops = { + .allow_idle = _allow_idle, + .deny_idle = _deny_idle, +}; + diff --git a/arch/arm/mach-omap2/clkt2xxx_osc.c b/arch/arm/mach-omap2/clkt2xxx_osc.c index df7b8050648..c3460928b5e 100644 --- a/arch/arm/mach-omap2/clkt2xxx_osc.c +++ b/arch/arm/mach-omap2/clkt2xxx_osc.c @@ -30,6 +30,13 @@ #include "prm2xxx_3xxx.h" #include "prm-regbits-24xx.h" +/* + * XXX This does not actually enable the osc_ck, since the osc_ck must + * be running for this function to be called. Instead, this function + * is used to disable an autoidle mode on the osc_ck. The existing + * clk_enable/clk_disable()-based usecounting for osc_ck should be + * replaced with autoidle-based usecounting. + */ static int omap2_enable_osc_ck(struct clk *clk) { u32 pcc; @@ -41,6 +48,13 @@ static int omap2_enable_osc_ck(struct clk *clk) return 0; } +/* + * XXX This does not actually disable the osc_ck, since doing so would + * immediately halt the system. Instead, this function is used to + * enable an autoidle mode on the osc_ck. The existing + * clk_enable/clk_disable()-based usecounting for osc_ck should be + * replaced with autoidle-based usecounting. + */ static void omap2_disable_osc_ck(struct clk *clk) { u32 pcc; diff --git a/arch/arm/mach-omap2/clkt_clksel.c b/arch/arm/mach-omap2/clkt_clksel.c index a781cd6795a..e25364de028 100644 --- a/arch/arm/mach-omap2/clkt_clksel.c +++ b/arch/arm/mach-omap2/clkt_clksel.c @@ -97,7 +97,7 @@ static u8 _get_div_and_fieldval(struct clk *src_clk, struct clk *clk, u32 *field_val) { const struct clksel *clks; - const struct clksel_rate *clkr, *max_clkr; + const struct clksel_rate *clkr, *max_clkr = NULL; u8 max_div = 0; clks = _get_clksel_by_parent(clk, src_clk); diff --git a/arch/arm/mach-omap2/clkt_dpll.c b/arch/arm/mach-omap2/clkt_dpll.c index acb7ae5b0a2..bcffee001bf 100644 --- a/arch/arm/mach-omap2/clkt_dpll.c +++ b/arch/arm/mach-omap2/clkt_dpll.c @@ -178,12 +178,11 @@ void omap2_init_dpll_parent(struct clk *clk) if (!dd) return; - /* Return bypass rate if DPLL is bypassed */ v = __raw_readl(dd->control_reg); v &= dd->enable_mask; v >>= __ffs(dd->enable_mask); - /* Reparent in case the dpll is in bypass */ + /* Reparent the struct clk in case the dpll is in bypass */ if (cpu_is_omap24xx()) { if (v == OMAP2XXX_EN_DPLL_LPBYPASS || v == OMAP2XXX_EN_DPLL_FRBYPASS) @@ -260,50 +259,22 @@ u32 omap2_get_dpll_rate(struct clk *clk) /* DPLL rate rounding code */ /** - * omap2_dpll_set_rate_tolerance: set the error tolerance during rate rounding - * @clk: struct clk * of the DPLL - * @tolerance: maximum rate error tolerance - * - * Set the maximum DPLL rate error tolerance for the rate rounding - * algorithm. The rate tolerance is an attempt to balance DPLL power - * saving (the least divider value "n") vs. rate fidelity (the least - * difference between the desired DPLL target rate and the rounded - * rate out of the algorithm). So, increasing the tolerance is likely - * to decrease DPLL power consumption and increase DPLL rate error. - * Returns -EINVAL if provided a null clock ptr or a clk that is not a - * DPLL; or 0 upon success. - */ -int omap2_dpll_set_rate_tolerance(struct clk *clk, unsigned int tolerance) -{ - if (!clk || !clk->dpll_data) - return -EINVAL; - - clk->dpll_data->rate_tolerance = tolerance; - - return 0; -} - -/** * omap2_dpll_round_rate - round a target rate for an OMAP DPLL * @clk: struct clk * for a DPLL * @target_rate: desired DPLL clock rate * - * Given a DPLL, a desired target rate, and a rate tolerance, round - * the target rate to a possible, programmable rate for this DPLL. - * Rate tolerance is assumed to be set by the caller before this - * function is called. Attempts to select the minimum possible n - * within the tolerance to reduce power consumption. Stores the - * computed (m, n) in the DPLL's dpll_data structure so set_rate() - * will not need to call this (expensive) function again. Returns ~0 - * if the target rate cannot be rounded, either because the rate is - * too low or because the rate tolerance is set too tightly; or the - * rounded rate upon success. + * Given a DPLL and a desired target rate, round the target rate to a + * possible, programmable rate for this DPLL. Attempts to select the + * minimum possible n. Stores the computed (m, n) in the DPLL's + * dpll_data structure so set_rate() will not need to call this + * (expensive) function again. Returns ~0 if the target rate cannot + * be rounded, or the rounded rate upon success. */ long omap2_dpll_round_rate(struct clk *clk, unsigned long target_rate) { - int m, n, r, e, scaled_max_m; - unsigned long scaled_rt_rp, new_rate; - int min_e = -1, min_e_m = -1, min_e_n = -1; + int m, n, r, scaled_max_m; + unsigned long scaled_rt_rp; + unsigned long new_rate = 0; struct dpll_data *dd; if (!clk || !clk->dpll_data) @@ -311,8 +282,8 @@ long omap2_dpll_round_rate(struct clk *clk, unsigned long target_rate) dd = clk->dpll_data; - pr_debug("clock: starting DPLL round_rate for clock %s, target rate " - "%ld\n", clk->name, target_rate); + pr_debug("clock: %s: starting DPLL round_rate, target rate %ld\n", + clk->name, target_rate); scaled_rt_rp = target_rate / (dd->clk_ref->rate / DPLL_SCALE_FACTOR); scaled_max_m = dd->max_multiplier * DPLL_SCALE_FACTOR; @@ -347,39 +318,23 @@ long omap2_dpll_round_rate(struct clk *clk, unsigned long target_rate) if (r == DPLL_MULT_UNDERFLOW) continue; - e = target_rate - new_rate; - pr_debug("clock: n = %d: m = %d: rate error is %d " - "(new_rate = %ld)\n", n, m, e, new_rate); - - if (min_e == -1 || - min_e >= (int)(abs(e) - dd->rate_tolerance)) { - min_e = e; - min_e_m = m; - min_e_n = n; - - pr_debug("clock: found new least error %d\n", min_e); + pr_debug("clock: %s: m = %d: n = %d: new_rate = %ld\n", + clk->name, m, n, new_rate); - /* We found good settings -- bail out now */ - if (min_e <= dd->rate_tolerance) - break; + if (target_rate == new_rate) { + dd->last_rounded_m = m; + dd->last_rounded_n = n; + dd->last_rounded_rate = target_rate; + break; } } - if (min_e < 0) { - pr_debug("clock: error: target rate or tolerance too low\n"); + if (target_rate != new_rate) { + pr_debug("clock: %s: cannot round to rate %ld\n", clk->name, + target_rate); return ~0; } - dd->last_rounded_m = min_e_m; - dd->last_rounded_n = min_e_n; - dd->last_rounded_rate = _dpll_compute_new_rate(dd->clk_ref->rate, - min_e_m, min_e_n); - - pr_debug("clock: final least error: e = %d, m = %d, n = %d\n", - min_e, min_e_m, min_e_n); - pr_debug("clock: final rate: %ld (target rate: %ld)\n", - dd->last_rounded_rate, target_rate); - - return dd->last_rounded_rate; + return target_rate; } diff --git a/arch/arm/mach-omap2/clkt_iclk.c b/arch/arm/mach-omap2/clkt_iclk.c new file mode 100644 index 00000000000..3d43fba2542 --- /dev/null +++ b/arch/arm/mach-omap2/clkt_iclk.c @@ -0,0 +1,82 @@ +/* + * OMAP2/3 interface clock control + * + * Copyright (C) 2011 Nokia Corporation + * Paul Walmsley + * + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License version 2 as + * published by the Free Software Foundation. + */ +#undef DEBUG + +#include <linux/kernel.h> +#include <linux/clk.h> +#include <linux/io.h> + +#include <plat/clock.h> +#include <plat/prcm.h> + +#include "clock.h" +#include "clock2xxx.h" +#include "cm2xxx_3xxx.h" +#include "cm-regbits-24xx.h" + +/* Private functions */ + +/* XXX */ +void omap2_clkt_iclk_allow_idle(struct clk *clk) +{ + u32 v, r; + + r = ((__force u32)clk->enable_reg ^ (CM_AUTOIDLE ^ CM_ICLKEN)); + + v = __raw_readl((__force void __iomem *)r); + v |= (1 << clk->enable_bit); + __raw_writel(v, (__force void __iomem *)r); +} + +/* XXX */ +void omap2_clkt_iclk_deny_idle(struct clk *clk) +{ + u32 v, r; + + r = ((__force u32)clk->enable_reg ^ (CM_AUTOIDLE ^ CM_ICLKEN)); + + v = __raw_readl((__force void __iomem *)r); + v &= ~(1 << clk->enable_bit); + __raw_writel(v, (__force void __iomem *)r); +} + +/* Public data */ + +const struct clkops clkops_omap2_iclk_dflt_wait = { + .enable = omap2_dflt_clk_enable, + .disable = omap2_dflt_clk_disable, + .find_companion = omap2_clk_dflt_find_companion, + .find_idlest = omap2_clk_dflt_find_idlest, + .allow_idle = omap2_clkt_iclk_allow_idle, + .deny_idle = omap2_clkt_iclk_deny_idle, +}; + +const struct clkops clkops_omap2_iclk_dflt = { + .enable = omap2_dflt_clk_enable, + .disable = omap2_dflt_clk_disable, + .allow_idle = omap2_clkt_iclk_allow_idle, + .deny_idle = omap2_clkt_iclk_deny_idle, +}; + +const struct clkops clkops_omap2_iclk_idle_only = { + .allow_idle = omap2_clkt_iclk_allow_idle, + .deny_idle = omap2_clkt_iclk_deny_idle, +}; + +const struct clkops clkops_omap2_mdmclk_dflt_wait = { + .enable = omap2_dflt_clk_enable, + .disable = omap2_dflt_clk_disable, + .find_companion = omap2_clk_dflt_find_companion, + .find_idlest = omap2_clk_dflt_find_idlest, + .allow_idle = omap2_clkt_iclk_allow_idle, + .deny_idle = omap2_clkt_iclk_deny_idle, +}; + diff --git a/arch/arm/mach-omap2/clock.c b/arch/arm/mach-omap2/clock.c index 2a2f15213ad..180299e4a83 100644 --- a/arch/arm/mach-omap2/clock.c +++ b/arch/arm/mach-omap2/clock.c @@ -22,7 +22,9 @@ #include <linux/clk.h> #include <linux/io.h> #include <linux/bitops.h> +#include <trace/events/power.h> +#include <asm/cpu.h> #include <plat/clock.h> #include "clockdomain.h" #include <plat/cpu.h> @@ -261,10 +263,13 @@ void omap2_clk_disable(struct clk *clk) pr_debug("clock: %s: disabling in hardware\n", clk->name); - clk->ops->disable(clk); + if (clk->ops && clk->ops->disable) { + trace_clock_disable(clk->name, 0, smp_processor_id()); + clk->ops->disable(clk); + } if (clk->clkdm) - omap2_clkdm_clk_disable(clk->clkdm, clk); + clkdm_clk_disable(clk->clkdm, clk); if (clk->parent) omap2_clk_disable(clk->parent); @@ -304,7 +309,7 @@ int omap2_clk_enable(struct clk *clk) } if (clk->clkdm) { - ret = omap2_clkdm_clk_enable(clk->clkdm, clk); + ret = clkdm_clk_enable(clk->clkdm, clk); if (ret) { WARN(1, "clock: %s: could not enable clockdomain %s: " "%d\n", clk->name, clk->clkdm->name, ret); @@ -312,17 +317,21 @@ int omap2_clk_enable(struct clk *clk) } } - ret = clk->ops->enable(clk); - if (ret) { - WARN(1, "clock: %s: could not enable: %d\n", clk->name, ret); - goto oce_err3; + if (clk->ops && clk->ops->enable) { + trace_clock_enable(clk->name, 1, smp_processor_id()); + ret = clk->ops->enable(clk); + if (ret) { + WARN(1, "clock: %s: could not enable: %d\n", + clk->name, ret); + goto oce_err3; + } } return 0; oce_err3: if (clk->clkdm) - omap2_clkdm_clk_disable(clk->clkdm, clk); + clkdm_clk_disable(clk->clkdm, clk); oce_err2: if (clk->parent) omap2_clk_disable(clk->parent); @@ -349,8 +358,10 @@ int omap2_clk_set_rate(struct clk *clk, unsigned long rate) pr_debug("clock: set_rate for clock %s to rate %ld\n", clk->name, rate); /* dpll_ck, core_ck, virt_prcm_set; plus all clksel clocks */ - if (clk->set_rate) + if (clk->set_rate) { + trace_clock_set_rate(clk->name, rate, smp_processor_id()); ret = clk->set_rate(clk, rate); + } return ret; } @@ -373,10 +384,16 @@ int omap2_clk_set_parent(struct clk *clk, struct clk *new_parent) const struct clkops clkops_omap3_noncore_dpll_ops = { .enable = omap3_noncore_dpll_enable, .disable = omap3_noncore_dpll_disable, + .allow_idle = omap3_dpll_allow_idle, + .deny_idle = omap3_dpll_deny_idle, }; -#endif +const struct clkops clkops_omap3_core_dpll_ops = { + .allow_idle = omap3_dpll_allow_idle, + .deny_idle = omap3_dpll_deny_idle, +}; +#endif /* * OMAP2+ clock reset and init functions diff --git a/arch/arm/mach-omap2/clock.h b/arch/arm/mach-omap2/clock.h index 896584e3c4a..e10ff2b5484 100644 --- a/arch/arm/mach-omap2/clock.h +++ b/arch/arm/mach-omap2/clock.h @@ -2,7 +2,7 @@ * linux/arch/arm/mach-omap2/clock.h * * Copyright (C) 2005-2009 Texas Instruments, Inc. - * Copyright (C) 2004-2009 Nokia Corporation + * Copyright (C) 2004-2011 Nokia Corporation * * Contacts: * Richard Woodruff <r-woodruff2@ti.com> @@ -18,9 +18,6 @@ #include <plat/clock.h> -/* The maximum error between a target DPLL rate and the rounded rate in Hz */ -#define DEFAULT_DPLL_RATE_TOLERANCE 50000 - /* CM_CLKSEL2_PLL.CORE_CLK_SRC bits (2XXX) */ #define CORE_CLK_SRC_32K 0x0 #define CORE_CLK_SRC_DPLL 0x1 @@ -55,7 +52,6 @@ void omap2_clk_disable(struct clk *clk); long omap2_clk_round_rate(struct clk *clk, unsigned long rate); int omap2_clk_set_rate(struct clk *clk, unsigned long rate); int omap2_clk_set_parent(struct clk *clk, struct clk *new_parent); -int omap2_dpll_set_rate_tolerance(struct clk *clk, unsigned int tolerance); long omap2_dpll_round_rate(struct clk *clk, unsigned long target_rate); unsigned long omap3_dpll_recalc(struct clk *clk); unsigned long omap3_clkoutx2_recalc(struct clk *clk); @@ -65,6 +61,9 @@ u32 omap3_dpll_autoidle_read(struct clk *clk); int omap3_noncore_dpll_set_rate(struct clk *clk, unsigned long rate); int omap3_noncore_dpll_enable(struct clk *clk); void omap3_noncore_dpll_disable(struct clk *clk); +int omap4_dpllmx_gatectrl_read(struct clk *clk); +void omap4_dpllmx_allow_gatectrl(struct clk *clk); +void omap4_dpllmx_deny_gatectrl(struct clk *clk); #ifdef CONFIG_OMAP_RESET_CLOCKS void omap2_clk_disable_unused(struct clk *clk); @@ -83,6 +82,10 @@ long omap2_clksel_round_rate(struct clk *clk, unsigned long target_rate); int omap2_clksel_set_rate(struct clk *clk, unsigned long rate); int omap2_clksel_set_parent(struct clk *clk, struct clk *new_parent); +/* clkt_iclk.c public functions */ +extern void omap2_clkt_iclk_allow_idle(struct clk *clk); +extern void omap2_clkt_iclk_deny_idle(struct clk *clk); + u32 omap2_get_dpll_rate(struct clk *clk); void omap2_init_dpll_parent(struct clk *clk); @@ -136,6 +139,7 @@ extern struct clk *vclk, *sclk; extern const struct clksel_rate gpt_32k_rates[]; extern const struct clksel_rate gpt_sys_rates[]; extern const struct clksel_rate gfx_l3_rates[]; +extern const struct clksel_rate dsp_ick_rates[]; #if defined(CONFIG_ARCH_OMAP2) && defined(CONFIG_CPU_FREQ) extern void omap2_clk_init_cpufreq_table(struct cpufreq_frequency_table **table); @@ -145,6 +149,13 @@ extern void omap2_clk_exit_cpufreq_table(struct cpufreq_frequency_table **table) #define omap2_clk_exit_cpufreq_table 0 #endif +extern const struct clkops clkops_omap2_iclk_dflt_wait; +extern const struct clkops clkops_omap2_iclk_dflt; +extern const struct clkops clkops_omap2_iclk_idle_only; +extern const struct clkops clkops_omap2_mdmclk_dflt_wait; +extern const struct clkops clkops_omap2xxx_dpll_ops; extern const struct clkops clkops_omap3_noncore_dpll_ops; +extern const struct clkops clkops_omap3_core_dpll_ops; +extern const struct clkops clkops_omap4_dpllmx_ops; #endif diff --git a/arch/arm/mach-omap2/clock2420_data.c b/arch/arm/mach-omap2/clock2420_data.c index 0a992bc8d0d..b6f65d4ac97 100644 --- a/arch/arm/mach-omap2/clock2420_data.c +++ b/arch/arm/mach-omap2/clock2420_data.c @@ -1,12 +1,12 @@ /* - * linux/arch/arm/mach-omap2/clock2420_data.c + * OMAP2420 clock data * - * Copyright (C) 2005-2009 Texas Instruments, Inc. - * Copyright (C) 2004-2010 Nokia Corporation + * Copyright (C) 2005-2009 Texas Instruments, Inc. + * Copyright (C) 2004-2011 Nokia Corporation * - * Contacts: - * Richard Woodruff <r-woodruff2@ti.com> - * Paul Walmsley + * Contacts: + * Richard Woodruff <r-woodruff2@ti.com> + * Paul Walmsley * * This program is free software; you can redistribute it and/or modify * it under the terms of the GNU General Public License version 2 as @@ -34,18 +34,15 @@ /* * 2420 clock tree. * - * NOTE:In many cases here we are assigning a 'default' parent. In many - * cases the parent is selectable. The get/set parent calls will also - * switch sources. - * - * Many some clocks say always_enabled, but they can be auto idled for - * power savings. They will always be available upon clock request. + * NOTE:In many cases here we are assigning a 'default' parent. In + * many cases the parent is selectable. The set parent calls will + * also switch sources. * * Several sources are given initial rates which may be wrong, this will * be fixed up in the init func. * * Things are broadly separated below by clock domains. It is - * noteworthy that most periferals have dependencies on multiple clock + * noteworthy that most peripherals have dependencies on multiple clock * domains. Many get their interface clocks from the L4 domain, but get * functional clocks from fixed sources or other core domain derived * clocks. @@ -55,7 +52,7 @@ static struct clk func_32k_ck = { .name = "func_32k_ck", .ops = &clkops_null, - .rate = 32000, + .rate = 32768, .clkdm_name = "wkup_clkdm", }; @@ -116,7 +113,6 @@ static struct dpll_data dpll_dd = { .max_multiplier = 1023, .min_divider = 1, .max_divider = 16, - .rate_tolerance = DEFAULT_DPLL_RATE_TOLERANCE }; /* @@ -125,7 +121,7 @@ static struct dpll_data dpll_dd = { */ static struct clk dpll_ck = { .name = "dpll_ck", - .ops = &clkops_null, + .ops = &clkops_omap2xxx_dpll_ops, .parent = &sys_ck, /* Can be func_32k also */ .dpll_data = &dpll_dd, .clkdm_name = "wkup_clkdm", @@ -455,36 +451,22 @@ static struct clk dsp_fck = { .recalc = &omap2_clksel_recalc, }; -/* DSP interface clock */ -static const struct clksel_rate dsp_irate_ick_rates[] = { - { .div = 1, .val = 1, .flags = RATE_IN_24XX }, - { .div = 2, .val = 2, .flags = RATE_IN_24XX }, - { .div = 0 }, -}; - -static const struct clksel dsp_irate_ick_clksel[] = { - { .parent = &dsp_fck, .rates = dsp_irate_ick_rates }, +static const struct clksel dsp_ick_clksel[] = { + { .parent = &dsp_fck, .rates = dsp_ick_rates }, { .parent = NULL } }; -/* This clock does not exist as such in the TRM. */ -static struct clk dsp_irate_ick = { - .name = "dsp_irate_ick", - .ops = &clkops_null, - .parent = &dsp_fck, - .clksel_reg = OMAP_CM_REGADDR(OMAP24XX_DSP_MOD, CM_CLKSEL), - .clksel_mask = OMAP24XX_CLKSEL_DSP_IF_MASK, - .clksel = dsp_irate_ick_clksel, - .recalc = &omap2_clksel_recalc, -}; - -/* 2420 only */ static struct clk dsp_ick = { .name = "dsp_ick", /* apparently ipi and isp */ - .ops = &clkops_omap2_dflt_wait, - .parent = &dsp_irate_ick, + .ops = &clkops_omap2_iclk_dflt_wait, + .parent = &dsp_fck, + .clkdm_name = "dsp_clkdm", .enable_reg = OMAP_CM_REGADDR(OMAP24XX_DSP_MOD, CM_ICLKEN), .enable_bit = OMAP2420_EN_DSP_IPI_SHIFT, /* for ipi */ + .clksel_reg = OMAP_CM_REGADDR(OMAP24XX_DSP_MOD, CM_CLKSEL), + .clksel_mask = OMAP24XX_CLKSEL_DSP_IF_MASK, + .clksel = dsp_ick_clksel, + .recalc = &omap2_clksel_recalc, }; /* @@ -579,7 +561,7 @@ static const struct clksel usb_l4_ick_clksel[] = { /* It is unclear from TRM whether usb_l4_ick is really in L3 or L4 clkdm */ static struct clk usb_l4_ick = { /* FS-USB interface clock */ .name = "usb_l4_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &core_l3_ck, .clkdm_name = "core_l4_clkdm", .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN2), @@ -661,7 +643,7 @@ static struct clk ssi_ssr_sst_fck = { */ static struct clk ssi_l4_ick = { .name = "ssi_l4_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &l4_ck, .clkdm_name = "core_l4_clkdm", .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN2), @@ -716,6 +698,7 @@ static struct clk gfx_2d_fck = { .recalc = &omap2_clksel_recalc, }; +/* This interface clock does not have a CM_AUTOIDLE bit */ static struct clk gfx_ick = { .name = "gfx_ick", /* From l3 */ .ops = &clkops_omap2_dflt_wait, @@ -763,7 +746,7 @@ static const struct clksel dss1_fck_clksel[] = { static struct clk dss_ick = { /* Enables both L3,L4 ICLK's */ .name = "dss_ick", - .ops = &clkops_omap2_dflt, + .ops = &clkops_omap2_iclk_dflt, .parent = &l4_ck, /* really both l3 and l4 */ .clkdm_name = "dss_clkdm", .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN1), @@ -825,6 +808,14 @@ static struct clk dss_54m_fck = { /* Alt clk used in power management */ .recalc = &followparent_recalc, }; +static struct clk wu_l4_ick = { + .name = "wu_l4_ick", + .ops = &clkops_null, + .parent = &sys_ck, + .clkdm_name = "wkup_clkdm", + .recalc = &followparent_recalc, +}; + /* * CORE power domain ICLK & FCLK defines. * Many of the these can have more than one possible parent. Entries @@ -845,9 +836,9 @@ static const struct clksel omap24xx_gpt_clksel[] = { static struct clk gpt1_ick = { .name = "gpt1_ick", - .ops = &clkops_omap2_dflt_wait, - .parent = &l4_ck, - .clkdm_name = "core_l4_clkdm", + .ops = &clkops_omap2_iclk_dflt_wait, + .parent = &wu_l4_ick, + .clkdm_name = "wkup_clkdm", .enable_reg = OMAP_CM_REGADDR(WKUP_MOD, CM_ICLKEN), .enable_bit = OMAP24XX_EN_GPT1_SHIFT, .recalc = &followparent_recalc, @@ -871,7 +862,7 @@ static struct clk gpt1_fck = { static struct clk gpt2_ick = { .name = "gpt2_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &l4_ck, .clkdm_name = "core_l4_clkdm", .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN1), @@ -895,7 +886,7 @@ static struct clk gpt2_fck = { static struct clk gpt3_ick = { .name = "gpt3_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &l4_ck, .clkdm_name = "core_l4_clkdm", .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN1), @@ -919,7 +910,7 @@ static struct clk gpt3_fck = { static struct clk gpt4_ick = { .name = "gpt4_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &l4_ck, .clkdm_name = "core_l4_clkdm", .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN1), @@ -943,7 +934,7 @@ static struct clk gpt4_fck = { static struct clk gpt5_ick = { .name = "gpt5_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &l4_ck, .clkdm_name = "core_l4_clkdm", .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN1), @@ -967,7 +958,7 @@ static struct clk gpt5_fck = { static struct clk gpt6_ick = { .name = "gpt6_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &l4_ck, .clkdm_name = "core_l4_clkdm", .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN1), @@ -991,8 +982,9 @@ static struct clk gpt6_fck = { static struct clk gpt7_ick = { .name = "gpt7_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &l4_ck, + .clkdm_name = "core_l4_clkdm", .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN1), .enable_bit = OMAP24XX_EN_GPT7_SHIFT, .recalc = &followparent_recalc, @@ -1014,7 +1006,7 @@ static struct clk gpt7_fck = { static struct clk gpt8_ick = { .name = "gpt8_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &l4_ck, .clkdm_name = "core_l4_clkdm", .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN1), @@ -1038,7 +1030,7 @@ static struct clk gpt8_fck = { static struct clk gpt9_ick = { .name = "gpt9_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &l4_ck, .clkdm_name = "core_l4_clkdm", .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN1), @@ -1062,7 +1054,7 @@ static struct clk gpt9_fck = { static struct clk gpt10_ick = { .name = "gpt10_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &l4_ck, .clkdm_name = "core_l4_clkdm", .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN1), @@ -1086,7 +1078,7 @@ static struct clk gpt10_fck = { static struct clk gpt11_ick = { .name = "gpt11_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &l4_ck, .clkdm_name = "core_l4_clkdm", .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN1), @@ -1110,7 +1102,7 @@ static struct clk gpt11_fck = { static struct clk gpt12_ick = { .name = "gpt12_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &l4_ck, .clkdm_name = "core_l4_clkdm", .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN1), @@ -1134,7 +1126,7 @@ static struct clk gpt12_fck = { static struct clk mcbsp1_ick = { .name = "mcbsp1_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &l4_ck, .clkdm_name = "core_l4_clkdm", .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN1), @@ -1174,7 +1166,7 @@ static struct clk mcbsp1_fck = { static struct clk mcbsp2_ick = { .name = "mcbsp2_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &l4_ck, .clkdm_name = "core_l4_clkdm", .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN1), @@ -1198,7 +1190,7 @@ static struct clk mcbsp2_fck = { static struct clk mcspi1_ick = { .name = "mcspi1_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &l4_ck, .clkdm_name = "core_l4_clkdm", .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN1), @@ -1218,7 +1210,7 @@ static struct clk mcspi1_fck = { static struct clk mcspi2_ick = { .name = "mcspi2_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &l4_ck, .clkdm_name = "core_l4_clkdm", .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN1), @@ -1238,7 +1230,7 @@ static struct clk mcspi2_fck = { static struct clk uart1_ick = { .name = "uart1_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &l4_ck, .clkdm_name = "core_l4_clkdm", .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN1), @@ -1258,7 +1250,7 @@ static struct clk uart1_fck = { static struct clk uart2_ick = { .name = "uart2_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &l4_ck, .clkdm_name = "core_l4_clkdm", .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN1), @@ -1278,7 +1270,7 @@ static struct clk uart2_fck = { static struct clk uart3_ick = { .name = "uart3_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &l4_ck, .clkdm_name = "core_l4_clkdm", .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN2), @@ -1298,9 +1290,9 @@ static struct clk uart3_fck = { static struct clk gpios_ick = { .name = "gpios_ick", - .ops = &clkops_omap2_dflt_wait, - .parent = &l4_ck, - .clkdm_name = "core_l4_clkdm", + .ops = &clkops_omap2_iclk_dflt_wait, + .parent = &wu_l4_ick, + .clkdm_name = "wkup_clkdm", .enable_reg = OMAP_CM_REGADDR(WKUP_MOD, CM_ICLKEN), .enable_bit = OMAP24XX_EN_GPIOS_SHIFT, .recalc = &followparent_recalc, @@ -1318,9 +1310,9 @@ static struct clk gpios_fck = { static struct clk mpu_wdt_ick = { .name = "mpu_wdt_ick", - .ops = &clkops_omap2_dflt_wait, - .parent = &l4_ck, - .clkdm_name = "core_l4_clkdm", + .ops = &clkops_omap2_iclk_dflt_wait, + .parent = &wu_l4_ick, + .clkdm_name = "wkup_clkdm", .enable_reg = OMAP_CM_REGADDR(WKUP_MOD, CM_ICLKEN), .enable_bit = OMAP24XX_EN_MPU_WDT_SHIFT, .recalc = &followparent_recalc, @@ -1338,10 +1330,10 @@ static struct clk mpu_wdt_fck = { static struct clk sync_32k_ick = { .name = "sync_32k_ick", - .ops = &clkops_omap2_dflt_wait, - .parent = &l4_ck, + .ops = &clkops_omap2_iclk_dflt_wait, + .parent = &wu_l4_ick, + .clkdm_name = "wkup_clkdm", .flags = ENABLE_ON_INIT, - .clkdm_name = "core_l4_clkdm", .enable_reg = OMAP_CM_REGADDR(WKUP_MOD, CM_ICLKEN), .enable_bit = OMAP24XX_EN_32KSYNC_SHIFT, .recalc = &followparent_recalc, @@ -1349,9 +1341,9 @@ static struct clk sync_32k_ick = { static struct clk wdt1_ick = { .name = "wdt1_ick", - .ops = &clkops_omap2_dflt_wait, - .parent = &l4_ck, - .clkdm_name = "core_l4_clkdm", + .ops = &clkops_omap2_iclk_dflt_wait, + .parent = &wu_l4_ick, + .clkdm_name = "wkup_clkdm", .enable_reg = OMAP_CM_REGADDR(WKUP_MOD, CM_ICLKEN), .enable_bit = OMAP24XX_EN_WDT1_SHIFT, .recalc = &followparent_recalc, @@ -1359,10 +1351,10 @@ static struct clk wdt1_ick = { static struct clk omapctrl_ick = { .name = "omapctrl_ick", - .ops = &clkops_omap2_dflt_wait, - .parent = &l4_ck, + .ops = &clkops_omap2_iclk_dflt_wait, + .parent = &wu_l4_ick, + .clkdm_name = "wkup_clkdm", .flags = ENABLE_ON_INIT, - .clkdm_name = "core_l4_clkdm", .enable_reg = OMAP_CM_REGADDR(WKUP_MOD, CM_ICLKEN), .enable_bit = OMAP24XX_EN_OMAPCTRL_SHIFT, .recalc = &followparent_recalc, @@ -1370,7 +1362,7 @@ static struct clk omapctrl_ick = { static struct clk cam_ick = { .name = "cam_ick", - .ops = &clkops_omap2_dflt, + .ops = &clkops_omap2_iclk_dflt, .parent = &l4_ck, .clkdm_name = "core_l4_clkdm", .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN1), @@ -1395,7 +1387,7 @@ static struct clk cam_fck = { static struct clk mailboxes_ick = { .name = "mailboxes_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &l4_ck, .clkdm_name = "core_l4_clkdm", .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN1), @@ -1405,7 +1397,7 @@ static struct clk mailboxes_ick = { static struct clk wdt4_ick = { .name = "wdt4_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &l4_ck, .clkdm_name = "core_l4_clkdm", .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN1), @@ -1425,7 +1417,7 @@ static struct clk wdt4_fck = { static struct clk wdt3_ick = { .name = "wdt3_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &l4_ck, .clkdm_name = "core_l4_clkdm", .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN1), @@ -1445,7 +1437,7 @@ static struct clk wdt3_fck = { static struct clk mspro_ick = { .name = "mspro_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &l4_ck, .clkdm_name = "core_l4_clkdm", .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN1), @@ -1465,7 +1457,7 @@ static struct clk mspro_fck = { static struct clk mmc_ick = { .name = "mmc_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &l4_ck, .clkdm_name = "core_l4_clkdm", .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN1), @@ -1485,7 +1477,7 @@ static struct clk mmc_fck = { static struct clk fac_ick = { .name = "fac_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &l4_ck, .clkdm_name = "core_l4_clkdm", .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN1), @@ -1505,7 +1497,7 @@ static struct clk fac_fck = { static struct clk eac_ick = { .name = "eac_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &l4_ck, .clkdm_name = "core_l4_clkdm", .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN1), @@ -1525,7 +1517,7 @@ static struct clk eac_fck = { static struct clk hdq_ick = { .name = "hdq_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &l4_ck, .clkdm_name = "core_l4_clkdm", .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN1), @@ -1545,7 +1537,7 @@ static struct clk hdq_fck = { static struct clk i2c2_ick = { .name = "i2c2_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &l4_ck, .clkdm_name = "core_l4_clkdm", .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN1), @@ -1565,7 +1557,7 @@ static struct clk i2c2_fck = { static struct clk i2c1_ick = { .name = "i2c1_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &l4_ck, .clkdm_name = "core_l4_clkdm", .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN1), @@ -1583,12 +1575,18 @@ static struct clk i2c1_fck = { .recalc = &followparent_recalc, }; +/* + * The enable_reg/enable_bit in this clock is only used for CM_AUTOIDLE + * accesses derived from this data. + */ static struct clk gpmc_fck = { .name = "gpmc_fck", - .ops = &clkops_null, /* RMK: missing? */ + .ops = &clkops_omap2_iclk_idle_only, .parent = &core_l3_ck, .flags = ENABLE_ON_INIT, .clkdm_name = "core_l3_clkdm", + .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN3), + .enable_bit = OMAP24XX_AUTO_GPMC_SHIFT, .recalc = &followparent_recalc, }; @@ -1600,17 +1598,38 @@ static struct clk sdma_fck = { .recalc = &followparent_recalc, }; +/* + * The enable_reg/enable_bit in this clock is only used for CM_AUTOIDLE + * accesses derived from this data. + */ static struct clk sdma_ick = { .name = "sdma_ick", - .ops = &clkops_null, /* RMK: missing? */ - .parent = &l4_ck, + .ops = &clkops_omap2_iclk_idle_only, + .parent = &core_l3_ck, + .clkdm_name = "core_l3_clkdm", + .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN3), + .enable_bit = OMAP24XX_AUTO_SDMA_SHIFT, + .recalc = &followparent_recalc, +}; + +/* + * The enable_reg/enable_bit in this clock is only used for CM_AUTOIDLE + * accesses derived from this data. + */ +static struct clk sdrc_ick = { + .name = "sdrc_ick", + .ops = &clkops_omap2_iclk_idle_only, + .parent = &core_l3_ck, + .flags = ENABLE_ON_INIT, .clkdm_name = "core_l3_clkdm", + .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN3), + .enable_bit = OMAP24XX_AUTO_SDRC_SHIFT, .recalc = &followparent_recalc, }; static struct clk vlynq_ick = { .name = "vlynq_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &core_l3_ck, .clkdm_name = "core_l3_clkdm", .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN1), @@ -1659,7 +1678,7 @@ static struct clk vlynq_fck = { static struct clk des_ick = { .name = "des_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &l4_ck, .clkdm_name = "core_l4_clkdm", .enable_reg = OMAP_CM_REGADDR(CORE_MOD, OMAP24XX_CM_ICLKEN4), @@ -1669,7 +1688,7 @@ static struct clk des_ick = { static struct clk sha_ick = { .name = "sha_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &l4_ck, .clkdm_name = "core_l4_clkdm", .enable_reg = OMAP_CM_REGADDR(CORE_MOD, OMAP24XX_CM_ICLKEN4), @@ -1679,7 +1698,7 @@ static struct clk sha_ick = { static struct clk rng_ick = { .name = "rng_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &l4_ck, .clkdm_name = "core_l4_clkdm", .enable_reg = OMAP_CM_REGADDR(CORE_MOD, OMAP24XX_CM_ICLKEN4), @@ -1689,7 +1708,7 @@ static struct clk rng_ick = { static struct clk aes_ick = { .name = "aes_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &l4_ck, .clkdm_name = "core_l4_clkdm", .enable_reg = OMAP_CM_REGADDR(CORE_MOD, OMAP24XX_CM_ICLKEN4), @@ -1699,7 +1718,7 @@ static struct clk aes_ick = { static struct clk pka_ick = { .name = "pka_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &l4_ck, .clkdm_name = "core_l4_clkdm", .enable_reg = OMAP_CM_REGADDR(CORE_MOD, OMAP24XX_CM_ICLKEN4), @@ -1777,7 +1796,6 @@ static struct omap_clk omap2420_clks[] = { CLK(NULL, "mpu_ck", &mpu_ck, CK_242X), /* dsp domain clocks */ CLK(NULL, "dsp_fck", &dsp_fck, CK_242X), - CLK(NULL, "dsp_irate_ick", &dsp_irate_ick, CK_242X), CLK(NULL, "dsp_ick", &dsp_ick, CK_242X), CLK(NULL, "iva1_ifck", &iva1_ifck, CK_242X), CLK(NULL, "iva1_mpu_int_ifck", &iva1_mpu_int_ifck, CK_242X), @@ -1797,6 +1815,7 @@ static struct omap_clk omap2420_clks[] = { /* L4 domain clocks */ CLK(NULL, "l4_ck", &l4_ck, CK_242X), CLK(NULL, "ssi_l4_ick", &ssi_l4_ick, CK_242X), + CLK(NULL, "wu_l4_ick", &wu_l4_ick, CK_242X), /* virtual meta-group clock */ CLK(NULL, "virt_prcm_set", &virt_prcm_set, CK_242X), /* general l4 interface ck, multi-parent functional clk */ @@ -1869,6 +1888,7 @@ static struct omap_clk omap2420_clks[] = { CLK(NULL, "gpmc_fck", &gpmc_fck, CK_242X), CLK(NULL, "sdma_fck", &sdma_fck, CK_242X), CLK(NULL, "sdma_ick", &sdma_ick, CK_242X), + CLK(NULL, "sdrc_ick", &sdrc_ick, CK_242X), CLK(NULL, "vlynq_ick", &vlynq_ick, CK_242X), CLK(NULL, "vlynq_fck", &vlynq_fck, CK_242X), CLK(NULL, "des_ick", &des_ick, CK_242X), @@ -1913,6 +1933,9 @@ int __init omap2420_clk_init(void) omap2_init_clk_clkdm(c->lk.clk); } + /* Disable autoidle on all clocks; let the PM code enable it later */ + omap_clk_disable_autoidle_all(); + /* Check the MPU rate set by bootloader */ clkrate = omap2xxx_clk_get_core_rate(&dpll_ck); for (prcm = rate_table; prcm->mpu_speed; prcm++) { diff --git a/arch/arm/mach-omap2/clock2430_data.c b/arch/arm/mach-omap2/clock2430_data.c index c047dcd007e..bba018331a7 100644 --- a/arch/arm/mach-omap2/clock2430_data.c +++ b/arch/arm/mach-omap2/clock2430_data.c @@ -1,12 +1,12 @@ /* - * linux/arch/arm/mach-omap2/clock2430_data.c + * OMAP2430 clock data * - * Copyright (C) 2005-2009 Texas Instruments, Inc. - * Copyright (C) 2004-2010 Nokia Corporation + * Copyright (C) 2005-2009 Texas Instruments, Inc. + * Copyright (C) 2004-2011 Nokia Corporation * - * Contacts: - * Richard Woodruff <r-woodruff2@ti.com> - * Paul Walmsley + * Contacts: + * Richard Woodruff <r-woodruff2@ti.com> + * Paul Walmsley * * This program is free software; you can redistribute it and/or modify * it under the terms of the GNU General Public License version 2 as @@ -34,18 +34,15 @@ /* * 2430 clock tree. * - * NOTE:In many cases here we are assigning a 'default' parent. In many - * cases the parent is selectable. The get/set parent calls will also - * switch sources. - * - * Many some clocks say always_enabled, but they can be auto idled for - * power savings. They will always be available upon clock request. + * NOTE:In many cases here we are assigning a 'default' parent. In + * many cases the parent is selectable. The set parent calls will + * also switch sources. * * Several sources are given initial rates which may be wrong, this will * be fixed up in the init func. * * Things are broadly separated below by clock domains. It is - * noteworthy that most periferals have dependencies on multiple clock + * noteworthy that most peripherals have dependencies on multiple clock * domains. Many get their interface clocks from the L4 domain, but get * functional clocks from fixed sources or other core domain derived * clocks. @@ -55,7 +52,7 @@ static struct clk func_32k_ck = { .name = "func_32k_ck", .ops = &clkops_null, - .rate = 32000, + .rate = 32768, .clkdm_name = "wkup_clkdm", }; @@ -116,7 +113,6 @@ static struct dpll_data dpll_dd = { .max_multiplier = 1023, .min_divider = 1, .max_divider = 16, - .rate_tolerance = DEFAULT_DPLL_RATE_TOLERANCE }; /* @@ -125,7 +121,7 @@ static struct dpll_data dpll_dd = { */ static struct clk dpll_ck = { .name = "dpll_ck", - .ops = &clkops_null, + .ops = &clkops_omap2xxx_dpll_ops, .parent = &sys_ck, /* Can be func_32k also */ .dpll_data = &dpll_dd, .clkdm_name = "wkup_clkdm", @@ -434,37 +430,23 @@ static struct clk dsp_fck = { .recalc = &omap2_clksel_recalc, }; -/* DSP interface clock */ -static const struct clksel_rate dsp_irate_ick_rates[] = { - { .div = 1, .val = 1, .flags = RATE_IN_24XX }, - { .div = 2, .val = 2, .flags = RATE_IN_24XX }, - { .div = 3, .val = 3, .flags = RATE_IN_243X }, - { .div = 0 }, -}; - -static const struct clksel dsp_irate_ick_clksel[] = { - { .parent = &dsp_fck, .rates = dsp_irate_ick_rates }, +static const struct clksel dsp_ick_clksel[] = { + { .parent = &dsp_fck, .rates = dsp_ick_rates }, { .parent = NULL } }; -/* This clock does not exist as such in the TRM. */ -static struct clk dsp_irate_ick = { - .name = "dsp_irate_ick", - .ops = &clkops_null, - .parent = &dsp_fck, - .clksel_reg = OMAP_CM_REGADDR(OMAP24XX_DSP_MOD, CM_CLKSEL), - .clksel_mask = OMAP24XX_CLKSEL_DSP_IF_MASK, - .clksel = dsp_irate_ick_clksel, - .recalc = &omap2_clksel_recalc, -}; - /* 2430 only - EN_DSP controls both dsp fclk and iclk on 2430 */ static struct clk iva2_1_ick = { .name = "iva2_1_ick", .ops = &clkops_omap2_dflt_wait, - .parent = &dsp_irate_ick, + .parent = &dsp_fck, + .clkdm_name = "dsp_clkdm", .enable_reg = OMAP_CM_REGADDR(OMAP24XX_DSP_MOD, CM_FCLKEN), .enable_bit = OMAP24XX_CM_FCLKEN_DSP_EN_DSP_SHIFT, + .clksel_reg = OMAP_CM_REGADDR(OMAP24XX_DSP_MOD, CM_CLKSEL), + .clksel_mask = OMAP24XX_CLKSEL_DSP_IF_MASK, + .clksel = dsp_ick_clksel, + .recalc = &omap2_clksel_recalc, }; /* @@ -525,7 +507,7 @@ static const struct clksel usb_l4_ick_clksel[] = { /* It is unclear from TRM whether usb_l4_ick is really in L3 or L4 clkdm */ static struct clk usb_l4_ick = { /* FS-USB interface clock */ .name = "usb_l4_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &core_l3_ck, .clkdm_name = "core_l4_clkdm", .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN2), @@ -606,7 +588,7 @@ static struct clk ssi_ssr_sst_fck = { */ static struct clk ssi_l4_ick = { .name = "ssi_l4_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &l4_ck, .clkdm_name = "core_l4_clkdm", .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN2), @@ -661,6 +643,7 @@ static struct clk gfx_2d_fck = { .recalc = &omap2_clksel_recalc, }; +/* This interface clock does not have a CM_AUTOIDLE bit */ static struct clk gfx_ick = { .name = "gfx_ick", /* From l3 */ .ops = &clkops_omap2_dflt_wait, @@ -693,7 +676,7 @@ static const struct clksel mdm_ick_clksel[] = { static struct clk mdm_ick = { /* used both as a ick and fck */ .name = "mdm_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &core_ck, .clkdm_name = "mdm_clkdm", .enable_reg = OMAP_CM_REGADDR(OMAP2430_MDM_MOD, CM_ICLKEN), @@ -706,7 +689,7 @@ static struct clk mdm_ick = { /* used both as a ick and fck */ static struct clk mdm_osc_ck = { .name = "mdm_osc_ck", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_mdmclk_dflt_wait, .parent = &osc_ck, .clkdm_name = "mdm_clkdm", .enable_reg = OMAP_CM_REGADDR(OMAP2430_MDM_MOD, CM_FCLKEN), @@ -751,7 +734,7 @@ static const struct clksel dss1_fck_clksel[] = { static struct clk dss_ick = { /* Enables both L3,L4 ICLK's */ .name = "dss_ick", - .ops = &clkops_omap2_dflt, + .ops = &clkops_omap2_iclk_dflt, .parent = &l4_ck, /* really both l3 and l4 */ .clkdm_name = "dss_clkdm", .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN1), @@ -813,6 +796,14 @@ static struct clk dss_54m_fck = { /* Alt clk used in power management */ .recalc = &followparent_recalc, }; +static struct clk wu_l4_ick = { + .name = "wu_l4_ick", + .ops = &clkops_null, + .parent = &sys_ck, + .clkdm_name = "wkup_clkdm", + .recalc = &followparent_recalc, +}; + /* * CORE power domain ICLK & FCLK defines. * Many of the these can have more than one possible parent. Entries @@ -833,9 +824,9 @@ static const struct clksel omap24xx_gpt_clksel[] = { static struct clk gpt1_ick = { .name = "gpt1_ick", - .ops = &clkops_omap2_dflt_wait, - .parent = &l4_ck, - .clkdm_name = "core_l4_clkdm", + .ops = &clkops_omap2_iclk_dflt_wait, + .parent = &wu_l4_ick, + .clkdm_name = "wkup_clkdm", .enable_reg = OMAP_CM_REGADDR(WKUP_MOD, CM_ICLKEN), .enable_bit = OMAP24XX_EN_GPT1_SHIFT, .recalc = &followparent_recalc, @@ -859,7 +850,7 @@ static struct clk gpt1_fck = { static struct clk gpt2_ick = { .name = "gpt2_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &l4_ck, .clkdm_name = "core_l4_clkdm", .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN1), @@ -883,7 +874,7 @@ static struct clk gpt2_fck = { static struct clk gpt3_ick = { .name = "gpt3_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &l4_ck, .clkdm_name = "core_l4_clkdm", .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN1), @@ -907,7 +898,7 @@ static struct clk gpt3_fck = { static struct clk gpt4_ick = { .name = "gpt4_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &l4_ck, .clkdm_name = "core_l4_clkdm", .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN1), @@ -931,7 +922,7 @@ static struct clk gpt4_fck = { static struct clk gpt5_ick = { .name = "gpt5_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &l4_ck, .clkdm_name = "core_l4_clkdm", .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN1), @@ -955,7 +946,7 @@ static struct clk gpt5_fck = { static struct clk gpt6_ick = { .name = "gpt6_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &l4_ck, .clkdm_name = "core_l4_clkdm", .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN1), @@ -979,8 +970,9 @@ static struct clk gpt6_fck = { static struct clk gpt7_ick = { .name = "gpt7_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &l4_ck, + .clkdm_name = "core_l4_clkdm", .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN1), .enable_bit = OMAP24XX_EN_GPT7_SHIFT, .recalc = &followparent_recalc, @@ -1002,7 +994,7 @@ static struct clk gpt7_fck = { static struct clk gpt8_ick = { .name = "gpt8_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &l4_ck, .clkdm_name = "core_l4_clkdm", .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN1), @@ -1026,7 +1018,7 @@ static struct clk gpt8_fck = { static struct clk gpt9_ick = { .name = "gpt9_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &l4_ck, .clkdm_name = "core_l4_clkdm", .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN1), @@ -1050,7 +1042,7 @@ static struct clk gpt9_fck = { static struct clk gpt10_ick = { .name = "gpt10_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &l4_ck, .clkdm_name = "core_l4_clkdm", .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN1), @@ -1074,7 +1066,7 @@ static struct clk gpt10_fck = { static struct clk gpt11_ick = { .name = "gpt11_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &l4_ck, .clkdm_name = "core_l4_clkdm", .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN1), @@ -1098,7 +1090,7 @@ static struct clk gpt11_fck = { static struct clk gpt12_ick = { .name = "gpt12_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &l4_ck, .clkdm_name = "core_l4_clkdm", .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN1), @@ -1122,7 +1114,7 @@ static struct clk gpt12_fck = { static struct clk mcbsp1_ick = { .name = "mcbsp1_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &l4_ck, .clkdm_name = "core_l4_clkdm", .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN1), @@ -1162,7 +1154,7 @@ static struct clk mcbsp1_fck = { static struct clk mcbsp2_ick = { .name = "mcbsp2_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &l4_ck, .clkdm_name = "core_l4_clkdm", .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN1), @@ -1186,7 +1178,7 @@ static struct clk mcbsp2_fck = { static struct clk mcbsp3_ick = { .name = "mcbsp3_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &l4_ck, .clkdm_name = "core_l4_clkdm", .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN2), @@ -1210,7 +1202,7 @@ static struct clk mcbsp3_fck = { static struct clk mcbsp4_ick = { .name = "mcbsp4_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &l4_ck, .clkdm_name = "core_l4_clkdm", .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN2), @@ -1234,7 +1226,7 @@ static struct clk mcbsp4_fck = { static struct clk mcbsp5_ick = { .name = "mcbsp5_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &l4_ck, .clkdm_name = "core_l4_clkdm", .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN2), @@ -1258,7 +1250,7 @@ static struct clk mcbsp5_fck = { static struct clk mcspi1_ick = { .name = "mcspi1_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &l4_ck, .clkdm_name = "core_l4_clkdm", .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN1), @@ -1278,7 +1270,7 @@ static struct clk mcspi1_fck = { static struct clk mcspi2_ick = { .name = "mcspi2_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &l4_ck, .clkdm_name = "core_l4_clkdm", .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN1), @@ -1298,7 +1290,7 @@ static struct clk mcspi2_fck = { static struct clk mcspi3_ick = { .name = "mcspi3_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &l4_ck, .clkdm_name = "core_l4_clkdm", .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN2), @@ -1318,7 +1310,7 @@ static struct clk mcspi3_fck = { static struct clk uart1_ick = { .name = "uart1_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &l4_ck, .clkdm_name = "core_l4_clkdm", .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN1), @@ -1338,7 +1330,7 @@ static struct clk uart1_fck = { static struct clk uart2_ick = { .name = "uart2_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &l4_ck, .clkdm_name = "core_l4_clkdm", .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN1), @@ -1358,7 +1350,7 @@ static struct clk uart2_fck = { static struct clk uart3_ick = { .name = "uart3_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &l4_ck, .clkdm_name = "core_l4_clkdm", .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN2), @@ -1378,9 +1370,9 @@ static struct clk uart3_fck = { static struct clk gpios_ick = { .name = "gpios_ick", - .ops = &clkops_omap2_dflt_wait, - .parent = &l4_ck, - .clkdm_name = "core_l4_clkdm", + .ops = &clkops_omap2_iclk_dflt_wait, + .parent = &wu_l4_ick, + .clkdm_name = "wkup_clkdm", .enable_reg = OMAP_CM_REGADDR(WKUP_MOD, CM_ICLKEN), .enable_bit = OMAP24XX_EN_GPIOS_SHIFT, .recalc = &followparent_recalc, @@ -1398,9 +1390,9 @@ static struct clk gpios_fck = { static struct clk mpu_wdt_ick = { .name = "mpu_wdt_ick", - .ops = &clkops_omap2_dflt_wait, - .parent = &l4_ck, - .clkdm_name = "core_l4_clkdm", + .ops = &clkops_omap2_iclk_dflt_wait, + .parent = &wu_l4_ick, + .clkdm_name = "wkup_clkdm", .enable_reg = OMAP_CM_REGADDR(WKUP_MOD, CM_ICLKEN), .enable_bit = OMAP24XX_EN_MPU_WDT_SHIFT, .recalc = &followparent_recalc, @@ -1418,10 +1410,10 @@ static struct clk mpu_wdt_fck = { static struct clk sync_32k_ick = { .name = "sync_32k_ick", - .ops = &clkops_omap2_dflt_wait, - .parent = &l4_ck, + .ops = &clkops_omap2_iclk_dflt_wait, .flags = ENABLE_ON_INIT, - .clkdm_name = "core_l4_clkdm", + .parent = &wu_l4_ick, + .clkdm_name = "wkup_clkdm", .enable_reg = OMAP_CM_REGADDR(WKUP_MOD, CM_ICLKEN), .enable_bit = OMAP24XX_EN_32KSYNC_SHIFT, .recalc = &followparent_recalc, @@ -1429,9 +1421,9 @@ static struct clk sync_32k_ick = { static struct clk wdt1_ick = { .name = "wdt1_ick", - .ops = &clkops_omap2_dflt_wait, - .parent = &l4_ck, - .clkdm_name = "core_l4_clkdm", + .ops = &clkops_omap2_iclk_dflt_wait, + .parent = &wu_l4_ick, + .clkdm_name = "wkup_clkdm", .enable_reg = OMAP_CM_REGADDR(WKUP_MOD, CM_ICLKEN), .enable_bit = OMAP24XX_EN_WDT1_SHIFT, .recalc = &followparent_recalc, @@ -1439,10 +1431,10 @@ static struct clk wdt1_ick = { static struct clk omapctrl_ick = { .name = "omapctrl_ick", - .ops = &clkops_omap2_dflt_wait, - .parent = &l4_ck, + .ops = &clkops_omap2_iclk_dflt_wait, .flags = ENABLE_ON_INIT, - .clkdm_name = "core_l4_clkdm", + .parent = &wu_l4_ick, + .clkdm_name = "wkup_clkdm", .enable_reg = OMAP_CM_REGADDR(WKUP_MOD, CM_ICLKEN), .enable_bit = OMAP24XX_EN_OMAPCTRL_SHIFT, .recalc = &followparent_recalc, @@ -1450,9 +1442,9 @@ static struct clk omapctrl_ick = { static struct clk icr_ick = { .name = "icr_ick", - .ops = &clkops_omap2_dflt_wait, - .parent = &l4_ck, - .clkdm_name = "core_l4_clkdm", + .ops = &clkops_omap2_iclk_dflt_wait, + .parent = &wu_l4_ick, + .clkdm_name = "wkup_clkdm", .enable_reg = OMAP_CM_REGADDR(WKUP_MOD, CM_ICLKEN), .enable_bit = OMAP2430_EN_ICR_SHIFT, .recalc = &followparent_recalc, @@ -1460,7 +1452,7 @@ static struct clk icr_ick = { static struct clk cam_ick = { .name = "cam_ick", - .ops = &clkops_omap2_dflt, + .ops = &clkops_omap2_iclk_dflt, .parent = &l4_ck, .clkdm_name = "core_l4_clkdm", .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN1), @@ -1485,7 +1477,7 @@ static struct clk cam_fck = { static struct clk mailboxes_ick = { .name = "mailboxes_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &l4_ck, .clkdm_name = "core_l4_clkdm", .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN1), @@ -1495,7 +1487,7 @@ static struct clk mailboxes_ick = { static struct clk wdt4_ick = { .name = "wdt4_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &l4_ck, .clkdm_name = "core_l4_clkdm", .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN1), @@ -1515,7 +1507,7 @@ static struct clk wdt4_fck = { static struct clk mspro_ick = { .name = "mspro_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &l4_ck, .clkdm_name = "core_l4_clkdm", .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN1), @@ -1535,7 +1527,7 @@ static struct clk mspro_fck = { static struct clk fac_ick = { .name = "fac_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &l4_ck, .clkdm_name = "core_l4_clkdm", .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN1), @@ -1555,7 +1547,7 @@ static struct clk fac_fck = { static struct clk hdq_ick = { .name = "hdq_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &l4_ck, .clkdm_name = "core_l4_clkdm", .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN1), @@ -1579,7 +1571,7 @@ static struct clk hdq_fck = { */ static struct clk i2c2_ick = { .name = "i2c2_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &l4_ck, .clkdm_name = "core_l4_clkdm", .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN1), @@ -1603,7 +1595,7 @@ static struct clk i2chs2_fck = { */ static struct clk i2c1_ick = { .name = "i2c1_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &l4_ck, .clkdm_name = "core_l4_clkdm", .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN1), @@ -1621,12 +1613,18 @@ static struct clk i2chs1_fck = { .recalc = &followparent_recalc, }; +/* + * The enable_reg/enable_bit in this clock is only used for CM_AUTOIDLE + * accesses derived from this data. + */ static struct clk gpmc_fck = { .name = "gpmc_fck", - .ops = &clkops_null, /* RMK: missing? */ + .ops = &clkops_omap2_iclk_idle_only, .parent = &core_l3_ck, .flags = ENABLE_ON_INIT, .clkdm_name = "core_l3_clkdm", + .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN3), + .enable_bit = OMAP24XX_AUTO_GPMC_SHIFT, .recalc = &followparent_recalc, }; @@ -1638,20 +1636,26 @@ static struct clk sdma_fck = { .recalc = &followparent_recalc, }; +/* + * The enable_reg/enable_bit in this clock is only used for CM_AUTOIDLE + * accesses derived from this data. + */ static struct clk sdma_ick = { .name = "sdma_ick", - .ops = &clkops_null, /* RMK: missing? */ - .parent = &l4_ck, + .ops = &clkops_omap2_iclk_idle_only, + .parent = &core_l3_ck, .clkdm_name = "core_l3_clkdm", + .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN3), + .enable_bit = OMAP24XX_AUTO_SDMA_SHIFT, .recalc = &followparent_recalc, }; static struct clk sdrc_ick = { .name = "sdrc_ick", - .ops = &clkops_omap2_dflt_wait, - .parent = &l4_ck, + .ops = &clkops_omap2_iclk_idle_only, + .parent = &core_l3_ck, .flags = ENABLE_ON_INIT, - .clkdm_name = "core_l4_clkdm", + .clkdm_name = "core_l3_clkdm", .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN3), .enable_bit = OMAP2430_EN_SDRC_SHIFT, .recalc = &followparent_recalc, @@ -1659,7 +1663,7 @@ static struct clk sdrc_ick = { static struct clk des_ick = { .name = "des_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &l4_ck, .clkdm_name = "core_l4_clkdm", .enable_reg = OMAP_CM_REGADDR(CORE_MOD, OMAP24XX_CM_ICLKEN4), @@ -1669,7 +1673,7 @@ static struct clk des_ick = { static struct clk sha_ick = { .name = "sha_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &l4_ck, .clkdm_name = "core_l4_clkdm", .enable_reg = OMAP_CM_REGADDR(CORE_MOD, OMAP24XX_CM_ICLKEN4), @@ -1679,7 +1683,7 @@ static struct clk sha_ick = { static struct clk rng_ick = { .name = "rng_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &l4_ck, .clkdm_name = "core_l4_clkdm", .enable_reg = OMAP_CM_REGADDR(CORE_MOD, OMAP24XX_CM_ICLKEN4), @@ -1689,7 +1693,7 @@ static struct clk rng_ick = { static struct clk aes_ick = { .name = "aes_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &l4_ck, .clkdm_name = "core_l4_clkdm", .enable_reg = OMAP_CM_REGADDR(CORE_MOD, OMAP24XX_CM_ICLKEN4), @@ -1699,7 +1703,7 @@ static struct clk aes_ick = { static struct clk pka_ick = { .name = "pka_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &l4_ck, .clkdm_name = "core_l4_clkdm", .enable_reg = OMAP_CM_REGADDR(CORE_MOD, OMAP24XX_CM_ICLKEN4), @@ -1719,7 +1723,7 @@ static struct clk usb_fck = { static struct clk usbhs_ick = { .name = "usbhs_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &core_l3_ck, .clkdm_name = "core_l3_clkdm", .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN2), @@ -1729,7 +1733,7 @@ static struct clk usbhs_ick = { static struct clk mmchs1_ick = { .name = "mmchs1_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &l4_ck, .clkdm_name = "core_l4_clkdm", .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN2), @@ -1741,7 +1745,7 @@ static struct clk mmchs1_fck = { .name = "mmchs1_fck", .ops = &clkops_omap2_dflt_wait, .parent = &func_96m_ck, - .clkdm_name = "core_l3_clkdm", + .clkdm_name = "core_l4_clkdm", .enable_reg = OMAP_CM_REGADDR(CORE_MOD, OMAP24XX_CM_FCLKEN2), .enable_bit = OMAP2430_EN_MMCHS1_SHIFT, .recalc = &followparent_recalc, @@ -1749,7 +1753,7 @@ static struct clk mmchs1_fck = { static struct clk mmchs2_ick = { .name = "mmchs2_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &l4_ck, .clkdm_name = "core_l4_clkdm", .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN2), @@ -1761,6 +1765,7 @@ static struct clk mmchs2_fck = { .name = "mmchs2_fck", .ops = &clkops_omap2_dflt_wait, .parent = &func_96m_ck, + .clkdm_name = "core_l4_clkdm", .enable_reg = OMAP_CM_REGADDR(CORE_MOD, OMAP24XX_CM_FCLKEN2), .enable_bit = OMAP2430_EN_MMCHS2_SHIFT, .recalc = &followparent_recalc, @@ -1768,7 +1773,7 @@ static struct clk mmchs2_fck = { static struct clk gpio5_ick = { .name = "gpio5_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &l4_ck, .clkdm_name = "core_l4_clkdm", .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN2), @@ -1788,7 +1793,7 @@ static struct clk gpio5_fck = { static struct clk mdm_intc_ick = { .name = "mdm_intc_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &l4_ck, .clkdm_name = "core_l4_clkdm", .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN2), @@ -1880,7 +1885,6 @@ static struct omap_clk omap2430_clks[] = { CLK(NULL, "mpu_ck", &mpu_ck, CK_243X), /* dsp domain clocks */ CLK(NULL, "dsp_fck", &dsp_fck, CK_243X), - CLK(NULL, "dsp_irate_ick", &dsp_irate_ick, CK_243X), CLK(NULL, "iva2_1_ick", &iva2_1_ick, CK_243X), /* GFX domain clocks */ CLK(NULL, "gfx_3d_fck", &gfx_3d_fck, CK_243X), @@ -1901,6 +1905,7 @@ static struct omap_clk omap2430_clks[] = { /* L4 domain clocks */ CLK(NULL, "l4_ck", &l4_ck, CK_243X), CLK(NULL, "ssi_l4_ick", &ssi_l4_ick, CK_243X), + CLK(NULL, "wu_l4_ick", &wu_l4_ick, CK_243X), /* virtual meta-group clock */ CLK(NULL, "virt_prcm_set", &virt_prcm_set, CK_243X), /* general l4 interface ck, multi-parent functional clk */ @@ -1984,15 +1989,15 @@ static struct omap_clk omap2430_clks[] = { CLK(NULL, "pka_ick", &pka_ick, CK_243X), CLK(NULL, "usb_fck", &usb_fck, CK_243X), CLK("musb-omap2430", "ick", &usbhs_ick, CK_243X), - CLK("mmci-omap-hs.0", "ick", &mmchs1_ick, CK_243X), - CLK("mmci-omap-hs.0", "fck", &mmchs1_fck, CK_243X), - CLK("mmci-omap-hs.1", "ick", &mmchs2_ick, CK_243X), - CLK("mmci-omap-hs.1", "fck", &mmchs2_fck, CK_243X), + CLK("omap_hsmmc.0", "ick", &mmchs1_ick, CK_243X), + CLK("omap_hsmmc.0", "fck", &mmchs1_fck, CK_243X), + CLK("omap_hsmmc.1", "ick", &mmchs2_ick, CK_243X), + CLK("omap_hsmmc.1", "fck", &mmchs2_fck, CK_243X), CLK(NULL, "gpio5_ick", &gpio5_ick, CK_243X), CLK(NULL, "gpio5_fck", &gpio5_fck, CK_243X), CLK(NULL, "mdm_intc_ick", &mdm_intc_ick, CK_243X), - CLK("mmci-omap-hs.0", "mmchsdb_fck", &mmchsdb1_fck, CK_243X), - CLK("mmci-omap-hs.1", "mmchsdb_fck", &mmchsdb2_fck, CK_243X), + CLK("omap_hsmmc.0", "mmchsdb_fck", &mmchsdb1_fck, CK_243X), + CLK("omap_hsmmc.1", "mmchsdb_fck", &mmchsdb2_fck, CK_243X), }; /* @@ -2028,6 +2033,9 @@ int __init omap2430_clk_init(void) omap2_init_clk_clkdm(c->lk.clk); } + /* Disable autoidle on all clocks; let the PM code enable it later */ + omap_clk_disable_autoidle_all(); + /* Check the MPU rate set by bootloader */ clkrate = omap2xxx_clk_get_core_rate(&dpll_ck); for (prcm = rate_table; prcm->mpu_speed; prcm++) { diff --git a/arch/arm/mach-omap2/clock2xxx.h b/arch/arm/mach-omap2/clock2xxx.h index 6a658b890c1..cb6df8ca9e4 100644 --- a/arch/arm/mach-omap2/clock2xxx.h +++ b/arch/arm/mach-omap2/clock2xxx.h @@ -20,16 +20,16 @@ u32 omap2xxx_get_apll_clkin(void); u32 omap2xxx_get_sysclkdiv(void); void omap2xxx_clk_prepare_for_reboot(void); -#ifdef CONFIG_ARCH_OMAP2420 +#ifdef CONFIG_SOC_OMAP2420 int omap2420_clk_init(void); #else -#define omap2420_clk_init() 0 +#define omap2420_clk_init() do { } while(0) #endif -#ifdef CONFIG_ARCH_OMAP2430 +#ifdef CONFIG_SOC_OMAP2430 int omap2430_clk_init(void); #else -#define omap2430_clk_init() 0 +#define omap2430_clk_init() do { } while(0) #endif extern void __iomem *prcm_clksrc_ctrl, *cm_idlest_pll; diff --git a/arch/arm/mach-omap2/clock34xx.c b/arch/arm/mach-omap2/clock34xx.c index 287abc48092..1fc96b9ee33 100644 --- a/arch/arm/mach-omap2/clock34xx.c +++ b/arch/arm/mach-omap2/clock34xx.c @@ -2,7 +2,7 @@ * OMAP3-specific clock framework functions * * Copyright (C) 2007-2008 Texas Instruments, Inc. - * Copyright (C) 2007-2010 Nokia Corporation + * Copyright (C) 2007-2011 Nokia Corporation * * Paul Walmsley * Jouni Högander @@ -59,6 +59,15 @@ const struct clkops clkops_omap3430es2_ssi_wait = { .find_companion = omap2_clk_dflt_find_companion, }; +const struct clkops clkops_omap3430es2_iclk_ssi_wait = { + .enable = omap2_dflt_clk_enable, + .disable = omap2_dflt_clk_disable, + .find_idlest = omap3430es2_clk_ssi_find_idlest, + .find_companion = omap2_clk_dflt_find_companion, + .allow_idle = omap2_clkt_iclk_allow_idle, + .deny_idle = omap2_clkt_iclk_deny_idle, +}; + /** * omap3430es2_clk_dss_usbhost_find_idlest - CM_IDLEST info for DSS, USBHOST * @clk: struct clk * being enabled @@ -94,6 +103,15 @@ const struct clkops clkops_omap3430es2_dss_usbhost_wait = { .find_companion = omap2_clk_dflt_find_companion, }; +const struct clkops clkops_omap3430es2_iclk_dss_usbhost_wait = { + .enable = omap2_dflt_clk_enable, + .disable = omap2_dflt_clk_disable, + .find_idlest = omap3430es2_clk_dss_usbhost_find_idlest, + .find_companion = omap2_clk_dflt_find_companion, + .allow_idle = omap2_clkt_iclk_allow_idle, + .deny_idle = omap2_clkt_iclk_deny_idle, +}; + /** * omap3430es2_clk_hsotgusb_find_idlest - return CM_IDLEST info for HSOTGUSB * @clk: struct clk * being enabled @@ -124,3 +142,12 @@ const struct clkops clkops_omap3430es2_hsotgusb_wait = { .find_idlest = omap3430es2_clk_hsotgusb_find_idlest, .find_companion = omap2_clk_dflt_find_companion, }; + +const struct clkops clkops_omap3430es2_iclk_hsotgusb_wait = { + .enable = omap2_dflt_clk_enable, + .disable = omap2_dflt_clk_disable, + .find_idlest = omap3430es2_clk_hsotgusb_find_idlest, + .find_companion = omap2_clk_dflt_find_companion, + .allow_idle = omap2_clkt_iclk_allow_idle, + .deny_idle = omap2_clkt_iclk_deny_idle, +}; diff --git a/arch/arm/mach-omap2/clock34xx.h b/arch/arm/mach-omap2/clock34xx.h index 628e8de5768..084ba71b2b3 100644 --- a/arch/arm/mach-omap2/clock34xx.h +++ b/arch/arm/mach-omap2/clock34xx.h @@ -2,14 +2,17 @@ * OMAP34xx clock function prototypes and macros * * Copyright (C) 2007-2010 Texas Instruments, Inc. - * Copyright (C) 2007-2010 Nokia Corporation + * Copyright (C) 2007-2011 Nokia Corporation */ #ifndef __ARCH_ARM_MACH_OMAP2_CLOCK34XX_H #define __ARCH_ARM_MACH_OMAP2_CLOCK34XX_H extern const struct clkops clkops_omap3430es2_ssi_wait; +extern const struct clkops clkops_omap3430es2_iclk_ssi_wait; extern const struct clkops clkops_omap3430es2_hsotgusb_wait; +extern const struct clkops clkops_omap3430es2_iclk_hsotgusb_wait; extern const struct clkops clkops_omap3430es2_dss_usbhost_wait; +extern const struct clkops clkops_omap3430es2_iclk_dss_usbhost_wait; #endif diff --git a/arch/arm/mach-omap2/clock3517.c b/arch/arm/mach-omap2/clock3517.c index 74116a3cf09..2e97d08f0e5 100644 --- a/arch/arm/mach-omap2/clock3517.c +++ b/arch/arm/mach-omap2/clock3517.c @@ -2,7 +2,7 @@ * OMAP3517/3505-specific clock framework functions * * Copyright (C) 2010 Texas Instruments, Inc. - * Copyright (C) 2010 Nokia Corporation + * Copyright (C) 2011 Nokia Corporation * * Ranjith Lohithakshan * Paul Walmsley @@ -119,6 +119,8 @@ const struct clkops clkops_am35xx_ipss_wait = { .disable = omap2_dflt_clk_disable, .find_idlest = am35xx_clk_ipss_find_idlest, .find_companion = omap2_clk_dflt_find_companion, + .allow_idle = omap2_clkt_iclk_allow_idle, + .deny_idle = omap2_clkt_iclk_deny_idle, }; diff --git a/arch/arm/mach-omap2/clock3xxx.c b/arch/arm/mach-omap2/clock3xxx.c index e9f66b6dec1..952c3e01c9e 100644 --- a/arch/arm/mach-omap2/clock3xxx.c +++ b/arch/arm/mach-omap2/clock3xxx.c @@ -65,9 +65,6 @@ void __init omap3_clk_lock_dpll5(void) clk_set_rate(dpll5_clk, DPLL5_FREQ_FOR_USBHOST); clk_enable(dpll5_clk); - /* Enable autoidle to allow it to enter low power bypass */ - omap3_dpll_allow_idle(dpll5_clk); - /* Program dpll5_m2_clk divider for no division */ dpll5_m2_clk = clk_get(NULL, "dpll5_m2_ck"); clk_enable(dpll5_m2_clk); diff --git a/arch/arm/mach-omap2/clock3xxx_data.c b/arch/arm/mach-omap2/clock3xxx_data.c index fbb1e30a73d..fcb321a64f1 100644 --- a/arch/arm/mach-omap2/clock3xxx_data.c +++ b/arch/arm/mach-omap2/clock3xxx_data.c @@ -2,7 +2,7 @@ * OMAP3 clock data * * Copyright (C) 2007-2010 Texas Instruments, Inc. - * Copyright (C) 2007-2010 Nokia Corporation + * Copyright (C) 2007-2011 Nokia Corporation * * Written by Paul Walmsley * With many device clock fixes by Kevin Hilman and Jouni Högander @@ -291,12 +291,11 @@ static struct dpll_data dpll1_dd = { .max_multiplier = OMAP3_MAX_DPLL_MULT, .min_divider = 1, .max_divider = OMAP3_MAX_DPLL_DIV, - .rate_tolerance = DEFAULT_DPLL_RATE_TOLERANCE }; static struct clk dpll1_ck = { .name = "dpll1_ck", - .ops = &clkops_null, + .ops = &clkops_omap3_noncore_dpll_ops, .parent = &sys_ck, .dpll_data = &dpll1_dd, .round_rate = &omap2_dpll_round_rate, @@ -364,7 +363,6 @@ static struct dpll_data dpll2_dd = { .max_multiplier = OMAP3_MAX_DPLL_MULT, .min_divider = 1, .max_divider = OMAP3_MAX_DPLL_DIV, - .rate_tolerance = DEFAULT_DPLL_RATE_TOLERANCE }; static struct clk dpll2_ck = { @@ -424,12 +422,11 @@ static struct dpll_data dpll3_dd = { .max_multiplier = OMAP3_MAX_DPLL_MULT, .min_divider = 1, .max_divider = OMAP3_MAX_DPLL_DIV, - .rate_tolerance = DEFAULT_DPLL_RATE_TOLERANCE }; static struct clk dpll3_ck = { .name = "dpll3_ck", - .ops = &clkops_null, + .ops = &clkops_omap3_core_dpll_ops, .parent = &sys_ck, .dpll_data = &dpll3_dd, .round_rate = &omap2_dpll_round_rate, @@ -583,7 +580,6 @@ static struct dpll_data dpll4_dd_34xx __initdata = { .max_multiplier = OMAP3_MAX_DPLL_MULT, .min_divider = 1, .max_divider = OMAP3_MAX_DPLL_DIV, - .rate_tolerance = DEFAULT_DPLL_RATE_TOLERANCE }; static struct dpll_data dpll4_dd_3630 __initdata = { @@ -607,7 +603,6 @@ static struct dpll_data dpll4_dd_3630 __initdata = { .max_multiplier = OMAP3630_MAX_JTYPE_DPLL_MULT, .min_divider = 1, .max_divider = OMAP3_MAX_DPLL_DIV, - .rate_tolerance = DEFAULT_DPLL_RATE_TOLERANCE, .flags = DPLL_J_TYPE }; @@ -939,7 +934,6 @@ static struct dpll_data dpll5_dd = { .max_multiplier = OMAP3_MAX_DPLL_MULT, .min_divider = 1, .max_divider = OMAP3_MAX_DPLL_DIV, - .rate_tolerance = DEFAULT_DPLL_RATE_TOLERANCE }; static struct clk dpll5_ck = { @@ -1205,7 +1199,10 @@ static const struct clksel gfx_l3_clksel[] = { { .parent = NULL } }; -/* Virtual parent clock for gfx_l3_ick and gfx_l3_fck */ +/* + * Virtual parent clock for gfx_l3_ick and gfx_l3_fck + * This interface clock does not have a CM_AUTOIDLE bit + */ static struct clk gfx_l3_ck = { .name = "gfx_l3_ck", .ops = &clkops_omap2_dflt_wait, @@ -1304,6 +1301,7 @@ static struct clk sgx_fck = { .round_rate = &omap2_clksel_round_rate }; +/* This interface clock does not have a CM_AUTOIDLE bit */ static struct clk sgx_ick = { .name = "sgx_ick", .ops = &clkops_omap2_dflt_wait, @@ -1328,7 +1326,7 @@ static struct clk d2d_26m_fck = { static struct clk modem_fck = { .name = "modem_fck", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_mdmclk_dflt_wait, .parent = &sys_ck, .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_FCLKEN1), .enable_bit = OMAP3430_EN_MODEM_SHIFT, @@ -1338,7 +1336,7 @@ static struct clk modem_fck = { static struct clk sad2d_ick = { .name = "sad2d_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &l3_ick, .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN1), .enable_bit = OMAP3430_EN_SAD2D_SHIFT, @@ -1348,7 +1346,7 @@ static struct clk sad2d_ick = { static struct clk mad2d_ick = { .name = "mad2d_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &l3_ick, .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN3), .enable_bit = OMAP3430_EN_MAD2D_SHIFT, @@ -1718,7 +1716,7 @@ static struct clk core_l3_ick = { static struct clk hsotgusb_ick_3430es1 = { .name = "hsotgusb_ick", - .ops = &clkops_omap2_dflt, + .ops = &clkops_omap2_iclk_dflt, .parent = &core_l3_ick, .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN1), .enable_bit = OMAP3430_EN_HSOTGUSB_SHIFT, @@ -1728,7 +1726,7 @@ static struct clk hsotgusb_ick_3430es1 = { static struct clk hsotgusb_ick_3430es2 = { .name = "hsotgusb_ick", - .ops = &clkops_omap3430es2_hsotgusb_wait, + .ops = &clkops_omap3430es2_iclk_hsotgusb_wait, .parent = &core_l3_ick, .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN1), .enable_bit = OMAP3430_EN_HSOTGUSB_SHIFT, @@ -1736,6 +1734,7 @@ static struct clk hsotgusb_ick_3430es2 = { .recalc = &followparent_recalc, }; +/* This interface clock does not have a CM_AUTOIDLE bit */ static struct clk sdrc_ick = { .name = "sdrc_ick", .ops = &clkops_omap2_dflt_wait, @@ -1767,7 +1766,7 @@ static struct clk security_l3_ick = { static struct clk pka_ick = { .name = "pka_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &security_l3_ick, .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN2), .enable_bit = OMAP3430_EN_PKA_SHIFT, @@ -1786,7 +1785,7 @@ static struct clk core_l4_ick = { static struct clk usbtll_ick = { .name = "usbtll_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &core_l4_ick, .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN3), .enable_bit = OMAP3430ES2_EN_USBTLL_SHIFT, @@ -1796,7 +1795,7 @@ static struct clk usbtll_ick = { static struct clk mmchs3_ick = { .name = "mmchs3_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &core_l4_ick, .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN1), .enable_bit = OMAP3430ES2_EN_MMC3_SHIFT, @@ -1807,7 +1806,7 @@ static struct clk mmchs3_ick = { /* Intersystem Communication Registers - chassis mode only */ static struct clk icr_ick = { .name = "icr_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &core_l4_ick, .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN1), .enable_bit = OMAP3430_EN_ICR_SHIFT, @@ -1817,7 +1816,7 @@ static struct clk icr_ick = { static struct clk aes2_ick = { .name = "aes2_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &core_l4_ick, .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN1), .enable_bit = OMAP3430_EN_AES2_SHIFT, @@ -1827,7 +1826,7 @@ static struct clk aes2_ick = { static struct clk sha12_ick = { .name = "sha12_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &core_l4_ick, .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN1), .enable_bit = OMAP3430_EN_SHA12_SHIFT, @@ -1837,7 +1836,7 @@ static struct clk sha12_ick = { static struct clk des2_ick = { .name = "des2_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &core_l4_ick, .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN1), .enable_bit = OMAP3430_EN_DES2_SHIFT, @@ -1847,7 +1846,7 @@ static struct clk des2_ick = { static struct clk mmchs2_ick = { .name = "mmchs2_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &core_l4_ick, .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN1), .enable_bit = OMAP3430_EN_MMC2_SHIFT, @@ -1857,7 +1856,7 @@ static struct clk mmchs2_ick = { static struct clk mmchs1_ick = { .name = "mmchs1_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &core_l4_ick, .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN1), .enable_bit = OMAP3430_EN_MMC1_SHIFT, @@ -1867,7 +1866,7 @@ static struct clk mmchs1_ick = { static struct clk mspro_ick = { .name = "mspro_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &core_l4_ick, .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN1), .enable_bit = OMAP3430_EN_MSPRO_SHIFT, @@ -1877,7 +1876,7 @@ static struct clk mspro_ick = { static struct clk hdq_ick = { .name = "hdq_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &core_l4_ick, .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN1), .enable_bit = OMAP3430_EN_HDQ_SHIFT, @@ -1887,7 +1886,7 @@ static struct clk hdq_ick = { static struct clk mcspi4_ick = { .name = "mcspi4_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &core_l4_ick, .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN1), .enable_bit = OMAP3430_EN_MCSPI4_SHIFT, @@ -1897,7 +1896,7 @@ static struct clk mcspi4_ick = { static struct clk mcspi3_ick = { .name = "mcspi3_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &core_l4_ick, .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN1), .enable_bit = OMAP3430_EN_MCSPI3_SHIFT, @@ -1907,7 +1906,7 @@ static struct clk mcspi3_ick = { static struct clk mcspi2_ick = { .name = "mcspi2_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &core_l4_ick, .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN1), .enable_bit = OMAP3430_EN_MCSPI2_SHIFT, @@ -1917,7 +1916,7 @@ static struct clk mcspi2_ick = { static struct clk mcspi1_ick = { .name = "mcspi1_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &core_l4_ick, .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN1), .enable_bit = OMAP3430_EN_MCSPI1_SHIFT, @@ -1927,7 +1926,7 @@ static struct clk mcspi1_ick = { static struct clk i2c3_ick = { .name = "i2c3_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &core_l4_ick, .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN1), .enable_bit = OMAP3430_EN_I2C3_SHIFT, @@ -1937,7 +1936,7 @@ static struct clk i2c3_ick = { static struct clk i2c2_ick = { .name = "i2c2_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &core_l4_ick, .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN1), .enable_bit = OMAP3430_EN_I2C2_SHIFT, @@ -1947,7 +1946,7 @@ static struct clk i2c2_ick = { static struct clk i2c1_ick = { .name = "i2c1_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &core_l4_ick, .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN1), .enable_bit = OMAP3430_EN_I2C1_SHIFT, @@ -1957,7 +1956,7 @@ static struct clk i2c1_ick = { static struct clk uart2_ick = { .name = "uart2_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &core_l4_ick, .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN1), .enable_bit = OMAP3430_EN_UART2_SHIFT, @@ -1967,7 +1966,7 @@ static struct clk uart2_ick = { static struct clk uart1_ick = { .name = "uart1_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &core_l4_ick, .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN1), .enable_bit = OMAP3430_EN_UART1_SHIFT, @@ -1977,7 +1976,7 @@ static struct clk uart1_ick = { static struct clk gpt11_ick = { .name = "gpt11_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &core_l4_ick, .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN1), .enable_bit = OMAP3430_EN_GPT11_SHIFT, @@ -1987,7 +1986,7 @@ static struct clk gpt11_ick = { static struct clk gpt10_ick = { .name = "gpt10_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &core_l4_ick, .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN1), .enable_bit = OMAP3430_EN_GPT10_SHIFT, @@ -1997,7 +1996,7 @@ static struct clk gpt10_ick = { static struct clk mcbsp5_ick = { .name = "mcbsp5_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &core_l4_ick, .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN1), .enable_bit = OMAP3430_EN_MCBSP5_SHIFT, @@ -2007,7 +2006,7 @@ static struct clk mcbsp5_ick = { static struct clk mcbsp1_ick = { .name = "mcbsp1_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &core_l4_ick, .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN1), .enable_bit = OMAP3430_EN_MCBSP1_SHIFT, @@ -2017,7 +2016,7 @@ static struct clk mcbsp1_ick = { static struct clk fac_ick = { .name = "fac_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &core_l4_ick, .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN1), .enable_bit = OMAP3430ES1_EN_FAC_SHIFT, @@ -2027,7 +2026,7 @@ static struct clk fac_ick = { static struct clk mailboxes_ick = { .name = "mailboxes_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &core_l4_ick, .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN1), .enable_bit = OMAP3430_EN_MAILBOXES_SHIFT, @@ -2037,7 +2036,7 @@ static struct clk mailboxes_ick = { static struct clk omapctrl_ick = { .name = "omapctrl_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &core_l4_ick, .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN1), .enable_bit = OMAP3430_EN_OMAPCTRL_SHIFT, @@ -2057,7 +2056,7 @@ static struct clk ssi_l4_ick = { static struct clk ssi_ick_3430es1 = { .name = "ssi_ick", - .ops = &clkops_omap2_dflt, + .ops = &clkops_omap2_iclk_dflt, .parent = &ssi_l4_ick, .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN1), .enable_bit = OMAP3430_EN_SSI_SHIFT, @@ -2067,7 +2066,7 @@ static struct clk ssi_ick_3430es1 = { static struct clk ssi_ick_3430es2 = { .name = "ssi_ick", - .ops = &clkops_omap3430es2_ssi_wait, + .ops = &clkops_omap3430es2_iclk_ssi_wait, .parent = &ssi_l4_ick, .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN1), .enable_bit = OMAP3430_EN_SSI_SHIFT, @@ -2085,7 +2084,7 @@ static const struct clksel usb_l4_clksel[] = { static struct clk usb_l4_ick = { .name = "usb_l4_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &l4_ick, .init = &omap2_init_clksel_parent, .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN1), @@ -2107,7 +2106,7 @@ static struct clk security_l4_ick2 = { static struct clk aes1_ick = { .name = "aes1_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &security_l4_ick2, .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN2), .enable_bit = OMAP3430_EN_AES1_SHIFT, @@ -2116,7 +2115,7 @@ static struct clk aes1_ick = { static struct clk rng_ick = { .name = "rng_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &security_l4_ick2, .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN2), .enable_bit = OMAP3430_EN_RNG_SHIFT, @@ -2125,7 +2124,7 @@ static struct clk rng_ick = { static struct clk sha11_ick = { .name = "sha11_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &security_l4_ick2, .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN2), .enable_bit = OMAP3430_EN_SHA11_SHIFT, @@ -2134,7 +2133,7 @@ static struct clk sha11_ick = { static struct clk des1_ick = { .name = "des1_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &security_l4_ick2, .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN2), .enable_bit = OMAP3430_EN_DES1_SHIFT, @@ -2195,7 +2194,7 @@ static struct clk dss2_alwon_fck = { static struct clk dss_ick_3430es1 = { /* Handles both L3 and L4 clocks */ .name = "dss_ick", - .ops = &clkops_omap2_dflt, + .ops = &clkops_omap2_iclk_dflt, .parent = &l4_ick, .enable_reg = OMAP_CM_REGADDR(OMAP3430_DSS_MOD, CM_ICLKEN), .enable_bit = OMAP3430_CM_ICLKEN_DSS_EN_DSS_SHIFT, @@ -2206,7 +2205,7 @@ static struct clk dss_ick_3430es1 = { static struct clk dss_ick_3430es2 = { /* Handles both L3 and L4 clocks */ .name = "dss_ick", - .ops = &clkops_omap3430es2_dss_usbhost_wait, + .ops = &clkops_omap3430es2_iclk_dss_usbhost_wait, .parent = &l4_ick, .enable_reg = OMAP_CM_REGADDR(OMAP3430_DSS_MOD, CM_ICLKEN), .enable_bit = OMAP3430_CM_ICLKEN_DSS_EN_DSS_SHIFT, @@ -2229,7 +2228,7 @@ static struct clk cam_mclk = { static struct clk cam_ick = { /* Handles both L3 and L4 clocks */ .name = "cam_ick", - .ops = &clkops_omap2_dflt, + .ops = &clkops_omap2_iclk_dflt, .parent = &l4_ick, .enable_reg = OMAP_CM_REGADDR(OMAP3430_CAM_MOD, CM_ICLKEN), .enable_bit = OMAP3430_EN_CAM_SHIFT, @@ -2272,7 +2271,7 @@ static struct clk usbhost_48m_fck = { static struct clk usbhost_ick = { /* Handles both L3 and L4 clocks */ .name = "usbhost_ick", - .ops = &clkops_omap3430es2_dss_usbhost_wait, + .ops = &clkops_omap3430es2_iclk_dss_usbhost_wait, .parent = &l4_ick, .enable_reg = OMAP_CM_REGADDR(OMAP3430ES2_USBHOST_MOD, CM_ICLKEN), .enable_bit = OMAP3430ES2_EN_USBHOST_SHIFT, @@ -2372,7 +2371,7 @@ static struct clk wkup_l4_ick = { /* Never specifically named in the TRM, so we have to infer a likely name */ static struct clk usim_ick = { .name = "usim_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &wkup_l4_ick, .enable_reg = OMAP_CM_REGADDR(WKUP_MOD, CM_ICLKEN), .enable_bit = OMAP3430ES2_EN_USIMOCP_SHIFT, @@ -2382,7 +2381,7 @@ static struct clk usim_ick = { static struct clk wdt2_ick = { .name = "wdt2_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &wkup_l4_ick, .enable_reg = OMAP_CM_REGADDR(WKUP_MOD, CM_ICLKEN), .enable_bit = OMAP3430_EN_WDT2_SHIFT, @@ -2392,7 +2391,7 @@ static struct clk wdt2_ick = { static struct clk wdt1_ick = { .name = "wdt1_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &wkup_l4_ick, .enable_reg = OMAP_CM_REGADDR(WKUP_MOD, CM_ICLKEN), .enable_bit = OMAP3430_EN_WDT1_SHIFT, @@ -2402,7 +2401,7 @@ static struct clk wdt1_ick = { static struct clk gpio1_ick = { .name = "gpio1_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &wkup_l4_ick, .enable_reg = OMAP_CM_REGADDR(WKUP_MOD, CM_ICLKEN), .enable_bit = OMAP3430_EN_GPIO1_SHIFT, @@ -2412,7 +2411,7 @@ static struct clk gpio1_ick = { static struct clk omap_32ksync_ick = { .name = "omap_32ksync_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &wkup_l4_ick, .enable_reg = OMAP_CM_REGADDR(WKUP_MOD, CM_ICLKEN), .enable_bit = OMAP3430_EN_32KSYNC_SHIFT, @@ -2423,7 +2422,7 @@ static struct clk omap_32ksync_ick = { /* XXX This clock no longer exists in 3430 TRM rev F */ static struct clk gpt12_ick = { .name = "gpt12_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &wkup_l4_ick, .enable_reg = OMAP_CM_REGADDR(WKUP_MOD, CM_ICLKEN), .enable_bit = OMAP3430_EN_GPT12_SHIFT, @@ -2433,7 +2432,7 @@ static struct clk gpt12_ick = { static struct clk gpt1_ick = { .name = "gpt1_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &wkup_l4_ick, .enable_reg = OMAP_CM_REGADDR(WKUP_MOD, CM_ICLKEN), .enable_bit = OMAP3430_EN_GPT1_SHIFT, @@ -2663,7 +2662,7 @@ static struct clk per_l4_ick = { static struct clk gpio6_ick = { .name = "gpio6_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &per_l4_ick, .enable_reg = OMAP_CM_REGADDR(OMAP3430_PER_MOD, CM_ICLKEN), .enable_bit = OMAP3430_EN_GPIO6_SHIFT, @@ -2673,7 +2672,7 @@ static struct clk gpio6_ick = { static struct clk gpio5_ick = { .name = "gpio5_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &per_l4_ick, .enable_reg = OMAP_CM_REGADDR(OMAP3430_PER_MOD, CM_ICLKEN), .enable_bit = OMAP3430_EN_GPIO5_SHIFT, @@ -2683,7 +2682,7 @@ static struct clk gpio5_ick = { static struct clk gpio4_ick = { .name = "gpio4_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &per_l4_ick, .enable_reg = OMAP_CM_REGADDR(OMAP3430_PER_MOD, CM_ICLKEN), .enable_bit = OMAP3430_EN_GPIO4_SHIFT, @@ -2693,7 +2692,7 @@ static struct clk gpio4_ick = { static struct clk gpio3_ick = { .name = "gpio3_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &per_l4_ick, .enable_reg = OMAP_CM_REGADDR(OMAP3430_PER_MOD, CM_ICLKEN), .enable_bit = OMAP3430_EN_GPIO3_SHIFT, @@ -2703,7 +2702,7 @@ static struct clk gpio3_ick = { static struct clk gpio2_ick = { .name = "gpio2_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &per_l4_ick, .enable_reg = OMAP_CM_REGADDR(OMAP3430_PER_MOD, CM_ICLKEN), .enable_bit = OMAP3430_EN_GPIO2_SHIFT, @@ -2713,7 +2712,7 @@ static struct clk gpio2_ick = { static struct clk wdt3_ick = { .name = "wdt3_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &per_l4_ick, .enable_reg = OMAP_CM_REGADDR(OMAP3430_PER_MOD, CM_ICLKEN), .enable_bit = OMAP3430_EN_WDT3_SHIFT, @@ -2723,7 +2722,7 @@ static struct clk wdt3_ick = { static struct clk uart3_ick = { .name = "uart3_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &per_l4_ick, .enable_reg = OMAP_CM_REGADDR(OMAP3430_PER_MOD, CM_ICLKEN), .enable_bit = OMAP3430_EN_UART3_SHIFT, @@ -2733,7 +2732,7 @@ static struct clk uart3_ick = { static struct clk uart4_ick = { .name = "uart4_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &per_l4_ick, .enable_reg = OMAP_CM_REGADDR(OMAP3430_PER_MOD, CM_ICLKEN), .enable_bit = OMAP3630_EN_UART4_SHIFT, @@ -2743,7 +2742,7 @@ static struct clk uart4_ick = { static struct clk gpt9_ick = { .name = "gpt9_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &per_l4_ick, .enable_reg = OMAP_CM_REGADDR(OMAP3430_PER_MOD, CM_ICLKEN), .enable_bit = OMAP3430_EN_GPT9_SHIFT, @@ -2753,7 +2752,7 @@ static struct clk gpt9_ick = { static struct clk gpt8_ick = { .name = "gpt8_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &per_l4_ick, .enable_reg = OMAP_CM_REGADDR(OMAP3430_PER_MOD, CM_ICLKEN), .enable_bit = OMAP3430_EN_GPT8_SHIFT, @@ -2763,7 +2762,7 @@ static struct clk gpt8_ick = { static struct clk gpt7_ick = { .name = "gpt7_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &per_l4_ick, .enable_reg = OMAP_CM_REGADDR(OMAP3430_PER_MOD, CM_ICLKEN), .enable_bit = OMAP3430_EN_GPT7_SHIFT, @@ -2773,7 +2772,7 @@ static struct clk gpt7_ick = { static struct clk gpt6_ick = { .name = "gpt6_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &per_l4_ick, .enable_reg = OMAP_CM_REGADDR(OMAP3430_PER_MOD, CM_ICLKEN), .enable_bit = OMAP3430_EN_GPT6_SHIFT, @@ -2783,7 +2782,7 @@ static struct clk gpt6_ick = { static struct clk gpt5_ick = { .name = "gpt5_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &per_l4_ick, .enable_reg = OMAP_CM_REGADDR(OMAP3430_PER_MOD, CM_ICLKEN), .enable_bit = OMAP3430_EN_GPT5_SHIFT, @@ -2793,7 +2792,7 @@ static struct clk gpt5_ick = { static struct clk gpt4_ick = { .name = "gpt4_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &per_l4_ick, .enable_reg = OMAP_CM_REGADDR(OMAP3430_PER_MOD, CM_ICLKEN), .enable_bit = OMAP3430_EN_GPT4_SHIFT, @@ -2803,7 +2802,7 @@ static struct clk gpt4_ick = { static struct clk gpt3_ick = { .name = "gpt3_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &per_l4_ick, .enable_reg = OMAP_CM_REGADDR(OMAP3430_PER_MOD, CM_ICLKEN), .enable_bit = OMAP3430_EN_GPT3_SHIFT, @@ -2813,7 +2812,7 @@ static struct clk gpt3_ick = { static struct clk gpt2_ick = { .name = "gpt2_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &per_l4_ick, .enable_reg = OMAP_CM_REGADDR(OMAP3430_PER_MOD, CM_ICLKEN), .enable_bit = OMAP3430_EN_GPT2_SHIFT, @@ -2823,7 +2822,7 @@ static struct clk gpt2_ick = { static struct clk mcbsp2_ick = { .name = "mcbsp2_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &per_l4_ick, .enable_reg = OMAP_CM_REGADDR(OMAP3430_PER_MOD, CM_ICLKEN), .enable_bit = OMAP3430_EN_MCBSP2_SHIFT, @@ -2833,7 +2832,7 @@ static struct clk mcbsp2_ick = { static struct clk mcbsp3_ick = { .name = "mcbsp3_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &per_l4_ick, .enable_reg = OMAP_CM_REGADDR(OMAP3430_PER_MOD, CM_ICLKEN), .enable_bit = OMAP3430_EN_MCBSP3_SHIFT, @@ -2843,7 +2842,7 @@ static struct clk mcbsp3_ick = { static struct clk mcbsp4_ick = { .name = "mcbsp4_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &per_l4_ick, .enable_reg = OMAP_CM_REGADDR(OMAP3430_PER_MOD, CM_ICLKEN), .enable_bit = OMAP3430_EN_MCBSP4_SHIFT, @@ -3186,7 +3185,7 @@ static struct clk vpfe_fck = { */ static struct clk uart4_ick_am35xx = { .name = "uart4_ick", - .ops = &clkops_omap2_dflt_wait, + .ops = &clkops_omap2_iclk_dflt_wait, .parent = &core_l4_ick, .enable_reg = OMAP_CM_REGADDR(CORE_MOD, CM_ICLKEN1), .enable_bit = AM35XX_EN_UART4_SHIFT, @@ -3290,10 +3289,10 @@ static struct omap_clk omap3xxx_clks[] = { CLK("omap-mcbsp.1", "prcm_fck", &core_96m_fck, CK_3XXX), CLK("omap-mcbsp.5", "prcm_fck", &core_96m_fck, CK_3XXX), CLK(NULL, "core_96m_fck", &core_96m_fck, CK_3XXX), - CLK("mmci-omap-hs.2", "fck", &mmchs3_fck, CK_3430ES2PLUS | CK_AM35XX | CK_36XX), - CLK("mmci-omap-hs.1", "fck", &mmchs2_fck, CK_3XXX), + CLK("omap_hsmmc.2", "fck", &mmchs3_fck, CK_3430ES2PLUS | CK_AM35XX | CK_36XX), + CLK("omap_hsmmc.1", "fck", &mmchs2_fck, CK_3XXX), CLK(NULL, "mspro_fck", &mspro_fck, CK_34XX | CK_36XX), - CLK("mmci-omap-hs.0", "fck", &mmchs1_fck, CK_3XXX), + CLK("omap_hsmmc.0", "fck", &mmchs1_fck, CK_3XXX), CLK("omap_i2c.3", "fck", &i2c3_fck, CK_3XXX), CLK("omap_i2c.2", "fck", &i2c2_fck, CK_3XXX), CLK("omap_i2c.1", "fck", &i2c1_fck, CK_3XXX), @@ -3323,13 +3322,13 @@ static struct omap_clk omap3xxx_clks[] = { CLK(NULL, "core_l4_ick", &core_l4_ick, CK_3XXX), CLK(NULL, "usbtll_ick", &usbtll_ick, CK_3430ES2PLUS | CK_AM35XX | CK_36XX), CLK("usbhs-omap.0", "usbtll_ick", &usbtll_ick, CK_3430ES2PLUS | CK_AM35XX | CK_36XX), - CLK("mmci-omap-hs.2", "ick", &mmchs3_ick, CK_3430ES2PLUS | CK_AM35XX | CK_36XX), + CLK("omap_hsmmc.2", "ick", &mmchs3_ick, CK_3430ES2PLUS | CK_AM35XX | CK_36XX), CLK(NULL, "icr_ick", &icr_ick, CK_34XX | CK_36XX), CLK("omap-aes", "ick", &aes2_ick, CK_34XX | CK_36XX), CLK("omap-sham", "ick", &sha12_ick, CK_34XX | CK_36XX), CLK(NULL, "des2_ick", &des2_ick, CK_34XX | CK_36XX), - CLK("mmci-omap-hs.1", "ick", &mmchs2_ick, CK_3XXX), - CLK("mmci-omap-hs.0", "ick", &mmchs1_ick, CK_3XXX), + CLK("omap_hsmmc.1", "ick", &mmchs2_ick, CK_3XXX), + CLK("omap_hsmmc.0", "ick", &mmchs1_ick, CK_3XXX), CLK(NULL, "mspro_ick", &mspro_ick, CK_34XX | CK_36XX), CLK("omap_hdq.0", "ick", &hdq_ick, CK_3XXX), CLK("omap2_mcspi.4", "ick", &mcspi4_ick, CK_3XXX), @@ -3480,6 +3479,9 @@ int __init omap3xxx_clk_init(void) } else if (cpu_is_omap3630()) { cpu_mask = (RATE_IN_34XX | RATE_IN_36XX); cpu_clkflg = CK_36XX; + } else if (cpu_is_ti816x()) { + cpu_mask = RATE_IN_TI816X; + cpu_clkflg = CK_TI816X; } else if (cpu_is_omap34xx()) { if (omap_rev() == OMAP3430_REV_ES1_0) { cpu_mask = RATE_IN_3430ES1; @@ -3544,6 +3546,9 @@ int __init omap3xxx_clk_init(void) omap2_init_clk_clkdm(c->lk.clk); } + /* Disable autoidle on all clocks; let the PM code enable it later */ + omap_clk_disable_autoidle_all(); + recalculate_root_clocks(); pr_info("Clocking rate (Crystal/Core/MPU): %ld.%01ld/%ld/%ld MHz\n", @@ -3557,9 +3562,10 @@ int __init omap3xxx_clk_init(void) clk_enable_init_clocks(); /* - * Lock DPLL5 and put it in autoidle. + * Lock DPLL5 -- here only until other device init code can + * handle this */ - if (omap_rev() >= OMAP3430_REV_ES2_0) + if (!cpu_is_ti816x() && (omap_rev() >= OMAP3430_REV_ES2_0)) omap3_clk_lock_dpll5(); /* Avoid sleeping during omap3_core_dpll_m2_set_rate() */ diff --git a/arch/arm/mach-omap2/clock44xx_data.c b/arch/arm/mach-omap2/clock44xx_data.c index 46fd3f674ca..d32ed979a8d 100644 --- a/arch/arm/mach-omap2/clock44xx_data.c +++ b/arch/arm/mach-omap2/clock44xx_data.c @@ -278,8 +278,10 @@ static struct clk dpll_abe_ck = { static struct clk dpll_abe_x2_ck = { .name = "dpll_abe_x2_ck", .parent = &dpll_abe_ck, - .ops = &clkops_null, + .flags = CLOCK_CLKOUTX2, + .ops = &clkops_omap4_dpllmx_ops, .recalc = &omap3_clkoutx2_recalc, + .clksel_reg = OMAP4430_CM_DIV_M2_DPLL_ABE, }; static const struct clksel_rate div31_1to31_rates[] = { @@ -328,7 +330,7 @@ static struct clk dpll_abe_m2x2_ck = { .clksel = dpll_abe_m2x2_div, .clksel_reg = OMAP4430_CM_DIV_M2_DPLL_ABE, .clksel_mask = OMAP4430_DPLL_CLKOUT_DIV_MASK, - .ops = &clkops_null, + .ops = &clkops_omap4_dpllmx_ops, .recalc = &omap2_clksel_recalc, .round_rate = &omap2_clksel_round_rate, .set_rate = &omap2_clksel_set_rate, @@ -395,7 +397,7 @@ static struct clk dpll_abe_m3x2_ck = { .clksel = dpll_abe_m2x2_div, .clksel_reg = OMAP4430_CM_DIV_M3_DPLL_ABE, .clksel_mask = OMAP4430_DPLL_CLKOUTHIF_DIV_MASK, - .ops = &clkops_null, + .ops = &clkops_omap4_dpllmx_ops, .recalc = &omap2_clksel_recalc, .round_rate = &omap2_clksel_round_rate, .set_rate = &omap2_clksel_set_rate, @@ -443,13 +445,14 @@ static struct clk dpll_core_ck = { .parent = &sys_clkin_ck, .dpll_data = &dpll_core_dd, .init = &omap2_init_dpll_parent, - .ops = &clkops_null, + .ops = &clkops_omap3_core_dpll_ops, .recalc = &omap3_dpll_recalc, }; static struct clk dpll_core_x2_ck = { .name = "dpll_core_x2_ck", .parent = &dpll_core_ck, + .flags = CLOCK_CLKOUTX2, .ops = &clkops_null, .recalc = &omap3_clkoutx2_recalc, }; @@ -465,7 +468,7 @@ static struct clk dpll_core_m6x2_ck = { .clksel = dpll_core_m6x2_div, .clksel_reg = OMAP4430_CM_DIV_M6_DPLL_CORE, .clksel_mask = OMAP4430_HSDIVIDER_CLKOUT3_DIV_MASK, - .ops = &clkops_null, + .ops = &clkops_omap4_dpllmx_ops, .recalc = &omap2_clksel_recalc, .round_rate = &omap2_clksel_round_rate, .set_rate = &omap2_clksel_set_rate, @@ -495,7 +498,7 @@ static struct clk dpll_core_m2_ck = { .clksel = dpll_core_m2_div, .clksel_reg = OMAP4430_CM_DIV_M2_DPLL_CORE, .clksel_mask = OMAP4430_DPLL_CLKOUT_DIV_MASK, - .ops = &clkops_null, + .ops = &clkops_omap4_dpllmx_ops, .recalc = &omap2_clksel_recalc, .round_rate = &omap2_clksel_round_rate, .set_rate = &omap2_clksel_set_rate, @@ -515,7 +518,7 @@ static struct clk dpll_core_m5x2_ck = { .clksel = dpll_core_m6x2_div, .clksel_reg = OMAP4430_CM_DIV_M5_DPLL_CORE, .clksel_mask = OMAP4430_HSDIVIDER_CLKOUT2_DIV_MASK, - .ops = &clkops_null, + .ops = &clkops_omap4_dpllmx_ops, .recalc = &omap2_clksel_recalc, .round_rate = &omap2_clksel_round_rate, .set_rate = &omap2_clksel_set_rate, @@ -581,7 +584,7 @@ static struct clk dpll_core_m4x2_ck = { .clksel = dpll_core_m6x2_div, .clksel_reg = OMAP4430_CM_DIV_M4_DPLL_CORE, .clksel_mask = OMAP4430_HSDIVIDER_CLKOUT1_DIV_MASK, - .ops = &clkops_null, + .ops = &clkops_omap4_dpllmx_ops, .recalc = &omap2_clksel_recalc, .round_rate = &omap2_clksel_round_rate, .set_rate = &omap2_clksel_set_rate, @@ -606,7 +609,7 @@ static struct clk dpll_abe_m2_ck = { .clksel = dpll_abe_m2_div, .clksel_reg = OMAP4430_CM_DIV_M2_DPLL_ABE, .clksel_mask = OMAP4430_DPLL_CLKOUT_DIV_MASK, - .ops = &clkops_null, + .ops = &clkops_omap4_dpllmx_ops, .recalc = &omap2_clksel_recalc, .round_rate = &omap2_clksel_round_rate, .set_rate = &omap2_clksel_set_rate, @@ -632,7 +635,7 @@ static struct clk dpll_core_m7x2_ck = { .clksel = dpll_core_m6x2_div, .clksel_reg = OMAP4430_CM_DIV_M7_DPLL_CORE, .clksel_mask = OMAP4430_HSDIVIDER_CLKOUT4_DIV_MASK, - .ops = &clkops_null, + .ops = &clkops_omap4_dpllmx_ops, .recalc = &omap2_clksel_recalc, .round_rate = &omap2_clksel_round_rate, .set_rate = &omap2_clksel_set_rate, @@ -689,6 +692,7 @@ static struct clk dpll_iva_ck = { static struct clk dpll_iva_x2_ck = { .name = "dpll_iva_x2_ck", .parent = &dpll_iva_ck, + .flags = CLOCK_CLKOUTX2, .ops = &clkops_null, .recalc = &omap3_clkoutx2_recalc, }; @@ -704,7 +708,7 @@ static struct clk dpll_iva_m4x2_ck = { .clksel = dpll_iva_m4x2_div, .clksel_reg = OMAP4430_CM_DIV_M4_DPLL_IVA, .clksel_mask = OMAP4430_HSDIVIDER_CLKOUT1_DIV_MASK, - .ops = &clkops_null, + .ops = &clkops_omap4_dpllmx_ops, .recalc = &omap2_clksel_recalc, .round_rate = &omap2_clksel_round_rate, .set_rate = &omap2_clksel_set_rate, @@ -716,7 +720,7 @@ static struct clk dpll_iva_m5x2_ck = { .clksel = dpll_iva_m4x2_div, .clksel_reg = OMAP4430_CM_DIV_M5_DPLL_IVA, .clksel_mask = OMAP4430_HSDIVIDER_CLKOUT2_DIV_MASK, - .ops = &clkops_null, + .ops = &clkops_omap4_dpllmx_ops, .recalc = &omap2_clksel_recalc, .round_rate = &omap2_clksel_round_rate, .set_rate = &omap2_clksel_set_rate, @@ -764,7 +768,7 @@ static struct clk dpll_mpu_m2_ck = { .clksel = dpll_mpu_m2_div, .clksel_reg = OMAP4430_CM_DIV_M2_DPLL_MPU, .clksel_mask = OMAP4430_DPLL_CLKOUT_DIV_MASK, - .ops = &clkops_null, + .ops = &clkops_omap4_dpllmx_ops, .recalc = &omap2_clksel_recalc, .round_rate = &omap2_clksel_round_rate, .set_rate = &omap2_clksel_set_rate, @@ -837,7 +841,7 @@ static struct clk dpll_per_m2_ck = { .clksel = dpll_per_m2_div, .clksel_reg = OMAP4430_CM_DIV_M2_DPLL_PER, .clksel_mask = OMAP4430_DPLL_CLKOUT_DIV_MASK, - .ops = &clkops_null, + .ops = &clkops_omap4_dpllmx_ops, .recalc = &omap2_clksel_recalc, .round_rate = &omap2_clksel_round_rate, .set_rate = &omap2_clksel_set_rate, @@ -846,8 +850,10 @@ static struct clk dpll_per_m2_ck = { static struct clk dpll_per_x2_ck = { .name = "dpll_per_x2_ck", .parent = &dpll_per_ck, - .ops = &clkops_null, + .flags = CLOCK_CLKOUTX2, + .ops = &clkops_omap4_dpllmx_ops, .recalc = &omap3_clkoutx2_recalc, + .clksel_reg = OMAP4430_CM_DIV_M2_DPLL_PER, }; static const struct clksel dpll_per_m2x2_div[] = { @@ -861,7 +867,7 @@ static struct clk dpll_per_m2x2_ck = { .clksel = dpll_per_m2x2_div, .clksel_reg = OMAP4430_CM_DIV_M2_DPLL_PER, .clksel_mask = OMAP4430_DPLL_CLKOUT_DIV_MASK, - .ops = &clkops_null, + .ops = &clkops_omap4_dpllmx_ops, .recalc = &omap2_clksel_recalc, .round_rate = &omap2_clksel_round_rate, .set_rate = &omap2_clksel_set_rate, @@ -887,7 +893,7 @@ static struct clk dpll_per_m4x2_ck = { .clksel = dpll_per_m2x2_div, .clksel_reg = OMAP4430_CM_DIV_M4_DPLL_PER, .clksel_mask = OMAP4430_HSDIVIDER_CLKOUT1_DIV_MASK, - .ops = &clkops_null, + .ops = &clkops_omap4_dpllmx_ops, .recalc = &omap2_clksel_recalc, .round_rate = &omap2_clksel_round_rate, .set_rate = &omap2_clksel_set_rate, @@ -899,7 +905,7 @@ static struct clk dpll_per_m5x2_ck = { .clksel = dpll_per_m2x2_div, .clksel_reg = OMAP4430_CM_DIV_M5_DPLL_PER, .clksel_mask = OMAP4430_HSDIVIDER_CLKOUT2_DIV_MASK, - .ops = &clkops_null, + .ops = &clkops_omap4_dpllmx_ops, .recalc = &omap2_clksel_recalc, .round_rate = &omap2_clksel_round_rate, .set_rate = &omap2_clksel_set_rate, @@ -911,7 +917,7 @@ static struct clk dpll_per_m6x2_ck = { .clksel = dpll_per_m2x2_div, .clksel_reg = OMAP4430_CM_DIV_M6_DPLL_PER, .clksel_mask = OMAP4430_HSDIVIDER_CLKOUT3_DIV_MASK, - .ops = &clkops_null, + .ops = &clkops_omap4_dpllmx_ops, .recalc = &omap2_clksel_recalc, .round_rate = &omap2_clksel_round_rate, .set_rate = &omap2_clksel_set_rate, @@ -923,7 +929,7 @@ static struct clk dpll_per_m7x2_ck = { .clksel = dpll_per_m2x2_div, .clksel_reg = OMAP4430_CM_DIV_M7_DPLL_PER, .clksel_mask = OMAP4430_HSDIVIDER_CLKOUT4_DIV_MASK, - .ops = &clkops_null, + .ops = &clkops_omap4_dpllmx_ops, .recalc = &omap2_clksel_recalc, .round_rate = &omap2_clksel_round_rate, .set_rate = &omap2_clksel_set_rate, @@ -964,6 +970,7 @@ static struct clk dpll_unipro_ck = { static struct clk dpll_unipro_x2_ck = { .name = "dpll_unipro_x2_ck", .parent = &dpll_unipro_ck, + .flags = CLOCK_CLKOUTX2, .ops = &clkops_null, .recalc = &omap3_clkoutx2_recalc, }; @@ -979,7 +986,7 @@ static struct clk dpll_unipro_m2x2_ck = { .clksel = dpll_unipro_m2x2_div, .clksel_reg = OMAP4430_CM_DIV_M2_DPLL_UNIPRO, .clksel_mask = OMAP4430_DPLL_CLKOUT_DIV_MASK, - .ops = &clkops_null, + .ops = &clkops_omap4_dpllmx_ops, .recalc = &omap2_clksel_recalc, .round_rate = &omap2_clksel_round_rate, .set_rate = &omap2_clksel_set_rate, @@ -1028,7 +1035,8 @@ static struct clk dpll_usb_ck = { static struct clk dpll_usb_clkdcoldo_ck = { .name = "dpll_usb_clkdcoldo_ck", .parent = &dpll_usb_ck, - .ops = &clkops_null, + .ops = &clkops_omap4_dpllmx_ops, + .clksel_reg = OMAP4430_CM_CLKDCOLDO_DPLL_USB, .recalc = &followparent_recalc, }; @@ -1043,7 +1051,7 @@ static struct clk dpll_usb_m2_ck = { .clksel = dpll_usb_m2_div, .clksel_reg = OMAP4430_CM_DIV_M2_DPLL_USB, .clksel_mask = OMAP4430_DPLL_CLKOUT_DIV_0_6_MASK, - .ops = &clkops_null, + .ops = &clkops_omap4_dpllmx_ops, .recalc = &omap2_clksel_recalc, .round_rate = &omap2_clksel_round_rate, .set_rate = &omap2_clksel_set_rate, @@ -3158,11 +3166,11 @@ static struct omap_clk omap44xx_clks[] = { CLK("omap2_mcspi.2", "fck", &mcspi2_fck, CK_443X), CLK("omap2_mcspi.3", "fck", &mcspi3_fck, CK_443X), CLK("omap2_mcspi.4", "fck", &mcspi4_fck, CK_443X), - CLK("mmci-omap-hs.0", "fck", &mmc1_fck, CK_443X), - CLK("mmci-omap-hs.1", "fck", &mmc2_fck, CK_443X), - CLK("mmci-omap-hs.2", "fck", &mmc3_fck, CK_443X), - CLK("mmci-omap-hs.3", "fck", &mmc4_fck, CK_443X), - CLK("mmci-omap-hs.4", "fck", &mmc5_fck, CK_443X), + CLK("omap_hsmmc.0", "fck", &mmc1_fck, CK_443X), + CLK("omap_hsmmc.1", "fck", &mmc2_fck, CK_443X), + CLK("omap_hsmmc.2", "fck", &mmc3_fck, CK_443X), + CLK("omap_hsmmc.3", "fck", &mmc4_fck, CK_443X), + CLK("omap_hsmmc.4", "fck", &mmc5_fck, CK_443X), CLK(NULL, "ocp2scp_usb_phy_phy_48m", &ocp2scp_usb_phy_phy_48m, CK_443X), CLK(NULL, "ocp2scp_usb_phy_ick", &ocp2scp_usb_phy_ick, CK_443X), CLK(NULL, "ocp_wp_noc_ick", &ocp_wp_noc_ick, CK_443X), @@ -3245,11 +3253,11 @@ static struct omap_clk omap44xx_clks[] = { CLK("omap_i2c.2", "ick", &dummy_ck, CK_443X), CLK("omap_i2c.3", "ick", &dummy_ck, CK_443X), CLK("omap_i2c.4", "ick", &dummy_ck, CK_443X), - CLK("mmci-omap-hs.0", "ick", &dummy_ck, CK_443X), - CLK("mmci-omap-hs.1", "ick", &dummy_ck, CK_443X), - CLK("mmci-omap-hs.2", "ick", &dummy_ck, CK_443X), - CLK("mmci-omap-hs.3", "ick", &dummy_ck, CK_443X), - CLK("mmci-omap-hs.4", "ick", &dummy_ck, CK_443X), + CLK("omap_hsmmc.0", "ick", &dummy_ck, CK_443X), + CLK("omap_hsmmc.1", "ick", &dummy_ck, CK_443X), + CLK("omap_hsmmc.2", "ick", &dummy_ck, CK_443X), + CLK("omap_hsmmc.3", "ick", &dummy_ck, CK_443X), + CLK("omap_hsmmc.4", "ick", &dummy_ck, CK_443X), CLK("omap-mcbsp.1", "ick", &dummy_ck, CK_443X), CLK("omap-mcbsp.2", "ick", &dummy_ck, CK_443X), CLK("omap-mcbsp.3", "ick", &dummy_ck, CK_443X), @@ -3301,6 +3309,9 @@ int __init omap4xxx_clk_init(void) omap2_init_clk_clkdm(c->lk.clk); } + /* Disable autoidle on all clocks; let the PM code enable it later */ + omap_clk_disable_autoidle_all(); + recalculate_root_clocks(); /* diff --git a/arch/arm/mach-omap2/clock_common_data.c b/arch/arm/mach-omap2/clock_common_data.c index 1cf8131205f..6424d46be14 100644 --- a/arch/arm/mach-omap2/clock_common_data.c +++ b/arch/arm/mach-omap2/clock_common_data.c @@ -37,3 +37,9 @@ const struct clksel_rate gfx_l3_rates[] = { { .div = 0 } }; +const struct clksel_rate dsp_ick_rates[] = { + { .div = 1, .val = 1, .flags = RATE_IN_24XX }, + { .div = 2, .val = 2, .flags = RATE_IN_24XX }, + { .div = 3, .val = 3, .flags = RATE_IN_243X }, + { .div = 0 }, +}; diff --git a/arch/arm/mach-omap2/clockdomain.c b/arch/arm/mach-omap2/clockdomain.c index 58e42f76603..ab878545bd9 100644 --- a/arch/arm/mach-omap2/clockdomain.c +++ b/arch/arm/mach-omap2/clockdomain.c @@ -26,17 +26,8 @@ #include <linux/bitops.h> -#include "prm2xxx_3xxx.h" -#include "prm-regbits-24xx.h" -#include "cm2xxx_3xxx.h" -#include "cm-regbits-24xx.h" -#include "cminst44xx.h" -#include "prcm44xx.h" - #include <plat/clock.h> -#include "powerdomain.h" #include "clockdomain.h" -#include <plat/prcm.h> /* clkdm_list contains all registered struct clockdomains */ static LIST_HEAD(clkdm_list); @@ -44,6 +35,7 @@ static LIST_HEAD(clkdm_list); /* array of clockdomain deps to be added/removed when clkdm in hwsup mode */ static struct clkdm_autodep *autodeps; +static struct clkdm_ops *arch_clkdm; /* Private functions */ @@ -177,11 +169,11 @@ static void _autodep_lookup(struct clkdm_autodep *autodep) * XXX autodeps are deprecated and should be removed at the earliest * opportunity */ -static void _clkdm_add_autodeps(struct clockdomain *clkdm) +void _clkdm_add_autodeps(struct clockdomain *clkdm) { struct clkdm_autodep *autodep; - if (!autodeps) + if (!autodeps || clkdm->flags & CLKDM_NO_AUTODEPS) return; for (autodep = autodeps; autodep->clkdm.ptr; autodep++) { @@ -211,11 +203,11 @@ static void _clkdm_add_autodeps(struct clockdomain *clkdm) * XXX autodeps are deprecated and should be removed at the earliest * opportunity */ -static void _clkdm_del_autodeps(struct clockdomain *clkdm) +void _clkdm_del_autodeps(struct clockdomain *clkdm) { struct clkdm_autodep *autodep; - if (!autodeps) + if (!autodeps || clkdm->flags & CLKDM_NO_AUTODEPS) return; for (autodep = autodeps; autodep->clkdm.ptr; autodep++) { @@ -235,55 +227,29 @@ static void _clkdm_del_autodeps(struct clockdomain *clkdm) } /** - * _enable_hwsup - place a clockdomain into hardware-supervised idle - * @clkdm: struct clockdomain * - * - * Place the clockdomain into hardware-supervised idle mode. No return - * value. + * _resolve_clkdm_deps() - resolve clkdm_names in @clkdm_deps to clkdms + * @clkdm: clockdomain that we are resolving dependencies for + * @clkdm_deps: ptr to array of struct clkdm_deps to resolve * - * XXX Should this return an error if the clockdomain does not support - * hardware-supervised idle mode? - */ -static void _enable_hwsup(struct clockdomain *clkdm) -{ - if (cpu_is_omap24xx()) - omap2xxx_cm_clkdm_enable_hwsup(clkdm->pwrdm.ptr->prcm_offs, - clkdm->clktrctrl_mask); - else if (cpu_is_omap34xx()) - omap3xxx_cm_clkdm_enable_hwsup(clkdm->pwrdm.ptr->prcm_offs, - clkdm->clktrctrl_mask); - else if (cpu_is_omap44xx()) - return omap4_cminst_clkdm_enable_hwsup(clkdm->prcm_partition, - clkdm->cm_inst, - clkdm->clkdm_offs); - else - BUG(); -} - -/** - * _disable_hwsup - place a clockdomain into software-supervised idle - * @clkdm: struct clockdomain * - * - * Place the clockdomain @clkdm into software-supervised idle mode. + * Iterates through @clkdm_deps, looking up the struct clockdomain named by + * clkdm_name and storing the clockdomain pointer in the struct clkdm_dep. * No return value. - * - * XXX Should this return an error if the clockdomain does not support - * software-supervised idle mode? */ -static void _disable_hwsup(struct clockdomain *clkdm) +static void _resolve_clkdm_deps(struct clockdomain *clkdm, + struct clkdm_dep *clkdm_deps) { - if (cpu_is_omap24xx()) - omap2xxx_cm_clkdm_disable_hwsup(clkdm->pwrdm.ptr->prcm_offs, - clkdm->clktrctrl_mask); - else if (cpu_is_omap34xx()) - omap3xxx_cm_clkdm_disable_hwsup(clkdm->pwrdm.ptr->prcm_offs, - clkdm->clktrctrl_mask); - else if (cpu_is_omap44xx()) - return omap4_cminst_clkdm_disable_hwsup(clkdm->prcm_partition, - clkdm->cm_inst, - clkdm->clkdm_offs); - else - BUG(); + struct clkdm_dep *cd; + + for (cd = clkdm_deps; cd && cd->clkdm_name; cd++) { + if (!omap_chip_is(cd->omap_chip)) + continue; + if (cd->clkdm) + continue; + cd->clkdm = _clkdm_lookup(cd->clkdm_name); + + WARN(!cd->clkdm, "clockdomain: %s: could not find clkdm %s while resolving dependencies - should never happen", + clkdm->name, cd->clkdm_name); + } } /* Public functions */ @@ -292,6 +258,7 @@ static void _disable_hwsup(struct clockdomain *clkdm) * clkdm_init - set up the clockdomain layer * @clkdms: optional pointer to an array of clockdomains to register * @init_autodeps: optional pointer to an array of autodeps to register + * @custom_funcs: func pointers for arch specfic implementations * * Set up internal state. If a pointer to an array of clockdomains * @clkdms was supplied, loop through the list of clockdomains, @@ -300,12 +267,18 @@ static void _disable_hwsup(struct clockdomain *clkdm) * @init_autodeps was provided, register those. No return value. */ void clkdm_init(struct clockdomain **clkdms, - struct clkdm_autodep *init_autodeps) + struct clkdm_autodep *init_autodeps, + struct clkdm_ops *custom_funcs) { struct clockdomain **c = NULL; struct clockdomain *clkdm; struct clkdm_autodep *autodep = NULL; + if (!custom_funcs) + WARN(1, "No custom clkdm functions registered\n"); + else + arch_clkdm = custom_funcs; + if (clkdms) for (c = clkdms; *c; c++) _clkdm_register(*c); @@ -321,11 +294,14 @@ void clkdm_init(struct clockdomain **clkdms, */ list_for_each_entry(clkdm, &clkdm_list, node) { if (clkdm->flags & CLKDM_CAN_FORCE_WAKEUP) - omap2_clkdm_wakeup(clkdm); + clkdm_wakeup(clkdm); else if (clkdm->flags & CLKDM_CAN_DISABLE_AUTO) - omap2_clkdm_deny_idle(clkdm); + clkdm_deny_idle(clkdm); + _resolve_clkdm_deps(clkdm, clkdm->wkdep_srcs); clkdm_clear_all_wkdeps(clkdm); + + _resolve_clkdm_deps(clkdm, clkdm->sleepdep_srcs); clkdm_clear_all_sleepdeps(clkdm); } } @@ -422,32 +398,32 @@ struct powerdomain *clkdm_get_pwrdm(struct clockdomain *clkdm) int clkdm_add_wkdep(struct clockdomain *clkdm1, struct clockdomain *clkdm2) { struct clkdm_dep *cd; - - if (!cpu_is_omap24xx() && !cpu_is_omap34xx()) { - pr_err("clockdomain: %s/%s: %s: not yet implemented\n", - clkdm1->name, clkdm2->name, __func__); - return -EINVAL; - } + int ret = 0; if (!clkdm1 || !clkdm2) return -EINVAL; cd = _clkdm_deps_lookup(clkdm2, clkdm1->wkdep_srcs); - if (IS_ERR(cd)) { + if (IS_ERR(cd)) + ret = PTR_ERR(cd); + + if (!arch_clkdm || !arch_clkdm->clkdm_add_wkdep) + ret = -EINVAL; + + if (ret) { pr_debug("clockdomain: hardware cannot set/clear wake up of " "%s when %s wakes up\n", clkdm1->name, clkdm2->name); - return PTR_ERR(cd); + return ret; } if (atomic_inc_return(&cd->wkdep_usecount) == 1) { pr_debug("clockdomain: hardware will wake up %s when %s wakes " "up\n", clkdm1->name, clkdm2->name); - omap2_prm_set_mod_reg_bits((1 << clkdm2->dep_bit), - clkdm1->pwrdm.ptr->prcm_offs, PM_WKDEP); + ret = arch_clkdm->clkdm_add_wkdep(clkdm1, clkdm2); } - return 0; + return ret; } /** @@ -463,32 +439,32 @@ int clkdm_add_wkdep(struct clockdomain *clkdm1, struct clockdomain *clkdm2) int clkdm_del_wkdep(struct clockdomain *clkdm1, struct clockdomain *clkdm2) { struct clkdm_dep *cd; - - if (!cpu_is_omap24xx() && !cpu_is_omap34xx()) { - pr_err("clockdomain: %s/%s: %s: not yet implemented\n", - clkdm1->name, clkdm2->name, __func__); - return -EINVAL; - } + int ret = 0; if (!clkdm1 || !clkdm2) return -EINVAL; cd = _clkdm_deps_lookup(clkdm2, clkdm1->wkdep_srcs); - if (IS_ERR(cd)) { + if (IS_ERR(cd)) + ret = PTR_ERR(cd); + + if (!arch_clkdm || !arch_clkdm->clkdm_del_wkdep) + ret = -EINVAL; + + if (ret) { pr_debug("clockdomain: hardware cannot set/clear wake up of " "%s when %s wakes up\n", clkdm1->name, clkdm2->name); - return PTR_ERR(cd); + return ret; } if (atomic_dec_return(&cd->wkdep_usecount) == 0) { pr_debug("clockdomain: hardware will no longer wake up %s " "after %s wakes up\n", clkdm1->name, clkdm2->name); - omap2_prm_clear_mod_reg_bits((1 << clkdm2->dep_bit), - clkdm1->pwrdm.ptr->prcm_offs, PM_WKDEP); + ret = arch_clkdm->clkdm_del_wkdep(clkdm1, clkdm2); } - return 0; + return ret; } /** @@ -508,26 +484,26 @@ int clkdm_del_wkdep(struct clockdomain *clkdm1, struct clockdomain *clkdm2) int clkdm_read_wkdep(struct clockdomain *clkdm1, struct clockdomain *clkdm2) { struct clkdm_dep *cd; + int ret = 0; if (!clkdm1 || !clkdm2) return -EINVAL; - if (!cpu_is_omap24xx() && !cpu_is_omap34xx()) { - pr_err("clockdomain: %s/%s: %s: not yet implemented\n", - clkdm1->name, clkdm2->name, __func__); - return -EINVAL; - } - cd = _clkdm_deps_lookup(clkdm2, clkdm1->wkdep_srcs); - if (IS_ERR(cd)) { + if (IS_ERR(cd)) + ret = PTR_ERR(cd); + + if (!arch_clkdm || !arch_clkdm->clkdm_read_wkdep) + ret = -EINVAL; + + if (ret) { pr_debug("clockdomain: hardware cannot set/clear wake up of " "%s when %s wakes up\n", clkdm1->name, clkdm2->name); - return PTR_ERR(cd); + return ret; } /* XXX It's faster to return the atomic wkdep_usecount */ - return omap2_prm_read_mod_bits_shift(clkdm1->pwrdm.ptr->prcm_offs, PM_WKDEP, - (1 << clkdm2->dep_bit)); + return arch_clkdm->clkdm_read_wkdep(clkdm1, clkdm2); } /** @@ -542,33 +518,13 @@ int clkdm_read_wkdep(struct clockdomain *clkdm1, struct clockdomain *clkdm2) */ int clkdm_clear_all_wkdeps(struct clockdomain *clkdm) { - struct clkdm_dep *cd; - u32 mask = 0; - - if (!cpu_is_omap24xx() && !cpu_is_omap34xx()) { - pr_err("clockdomain: %s: %s: not yet implemented\n", - clkdm->name, __func__); - return -EINVAL; - } - if (!clkdm) return -EINVAL; - for (cd = clkdm->wkdep_srcs; cd && cd->clkdm_name; cd++) { - if (!omap_chip_is(cd->omap_chip)) - continue; - - if (!cd->clkdm && cd->clkdm_name) - cd->clkdm = _clkdm_lookup(cd->clkdm_name); - - /* PRM accesses are slow, so minimize them */ - mask |= 1 << cd->clkdm->dep_bit; - atomic_set(&cd->wkdep_usecount, 0); - } - - omap2_prm_clear_mod_reg_bits(mask, clkdm->pwrdm.ptr->prcm_offs, PM_WKDEP); + if (!arch_clkdm || !arch_clkdm->clkdm_clear_all_wkdeps) + return -EINVAL; - return 0; + return arch_clkdm->clkdm_clear_all_wkdeps(clkdm); } /** @@ -586,31 +542,33 @@ int clkdm_clear_all_wkdeps(struct clockdomain *clkdm) int clkdm_add_sleepdep(struct clockdomain *clkdm1, struct clockdomain *clkdm2) { struct clkdm_dep *cd; - - if (!cpu_is_omap34xx()) - return -EINVAL; + int ret = 0; if (!clkdm1 || !clkdm2) return -EINVAL; cd = _clkdm_deps_lookup(clkdm2, clkdm1->sleepdep_srcs); - if (IS_ERR(cd)) { + if (IS_ERR(cd)) + ret = PTR_ERR(cd); + + if (!arch_clkdm || !arch_clkdm->clkdm_add_sleepdep) + ret = -EINVAL; + + if (ret) { pr_debug("clockdomain: hardware cannot set/clear sleep " "dependency affecting %s from %s\n", clkdm1->name, clkdm2->name); - return PTR_ERR(cd); + return ret; } if (atomic_inc_return(&cd->sleepdep_usecount) == 1) { pr_debug("clockdomain: will prevent %s from sleeping if %s " "is active\n", clkdm1->name, clkdm2->name); - omap2_cm_set_mod_reg_bits((1 << clkdm2->dep_bit), - clkdm1->pwrdm.ptr->prcm_offs, - OMAP3430_CM_SLEEPDEP); + ret = arch_clkdm->clkdm_add_sleepdep(clkdm1, clkdm2); } - return 0; + return ret; } /** @@ -628,19 +586,23 @@ int clkdm_add_sleepdep(struct clockdomain *clkdm1, struct clockdomain *clkdm2) int clkdm_del_sleepdep(struct clockdomain *clkdm1, struct clockdomain *clkdm2) { struct clkdm_dep *cd; - - if (!cpu_is_omap34xx()) - return -EINVAL; + int ret = 0; if (!clkdm1 || !clkdm2) return -EINVAL; cd = _clkdm_deps_lookup(clkdm2, clkdm1->sleepdep_srcs); - if (IS_ERR(cd)) { + if (IS_ERR(cd)) + ret = PTR_ERR(cd); + + if (!arch_clkdm || !arch_clkdm->clkdm_del_sleepdep) + ret = -EINVAL; + + if (ret) { pr_debug("clockdomain: hardware cannot set/clear sleep " "dependency affecting %s from %s\n", clkdm1->name, clkdm2->name); - return PTR_ERR(cd); + return ret; } if (atomic_dec_return(&cd->sleepdep_usecount) == 0) { @@ -648,12 +610,10 @@ int clkdm_del_sleepdep(struct clockdomain *clkdm1, struct clockdomain *clkdm2) "sleeping if %s is active\n", clkdm1->name, clkdm2->name); - omap2_cm_clear_mod_reg_bits((1 << clkdm2->dep_bit), - clkdm1->pwrdm.ptr->prcm_offs, - OMAP3430_CM_SLEEPDEP); + ret = arch_clkdm->clkdm_del_sleepdep(clkdm1, clkdm2); } - return 0; + return ret; } /** @@ -675,25 +635,27 @@ int clkdm_del_sleepdep(struct clockdomain *clkdm1, struct clockdomain *clkdm2) int clkdm_read_sleepdep(struct clockdomain *clkdm1, struct clockdomain *clkdm2) { struct clkdm_dep *cd; - - if (!cpu_is_omap34xx()) - return -EINVAL; + int ret = 0; if (!clkdm1 || !clkdm2) return -EINVAL; cd = _clkdm_deps_lookup(clkdm2, clkdm1->sleepdep_srcs); - if (IS_ERR(cd)) { + if (IS_ERR(cd)) + ret = PTR_ERR(cd); + + if (!arch_clkdm || !arch_clkdm->clkdm_read_sleepdep) + ret = -EINVAL; + + if (ret) { pr_debug("clockdomain: hardware cannot set/clear sleep " "dependency affecting %s from %s\n", clkdm1->name, clkdm2->name); - return PTR_ERR(cd); + return ret; } /* XXX It's faster to return the atomic sleepdep_usecount */ - return omap2_prm_read_mod_bits_shift(clkdm1->pwrdm.ptr->prcm_offs, - OMAP3430_CM_SLEEPDEP, - (1 << clkdm2->dep_bit)); + return arch_clkdm->clkdm_read_sleepdep(clkdm1, clkdm2); } /** @@ -708,35 +670,17 @@ int clkdm_read_sleepdep(struct clockdomain *clkdm1, struct clockdomain *clkdm2) */ int clkdm_clear_all_sleepdeps(struct clockdomain *clkdm) { - struct clkdm_dep *cd; - u32 mask = 0; - - if (!cpu_is_omap34xx()) - return -EINVAL; - if (!clkdm) return -EINVAL; - for (cd = clkdm->sleepdep_srcs; cd && cd->clkdm_name; cd++) { - if (!omap_chip_is(cd->omap_chip)) - continue; - - if (!cd->clkdm && cd->clkdm_name) - cd->clkdm = _clkdm_lookup(cd->clkdm_name); - - /* PRM accesses are slow, so minimize them */ - mask |= 1 << cd->clkdm->dep_bit; - atomic_set(&cd->sleepdep_usecount, 0); - } - - omap2_prm_clear_mod_reg_bits(mask, clkdm->pwrdm.ptr->prcm_offs, - OMAP3430_CM_SLEEPDEP); + if (!arch_clkdm || !arch_clkdm->clkdm_clear_all_sleepdeps) + return -EINVAL; - return 0; + return arch_clkdm->clkdm_clear_all_sleepdeps(clkdm); } /** - * omap2_clkdm_sleep - force clockdomain sleep transition + * clkdm_sleep - force clockdomain sleep transition * @clkdm: struct clockdomain * * * Instruct the CM to force a sleep transition on the specified @@ -744,7 +688,7 @@ int clkdm_clear_all_sleepdeps(struct clockdomain *clkdm) * clockdomain does not support software-initiated sleep; 0 upon * success. */ -int omap2_clkdm_sleep(struct clockdomain *clkdm) +int clkdm_sleep(struct clockdomain *clkdm) { if (!clkdm) return -EINVAL; @@ -755,33 +699,16 @@ int omap2_clkdm_sleep(struct clockdomain *clkdm) return -EINVAL; } - pr_debug("clockdomain: forcing sleep on %s\n", clkdm->name); - - if (cpu_is_omap24xx()) { - - omap2_cm_set_mod_reg_bits(OMAP24XX_FORCESTATE_MASK, - clkdm->pwrdm.ptr->prcm_offs, OMAP2_PM_PWSTCTRL); - - } else if (cpu_is_omap34xx()) { - - omap3xxx_cm_clkdm_force_sleep(clkdm->pwrdm.ptr->prcm_offs, - clkdm->clktrctrl_mask); - - } else if (cpu_is_omap44xx()) { - - omap4_cminst_clkdm_force_sleep(clkdm->prcm_partition, - clkdm->cm_inst, - clkdm->clkdm_offs); + if (!arch_clkdm || !arch_clkdm->clkdm_sleep) + return -EINVAL; - } else { - BUG(); - }; + pr_debug("clockdomain: forcing sleep on %s\n", clkdm->name); - return 0; + return arch_clkdm->clkdm_sleep(clkdm); } /** - * omap2_clkdm_wakeup - force clockdomain wakeup transition + * clkdm_wakeup - force clockdomain wakeup transition * @clkdm: struct clockdomain * * * Instruct the CM to force a wakeup transition on the specified @@ -789,7 +716,7 @@ int omap2_clkdm_sleep(struct clockdomain *clkdm) * clockdomain does not support software-controlled wakeup; 0 upon * success. */ -int omap2_clkdm_wakeup(struct clockdomain *clkdm) +int clkdm_wakeup(struct clockdomain *clkdm) { if (!clkdm) return -EINVAL; @@ -800,33 +727,16 @@ int omap2_clkdm_wakeup(struct clockdomain *clkdm) return -EINVAL; } - pr_debug("clockdomain: forcing wakeup on %s\n", clkdm->name); - - if (cpu_is_omap24xx()) { - - omap2_cm_clear_mod_reg_bits(OMAP24XX_FORCESTATE_MASK, - clkdm->pwrdm.ptr->prcm_offs, OMAP2_PM_PWSTCTRL); - - } else if (cpu_is_omap34xx()) { - - omap3xxx_cm_clkdm_force_wakeup(clkdm->pwrdm.ptr->prcm_offs, - clkdm->clktrctrl_mask); - - } else if (cpu_is_omap44xx()) { - - omap4_cminst_clkdm_force_wakeup(clkdm->prcm_partition, - clkdm->cm_inst, - clkdm->clkdm_offs); + if (!arch_clkdm || !arch_clkdm->clkdm_wakeup) + return -EINVAL; - } else { - BUG(); - }; + pr_debug("clockdomain: forcing wakeup on %s\n", clkdm->name); - return 0; + return arch_clkdm->clkdm_wakeup(clkdm); } /** - * omap2_clkdm_allow_idle - enable hwsup idle transitions for clkdm + * clkdm_allow_idle - enable hwsup idle transitions for clkdm * @clkdm: struct clockdomain * * * Allow the hardware to automatically switch the clockdomain @clkdm into @@ -835,7 +745,7 @@ int omap2_clkdm_wakeup(struct clockdomain *clkdm) * framework, wkdep/sleepdep autodependencies are added; this is so * device drivers can read and write to the device. No return value. */ -void omap2_clkdm_allow_idle(struct clockdomain *clkdm) +void clkdm_allow_idle(struct clockdomain *clkdm) { if (!clkdm) return; @@ -846,27 +756,18 @@ void omap2_clkdm_allow_idle(struct clockdomain *clkdm) return; } + if (!arch_clkdm || !arch_clkdm->clkdm_allow_idle) + return; + pr_debug("clockdomain: enabling automatic idle transitions for %s\n", clkdm->name); - /* - * XXX This should be removed once TI adds wakeup/sleep - * dependency code and data for OMAP4. - */ - if (cpu_is_omap44xx()) { - pr_err("clockdomain: %s: OMAP4 wakeup/sleep dependency support: not yet implemented\n", clkdm->name); - } else { - if (atomic_read(&clkdm->usecount) > 0) - _clkdm_add_autodeps(clkdm); - } - - _enable_hwsup(clkdm); - + arch_clkdm->clkdm_allow_idle(clkdm); pwrdm_clkdm_state_switch(clkdm); } /** - * omap2_clkdm_deny_idle - disable hwsup idle transitions for clkdm + * clkdm_deny_idle - disable hwsup idle transitions for clkdm * @clkdm: struct clockdomain * * * Prevent the hardware from automatically switching the clockdomain @@ -874,7 +775,7 @@ void omap2_clkdm_allow_idle(struct clockdomain *clkdm) * downstream clocks enabled in the clock framework, wkdep/sleepdep * autodependencies are removed. No return value. */ -void omap2_clkdm_deny_idle(struct clockdomain *clkdm) +void clkdm_deny_idle(struct clockdomain *clkdm) { if (!clkdm) return; @@ -885,28 +786,20 @@ void omap2_clkdm_deny_idle(struct clockdomain *clkdm) return; } + if (!arch_clkdm || !arch_clkdm->clkdm_deny_idle) + return; + pr_debug("clockdomain: disabling automatic idle transitions for %s\n", clkdm->name); - _disable_hwsup(clkdm); - - /* - * XXX This should be removed once TI adds wakeup/sleep - * dependency code and data for OMAP4. - */ - if (cpu_is_omap44xx()) { - pr_err("clockdomain: %s: OMAP4 wakeup/sleep dependency support: not yet implemented\n", clkdm->name); - } else { - if (atomic_read(&clkdm->usecount) > 0) - _clkdm_del_autodeps(clkdm); - } + arch_clkdm->clkdm_deny_idle(clkdm); } /* Clockdomain-to-clock framework interface code */ /** - * omap2_clkdm_clk_enable - add an enabled downstream clock to this clkdm + * clkdm_clk_enable - add an enabled downstream clock to this clkdm * @clkdm: struct clockdomain * * @clk: struct clk * of the enabled downstream clock * @@ -919,10 +812,8 @@ void omap2_clkdm_deny_idle(struct clockdomain *clkdm) * by on-chip processors. Returns -EINVAL if passed null pointers; * returns 0 upon success or if the clockdomain is in hwsup idle mode. */ -int omap2_clkdm_clk_enable(struct clockdomain *clkdm, struct clk *clk) +int clkdm_clk_enable(struct clockdomain *clkdm, struct clk *clk) { - bool hwsup = false; - /* * XXX Rewrite this code to maintain a list of enabled * downstream clocks for debugging purposes? @@ -931,6 +822,9 @@ int omap2_clkdm_clk_enable(struct clockdomain *clkdm, struct clk *clk) if (!clkdm || !clk) return -EINVAL; + if (!arch_clkdm || !arch_clkdm->clkdm_clk_enable) + return -EINVAL; + if (atomic_inc_return(&clkdm->usecount) > 1) return 0; @@ -939,31 +833,7 @@ int omap2_clkdm_clk_enable(struct clockdomain *clkdm, struct clk *clk) pr_debug("clockdomain: clkdm %s: clk %s now enabled\n", clkdm->name, clk->name); - if (cpu_is_omap24xx() || cpu_is_omap34xx()) { - - if (!clkdm->clktrctrl_mask) - return 0; - - hwsup = omap2_cm_is_clkdm_in_hwsup(clkdm->pwrdm.ptr->prcm_offs, - clkdm->clktrctrl_mask); - - } else if (cpu_is_omap44xx()) { - - hwsup = omap4_cminst_is_clkdm_in_hwsup(clkdm->prcm_partition, - clkdm->cm_inst, - clkdm->clkdm_offs); - - } - - if (hwsup) { - /* Disable HW transitions when we are changing deps */ - _disable_hwsup(clkdm); - _clkdm_add_autodeps(clkdm); - _enable_hwsup(clkdm); - } else { - omap2_clkdm_wakeup(clkdm); - } - + arch_clkdm->clkdm_clk_enable(clkdm); pwrdm_wait_transition(clkdm->pwrdm.ptr); pwrdm_clkdm_state_switch(clkdm); @@ -971,7 +841,7 @@ int omap2_clkdm_clk_enable(struct clockdomain *clkdm, struct clk *clk) } /** - * omap2_clkdm_clk_disable - remove an enabled downstream clock from this clkdm + * clkdm_clk_disable - remove an enabled downstream clock from this clkdm * @clkdm: struct clockdomain * * @clk: struct clk * of the disabled downstream clock * @@ -984,10 +854,8 @@ int omap2_clkdm_clk_enable(struct clockdomain *clkdm, struct clk *clk) * is enabled; or returns 0 upon success or if the clockdomain is in * hwsup idle mode. */ -int omap2_clkdm_clk_disable(struct clockdomain *clkdm, struct clk *clk) +int clkdm_clk_disable(struct clockdomain *clkdm, struct clk *clk) { - bool hwsup = false; - /* * XXX Rewrite this code to maintain a list of enabled * downstream clocks for debugging purposes? @@ -996,6 +864,9 @@ int omap2_clkdm_clk_disable(struct clockdomain *clkdm, struct clk *clk) if (!clkdm || !clk) return -EINVAL; + if (!arch_clkdm || !arch_clkdm->clkdm_clk_disable) + return -EINVAL; + #ifdef DEBUG if (atomic_read(&clkdm->usecount) == 0) { WARN_ON(1); /* underflow */ @@ -1011,31 +882,7 @@ int omap2_clkdm_clk_disable(struct clockdomain *clkdm, struct clk *clk) pr_debug("clockdomain: clkdm %s: clk %s now disabled\n", clkdm->name, clk->name); - if (cpu_is_omap24xx() || cpu_is_omap34xx()) { - - if (!clkdm->clktrctrl_mask) - return 0; - - hwsup = omap2_cm_is_clkdm_in_hwsup(clkdm->pwrdm.ptr->prcm_offs, - clkdm->clktrctrl_mask); - - } else if (cpu_is_omap44xx()) { - - hwsup = omap4_cminst_is_clkdm_in_hwsup(clkdm->prcm_partition, - clkdm->cm_inst, - clkdm->clkdm_offs); - - } - - if (hwsup) { - /* Disable HW transitions when we are changing deps */ - _disable_hwsup(clkdm); - _clkdm_del_autodeps(clkdm); - _enable_hwsup(clkdm); - } else { - omap2_clkdm_sleep(clkdm); - } - + arch_clkdm->clkdm_clk_disable(clkdm); pwrdm_clkdm_state_switch(clkdm); return 0; diff --git a/arch/arm/mach-omap2/clockdomain.h b/arch/arm/mach-omap2/clockdomain.h index 9b459c26fb8..85b3dce6564 100644 --- a/arch/arm/mach-omap2/clockdomain.h +++ b/arch/arm/mach-omap2/clockdomain.h @@ -4,7 +4,7 @@ * OMAP2/3 clockdomain framework functions * * Copyright (C) 2008 Texas Instruments, Inc. - * Copyright (C) 2008-2010 Nokia Corporation + * Copyright (C) 2008-2011 Nokia Corporation * * Paul Walmsley * @@ -22,11 +22,19 @@ #include <plat/clock.h> #include <plat/cpu.h> -/* Clockdomain capability flags */ +/* + * Clockdomain flags + * + * XXX Document CLKDM_CAN_* flags + * + * CLKDM_NO_AUTODEPS: Prevent "autodeps" from being added/removed from this + * clockdomain. (Currently, this applies to OMAP3 clockdomains only.) + */ #define CLKDM_CAN_FORCE_SLEEP (1 << 0) #define CLKDM_CAN_FORCE_WAKEUP (1 << 1) #define CLKDM_CAN_ENABLE_AUTO (1 << 2) #define CLKDM_CAN_DISABLE_AUTO (1 << 3) +#define CLKDM_NO_AUTODEPS (1 << 4) #define CLKDM_CAN_HWSUP (CLKDM_CAN_ENABLE_AUTO | CLKDM_CAN_DISABLE_AUTO) #define CLKDM_CAN_SWSUP (CLKDM_CAN_FORCE_SLEEP | CLKDM_CAN_FORCE_WAKEUP) @@ -116,7 +124,42 @@ struct clockdomain { struct list_head node; }; -void clkdm_init(struct clockdomain **clkdms, struct clkdm_autodep *autodeps); +/** + * struct clkdm_ops - Arch specfic function implementations + * @clkdm_add_wkdep: Add a wakeup dependency between clk domains + * @clkdm_del_wkdep: Delete a wakeup dependency between clk domains + * @clkdm_read_wkdep: Read wakeup dependency state between clk domains + * @clkdm_clear_all_wkdeps: Remove all wakeup dependencies from the clk domain + * @clkdm_add_sleepdep: Add a sleep dependency between clk domains + * @clkdm_del_sleepdep: Delete a sleep dependency between clk domains + * @clkdm_read_sleepdep: Read sleep dependency state between clk domains + * @clkdm_clear_all_sleepdeps: Remove all sleep dependencies from the clk domain + * @clkdm_sleep: Force a clockdomain to sleep + * @clkdm_wakeup: Force a clockdomain to wakeup + * @clkdm_allow_idle: Enable hw supervised idle transitions for clock domain + * @clkdm_deny_idle: Disable hw supervised idle transitions for clock domain + * @clkdm_clk_enable: Put the clkdm in right state for a clock enable + * @clkdm_clk_disable: Put the clkdm in right state for a clock disable + */ +struct clkdm_ops { + int (*clkdm_add_wkdep)(struct clockdomain *clkdm1, struct clockdomain *clkdm2); + int (*clkdm_del_wkdep)(struct clockdomain *clkdm1, struct clockdomain *clkdm2); + int (*clkdm_read_wkdep)(struct clockdomain *clkdm1, struct clockdomain *clkdm2); + int (*clkdm_clear_all_wkdeps)(struct clockdomain *clkdm); + int (*clkdm_add_sleepdep)(struct clockdomain *clkdm1, struct clockdomain *clkdm2); + int (*clkdm_del_sleepdep)(struct clockdomain *clkdm1, struct clockdomain *clkdm2); + int (*clkdm_read_sleepdep)(struct clockdomain *clkdm1, struct clockdomain *clkdm2); + int (*clkdm_clear_all_sleepdeps)(struct clockdomain *clkdm); + int (*clkdm_sleep)(struct clockdomain *clkdm); + int (*clkdm_wakeup)(struct clockdomain *clkdm); + void (*clkdm_allow_idle)(struct clockdomain *clkdm); + void (*clkdm_deny_idle)(struct clockdomain *clkdm); + int (*clkdm_clk_enable)(struct clockdomain *clkdm); + int (*clkdm_clk_disable)(struct clockdomain *clkdm); +}; + +void clkdm_init(struct clockdomain **clkdms, struct clkdm_autodep *autodeps, + struct clkdm_ops *custom_funcs); struct clockdomain *clkdm_lookup(const char *name); int clkdm_for_each(int (*fn)(struct clockdomain *clkdm, void *user), @@ -132,16 +175,23 @@ int clkdm_del_sleepdep(struct clockdomain *clkdm1, struct clockdomain *clkdm2); int clkdm_read_sleepdep(struct clockdomain *clkdm1, struct clockdomain *clkdm2); int clkdm_clear_all_sleepdeps(struct clockdomain *clkdm); -void omap2_clkdm_allow_idle(struct clockdomain *clkdm); -void omap2_clkdm_deny_idle(struct clockdomain *clkdm); +void clkdm_allow_idle(struct clockdomain *clkdm); +void clkdm_deny_idle(struct clockdomain *clkdm); -int omap2_clkdm_wakeup(struct clockdomain *clkdm); -int omap2_clkdm_sleep(struct clockdomain *clkdm); +int clkdm_wakeup(struct clockdomain *clkdm); +int clkdm_sleep(struct clockdomain *clkdm); -int omap2_clkdm_clk_enable(struct clockdomain *clkdm, struct clk *clk); -int omap2_clkdm_clk_disable(struct clockdomain *clkdm, struct clk *clk); +int clkdm_clk_enable(struct clockdomain *clkdm, struct clk *clk); +int clkdm_clk_disable(struct clockdomain *clkdm, struct clk *clk); -extern void __init omap2_clockdomains_init(void); +extern void __init omap2xxx_clockdomains_init(void); +extern void __init omap3xxx_clockdomains_init(void); extern void __init omap44xx_clockdomains_init(void); +extern void _clkdm_add_autodeps(struct clockdomain *clkdm); +extern void _clkdm_del_autodeps(struct clockdomain *clkdm); + +extern struct clkdm_ops omap2_clkdm_operations; +extern struct clkdm_ops omap3_clkdm_operations; +extern struct clkdm_ops omap4_clkdm_operations; #endif diff --git a/arch/arm/mach-omap2/clockdomain2xxx_3xxx.c b/arch/arm/mach-omap2/clockdomain2xxx_3xxx.c new file mode 100644 index 00000000000..48d0db7e606 --- /dev/null +++ b/arch/arm/mach-omap2/clockdomain2xxx_3xxx.c @@ -0,0 +1,274 @@ +/* + * OMAP2 and OMAP3 clockdomain control + * + * Copyright (C) 2008-2010 Texas Instruments, Inc. + * Copyright (C) 2008-2010 Nokia Corporation + * + * Derived from mach-omap2/clockdomain.c written by Paul Walmsley + * Rajendra Nayak <rnayak@ti.com> + * + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License version 2 as + * published by the Free Software Foundation. + */ + +#include <linux/types.h> +#include <plat/prcm.h> +#include "prm.h" +#include "prm2xxx_3xxx.h" +#include "cm.h" +#include "cm2xxx_3xxx.h" +#include "cm-regbits-24xx.h" +#include "cm-regbits-34xx.h" +#include "prm-regbits-24xx.h" +#include "clockdomain.h" + +static int omap2_clkdm_add_wkdep(struct clockdomain *clkdm1, + struct clockdomain *clkdm2) +{ + omap2_prm_set_mod_reg_bits((1 << clkdm2->dep_bit), + clkdm1->pwrdm.ptr->prcm_offs, PM_WKDEP); + return 0; +} + +static int omap2_clkdm_del_wkdep(struct clockdomain *clkdm1, + struct clockdomain *clkdm2) +{ + omap2_prm_clear_mod_reg_bits((1 << clkdm2->dep_bit), + clkdm1->pwrdm.ptr->prcm_offs, PM_WKDEP); + return 0; +} + +static int omap2_clkdm_read_wkdep(struct clockdomain *clkdm1, + struct clockdomain *clkdm2) +{ + return omap2_prm_read_mod_bits_shift(clkdm1->pwrdm.ptr->prcm_offs, + PM_WKDEP, (1 << clkdm2->dep_bit)); +} + +static int omap2_clkdm_clear_all_wkdeps(struct clockdomain *clkdm) +{ + struct clkdm_dep *cd; + u32 mask = 0; + + for (cd = clkdm->wkdep_srcs; cd && cd->clkdm_name; cd++) { + if (!omap_chip_is(cd->omap_chip)) + continue; + if (!cd->clkdm) + continue; /* only happens if data is erroneous */ + + /* PRM accesses are slow, so minimize them */ + mask |= 1 << cd->clkdm->dep_bit; + atomic_set(&cd->wkdep_usecount, 0); + } + + omap2_prm_clear_mod_reg_bits(mask, clkdm->pwrdm.ptr->prcm_offs, + PM_WKDEP); + return 0; +} + +static int omap3_clkdm_add_sleepdep(struct clockdomain *clkdm1, + struct clockdomain *clkdm2) +{ + omap2_cm_set_mod_reg_bits((1 << clkdm2->dep_bit), + clkdm1->pwrdm.ptr->prcm_offs, + OMAP3430_CM_SLEEPDEP); + return 0; +} + +static int omap3_clkdm_del_sleepdep(struct clockdomain *clkdm1, + struct clockdomain *clkdm2) +{ + omap2_cm_clear_mod_reg_bits((1 << clkdm2->dep_bit), + clkdm1->pwrdm.ptr->prcm_offs, + OMAP3430_CM_SLEEPDEP); + return 0; +} + +static int omap3_clkdm_read_sleepdep(struct clockdomain *clkdm1, + struct clockdomain *clkdm2) +{ + return omap2_prm_read_mod_bits_shift(clkdm1->pwrdm.ptr->prcm_offs, + OMAP3430_CM_SLEEPDEP, (1 << clkdm2->dep_bit)); +} + +static int omap3_clkdm_clear_all_sleepdeps(struct clockdomain *clkdm) +{ + struct clkdm_dep *cd; + u32 mask = 0; + + for (cd = clkdm->sleepdep_srcs; cd && cd->clkdm_name; cd++) { + if (!omap_chip_is(cd->omap_chip)) + continue; + if (!cd->clkdm) + continue; /* only happens if data is erroneous */ + + /* PRM accesses are slow, so minimize them */ + mask |= 1 << cd->clkdm->dep_bit; + atomic_set(&cd->sleepdep_usecount, 0); + } + omap2_prm_clear_mod_reg_bits(mask, clkdm->pwrdm.ptr->prcm_offs, + OMAP3430_CM_SLEEPDEP); + return 0; +} + +static int omap2_clkdm_sleep(struct clockdomain *clkdm) +{ + omap2_cm_set_mod_reg_bits(OMAP24XX_FORCESTATE_MASK, + clkdm->pwrdm.ptr->prcm_offs, + OMAP2_PM_PWSTCTRL); + return 0; +} + +static int omap2_clkdm_wakeup(struct clockdomain *clkdm) +{ + omap2_cm_clear_mod_reg_bits(OMAP24XX_FORCESTATE_MASK, + clkdm->pwrdm.ptr->prcm_offs, + OMAP2_PM_PWSTCTRL); + return 0; +} + +static void omap2_clkdm_allow_idle(struct clockdomain *clkdm) +{ + if (atomic_read(&clkdm->usecount) > 0) + _clkdm_add_autodeps(clkdm); + + omap2xxx_cm_clkdm_enable_hwsup(clkdm->pwrdm.ptr->prcm_offs, + clkdm->clktrctrl_mask); +} + +static void omap2_clkdm_deny_idle(struct clockdomain *clkdm) +{ + omap2xxx_cm_clkdm_disable_hwsup(clkdm->pwrdm.ptr->prcm_offs, + clkdm->clktrctrl_mask); + + if (atomic_read(&clkdm->usecount) > 0) + _clkdm_del_autodeps(clkdm); +} + +static void _enable_hwsup(struct clockdomain *clkdm) +{ + if (cpu_is_omap24xx()) + omap2xxx_cm_clkdm_enable_hwsup(clkdm->pwrdm.ptr->prcm_offs, + clkdm->clktrctrl_mask); + else if (cpu_is_omap34xx()) + omap3xxx_cm_clkdm_enable_hwsup(clkdm->pwrdm.ptr->prcm_offs, + clkdm->clktrctrl_mask); +} + +static void _disable_hwsup(struct clockdomain *clkdm) +{ + if (cpu_is_omap24xx()) + omap2xxx_cm_clkdm_disable_hwsup(clkdm->pwrdm.ptr->prcm_offs, + clkdm->clktrctrl_mask); + else if (cpu_is_omap34xx()) + omap3xxx_cm_clkdm_disable_hwsup(clkdm->pwrdm.ptr->prcm_offs, + clkdm->clktrctrl_mask); +} + + +static int omap2_clkdm_clk_enable(struct clockdomain *clkdm) +{ + bool hwsup = false; + + if (!clkdm->clktrctrl_mask) + return 0; + + hwsup = omap2_cm_is_clkdm_in_hwsup(clkdm->pwrdm.ptr->prcm_offs, + clkdm->clktrctrl_mask); + + if (hwsup) { + /* Disable HW transitions when we are changing deps */ + _disable_hwsup(clkdm); + _clkdm_add_autodeps(clkdm); + _enable_hwsup(clkdm); + } else { + clkdm_wakeup(clkdm); + } + + return 0; +} + +static int omap2_clkdm_clk_disable(struct clockdomain *clkdm) +{ + bool hwsup = false; + + if (!clkdm->clktrctrl_mask) + return 0; + + hwsup = omap2_cm_is_clkdm_in_hwsup(clkdm->pwrdm.ptr->prcm_offs, + clkdm->clktrctrl_mask); + + if (hwsup) { + /* Disable HW transitions when we are changing deps */ + _disable_hwsup(clkdm); + _clkdm_del_autodeps(clkdm); + _enable_hwsup(clkdm); + } else { + clkdm_sleep(clkdm); + } + + return 0; +} + +static int omap3_clkdm_sleep(struct clockdomain *clkdm) +{ + omap3xxx_cm_clkdm_force_sleep(clkdm->pwrdm.ptr->prcm_offs, + clkdm->clktrctrl_mask); + return 0; +} + +static int omap3_clkdm_wakeup(struct clockdomain *clkdm) +{ + omap3xxx_cm_clkdm_force_wakeup(clkdm->pwrdm.ptr->prcm_offs, + clkdm->clktrctrl_mask); + return 0; +} + +static void omap3_clkdm_allow_idle(struct clockdomain *clkdm) +{ + if (atomic_read(&clkdm->usecount) > 0) + _clkdm_add_autodeps(clkdm); + + omap3xxx_cm_clkdm_enable_hwsup(clkdm->pwrdm.ptr->prcm_offs, + clkdm->clktrctrl_mask); +} + +static void omap3_clkdm_deny_idle(struct clockdomain *clkdm) +{ + omap3xxx_cm_clkdm_disable_hwsup(clkdm->pwrdm.ptr->prcm_offs, + clkdm->clktrctrl_mask); + + if (atomic_read(&clkdm->usecount) > 0) + _clkdm_del_autodeps(clkdm); +} + +struct clkdm_ops omap2_clkdm_operations = { + .clkdm_add_wkdep = omap2_clkdm_add_wkdep, + .clkdm_del_wkdep = omap2_clkdm_del_wkdep, + .clkdm_read_wkdep = omap2_clkdm_read_wkdep, + .clkdm_clear_all_wkdeps = omap2_clkdm_clear_all_wkdeps, + .clkdm_sleep = omap2_clkdm_sleep, + .clkdm_wakeup = omap2_clkdm_wakeup, + .clkdm_allow_idle = omap2_clkdm_allow_idle, + .clkdm_deny_idle = omap2_clkdm_deny_idle, + .clkdm_clk_enable = omap2_clkdm_clk_enable, + .clkdm_clk_disable = omap2_clkdm_clk_disable, +}; + +struct clkdm_ops omap3_clkdm_operations = { + .clkdm_add_wkdep = omap2_clkdm_add_wkdep, + .clkdm_del_wkdep = omap2_clkdm_del_wkdep, + .clkdm_read_wkdep = omap2_clkdm_read_wkdep, + .clkdm_clear_all_wkdeps = omap2_clkdm_clear_all_wkdeps, + .clkdm_add_sleepdep = omap3_clkdm_add_sleepdep, + .clkdm_del_sleepdep = omap3_clkdm_del_sleepdep, + .clkdm_read_sleepdep = omap3_clkdm_read_sleepdep, + .clkdm_clear_all_sleepdeps = omap3_clkdm_clear_all_sleepdeps, + .clkdm_sleep = omap3_clkdm_sleep, + .clkdm_wakeup = omap3_clkdm_wakeup, + .clkdm_allow_idle = omap3_clkdm_allow_idle, + .clkdm_deny_idle = omap3_clkdm_deny_idle, + .clkdm_clk_enable = omap2_clkdm_clk_enable, + .clkdm_clk_disable = omap2_clkdm_clk_disable, +}; diff --git a/arch/arm/mach-omap2/clockdomain44xx.c b/arch/arm/mach-omap2/clockdomain44xx.c new file mode 100644 index 00000000000..a1a4ecd2654 --- /dev/null +++ b/arch/arm/mach-omap2/clockdomain44xx.c @@ -0,0 +1,137 @@ +/* + * OMAP4 clockdomain control + * + * Copyright (C) 2008-2010 Texas Instruments, Inc. + * Copyright (C) 2008-2010 Nokia Corporation + * + * Derived from mach-omap2/clockdomain.c written by Paul Walmsley + * Rajendra Nayak <rnayak@ti.com> + * + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License version 2 as + * published by the Free Software Foundation. + */ + +#include <linux/kernel.h> +#include "clockdomain.h" +#include "cminst44xx.h" +#include "cm44xx.h" + +static int omap4_clkdm_add_wkup_sleep_dep(struct clockdomain *clkdm1, + struct clockdomain *clkdm2) +{ + omap4_cminst_set_inst_reg_bits((1 << clkdm2->dep_bit), + clkdm1->prcm_partition, + clkdm1->cm_inst, clkdm1->clkdm_offs + + OMAP4_CM_STATICDEP); + return 0; +} + +static int omap4_clkdm_del_wkup_sleep_dep(struct clockdomain *clkdm1, + struct clockdomain *clkdm2) +{ + omap4_cminst_clear_inst_reg_bits((1 << clkdm2->dep_bit), + clkdm1->prcm_partition, + clkdm1->cm_inst, clkdm1->clkdm_offs + + OMAP4_CM_STATICDEP); + return 0; +} + +static int omap4_clkdm_read_wkup_sleep_dep(struct clockdomain *clkdm1, + struct clockdomain *clkdm2) +{ + return omap4_cminst_read_inst_reg_bits(clkdm1->prcm_partition, + clkdm1->cm_inst, clkdm1->clkdm_offs + + OMAP4_CM_STATICDEP, + (1 << clkdm2->dep_bit)); +} + +static int omap4_clkdm_clear_all_wkup_sleep_deps(struct clockdomain *clkdm) +{ + struct clkdm_dep *cd; + u32 mask = 0; + + for (cd = clkdm->wkdep_srcs; cd && cd->clkdm_name; cd++) { + if (!omap_chip_is(cd->omap_chip)) + continue; + if (!cd->clkdm) + continue; /* only happens if data is erroneous */ + + mask |= 1 << cd->clkdm->dep_bit; + atomic_set(&cd->wkdep_usecount, 0); + } + + omap4_cminst_clear_inst_reg_bits(mask, clkdm->prcm_partition, + clkdm->cm_inst, clkdm->clkdm_offs + + OMAP4_CM_STATICDEP); + return 0; +} + +static int omap4_clkdm_sleep(struct clockdomain *clkdm) +{ + omap4_cminst_clkdm_force_sleep(clkdm->prcm_partition, + clkdm->cm_inst, clkdm->clkdm_offs); + return 0; +} + +static int omap4_clkdm_wakeup(struct clockdomain *clkdm) +{ + omap4_cminst_clkdm_force_wakeup(clkdm->prcm_partition, + clkdm->cm_inst, clkdm->clkdm_offs); + return 0; +} + +static void omap4_clkdm_allow_idle(struct clockdomain *clkdm) +{ + omap4_cminst_clkdm_enable_hwsup(clkdm->prcm_partition, + clkdm->cm_inst, clkdm->clkdm_offs); +} + +static void omap4_clkdm_deny_idle(struct clockdomain *clkdm) +{ + omap4_cminst_clkdm_disable_hwsup(clkdm->prcm_partition, + clkdm->cm_inst, clkdm->clkdm_offs); +} + +static int omap4_clkdm_clk_enable(struct clockdomain *clkdm) +{ + bool hwsup = false; + + hwsup = omap4_cminst_is_clkdm_in_hwsup(clkdm->prcm_partition, + clkdm->cm_inst, clkdm->clkdm_offs); + + if (!hwsup) + clkdm_wakeup(clkdm); + + return 0; +} + +static int omap4_clkdm_clk_disable(struct clockdomain *clkdm) +{ + bool hwsup = false; + + hwsup = omap4_cminst_is_clkdm_in_hwsup(clkdm->prcm_partition, + clkdm->cm_inst, clkdm->clkdm_offs); + + if (!hwsup) + clkdm_sleep(clkdm); + + return 0; +} + +struct clkdm_ops omap4_clkdm_operations = { + .clkdm_add_wkdep = omap4_clkdm_add_wkup_sleep_dep, + .clkdm_del_wkdep = omap4_clkdm_del_wkup_sleep_dep, + .clkdm_read_wkdep = omap4_clkdm_read_wkup_sleep_dep, + .clkdm_clear_all_wkdeps = omap4_clkdm_clear_all_wkup_sleep_deps, + .clkdm_add_sleepdep = omap4_clkdm_add_wkup_sleep_dep, + .clkdm_del_sleepdep = omap4_clkdm_del_wkup_sleep_dep, + .clkdm_read_sleepdep = omap4_clkdm_read_wkup_sleep_dep, + .clkdm_clear_all_sleepdeps = omap4_clkdm_clear_all_wkup_sleep_deps, + .clkdm_sleep = omap4_clkdm_sleep, + .clkdm_wakeup = omap4_clkdm_wakeup, + .clkdm_allow_idle = omap4_clkdm_allow_idle, + .clkdm_deny_idle = omap4_clkdm_deny_idle, + .clkdm_clk_enable = omap4_clkdm_clk_enable, + .clkdm_clk_disable = omap4_clkdm_clk_disable, +}; diff --git a/arch/arm/mach-omap2/clockdomains2xxx_3xxx_data.c b/arch/arm/mach-omap2/clockdomains2xxx_3xxx_data.c index e4a7133ea3b..13bde95b679 100644 --- a/arch/arm/mach-omap2/clockdomains2xxx_3xxx_data.c +++ b/arch/arm/mach-omap2/clockdomains2xxx_3xxx_data.c @@ -89,6 +89,8 @@ static struct clkdm_dep gfx_sgx_wkdeps[] = { /* 24XX-specific possible dependencies */ +#ifdef CONFIG_ARCH_OMAP2 + /* Wakeup dependency source arrays */ /* 2420/2430 PM_WKDEP_DSP: CORE, MPU, WKUP */ @@ -168,10 +170,11 @@ static struct clkdm_dep core_24xx_wkdeps[] = { { NULL }, }; +#endif /* CONFIG_ARCH_OMAP2 */ /* 2430-specific possible wakeup dependencies */ -#ifdef CONFIG_ARCH_OMAP2430 +#ifdef CONFIG_SOC_OMAP2430 /* 2430 PM_WKDEP_MDM: CORE, MPU, WKUP */ static struct clkdm_dep mdm_2430_wkdeps[] = { @@ -194,7 +197,7 @@ static struct clkdm_dep mdm_2430_wkdeps[] = { { NULL }, }; -#endif /* CONFIG_ARCH_OMAP2430 */ +#endif /* CONFIG_SOC_OMAP2430 */ /* OMAP3-specific possible dependencies */ @@ -450,7 +453,7 @@ static struct clockdomain cm_clkdm = { * 2420-only clockdomains */ -#if defined(CONFIG_ARCH_OMAP2420) +#if defined(CONFIG_SOC_OMAP2420) static struct clockdomain mpu_2420_clkdm = { .name = "mpu_clkdm", @@ -514,14 +517,14 @@ static struct clockdomain dss_2420_clkdm = { .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP2420), }; -#endif /* CONFIG_ARCH_OMAP2420 */ +#endif /* CONFIG_SOC_OMAP2420 */ /* * 2430-only clockdomains */ -#if defined(CONFIG_ARCH_OMAP2430) +#if defined(CONFIG_SOC_OMAP2430) static struct clockdomain mpu_2430_clkdm = { .name = "mpu_clkdm", @@ -600,7 +603,7 @@ static struct clockdomain dss_2430_clkdm = { .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP2430), }; -#endif /* CONFIG_ARCH_OMAP2430 */ +#endif /* CONFIG_SOC_OMAP2430 */ /* @@ -811,7 +814,7 @@ static struct clockdomain *clockdomains_omap2[] __initdata = { &cm_clkdm, &prm_clkdm, -#ifdef CONFIG_ARCH_OMAP2420 +#ifdef CONFIG_SOC_OMAP2420 &mpu_2420_clkdm, &iva1_2420_clkdm, &dsp_2420_clkdm, @@ -821,7 +824,7 @@ static struct clockdomain *clockdomains_omap2[] __initdata = { &dss_2420_clkdm, #endif -#ifdef CONFIG_ARCH_OMAP2430 +#ifdef CONFIG_SOC_OMAP2430 &mpu_2430_clkdm, &mdm_clkdm, &dsp_2430_clkdm, @@ -854,7 +857,12 @@ static struct clockdomain *clockdomains_omap2[] __initdata = { NULL, }; -void __init omap2_clockdomains_init(void) +void __init omap2xxx_clockdomains_init(void) +{ + clkdm_init(clockdomains_omap2, clkdm_autodeps, &omap2_clkdm_operations); +} + +void __init omap3xxx_clockdomains_init(void) { - clkdm_init(clockdomains_omap2, clkdm_autodeps); + clkdm_init(clockdomains_omap2, clkdm_autodeps, &omap3_clkdm_operations); } diff --git a/arch/arm/mach-omap2/clockdomains44xx_data.c b/arch/arm/mach-omap2/clockdomains44xx_data.c index 10622c914ab..a607ec196e8 100644 --- a/arch/arm/mach-omap2/clockdomains44xx_data.c +++ b/arch/arm/mach-omap2/clockdomains44xx_data.c @@ -18,11 +18,6 @@ * published by the Free Software Foundation. */ -/* - * To-Do List - * -> Populate the Sleep/Wakeup dependencies for the domains - */ - #include <linux/kernel.h> #include <linux/io.h> @@ -35,6 +30,355 @@ #include "prcm44xx.h" #include "prcm_mpu44xx.h" +/* Static Dependencies for OMAP4 Clock Domains */ + +static struct clkdm_dep ducati_wkup_sleep_deps[] = { + { + .clkdm_name = "abe_clkdm", + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430) + }, + { + .clkdm_name = "ivahd_clkdm", + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430) + }, + { + .clkdm_name = "l3_1_clkdm", + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430) + }, + { + .clkdm_name = "l3_2_clkdm", + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430) + }, + { + .clkdm_name = "l3_dss_clkdm", + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430) + }, + { + .clkdm_name = "l3_emif_clkdm", + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430) + }, + { + .clkdm_name = "l3_gfx_clkdm", + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430) + }, + { + .clkdm_name = "l3_init_clkdm", + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430) + }, + { + .clkdm_name = "l4_cfg_clkdm", + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430) + }, + { + .clkdm_name = "l4_per_clkdm", + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430) + }, + { + .clkdm_name = "l4_secure_clkdm", + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430) + }, + { + .clkdm_name = "l4_wkup_clkdm", + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430) + }, + { + .clkdm_name = "tesla_clkdm", + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430) + }, + { NULL }, +}; + +static struct clkdm_dep iss_wkup_sleep_deps[] = { + { + .clkdm_name = "ivahd_clkdm", + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430) + }, + { + .clkdm_name = "l3_1_clkdm", + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430) + }, + { + .clkdm_name = "l3_emif_clkdm", + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430) + }, + { NULL }, +}; + +static struct clkdm_dep ivahd_wkup_sleep_deps[] = { + { + .clkdm_name = "l3_1_clkdm", + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430) + }, + { + .clkdm_name = "l3_emif_clkdm", + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430) + }, + { NULL }, +}; + +static struct clkdm_dep l3_d2d_wkup_sleep_deps[] = { + { + .clkdm_name = "abe_clkdm", + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430) + }, + { + .clkdm_name = "ivahd_clkdm", + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430) + }, + { + .clkdm_name = "l3_1_clkdm", + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430) + }, + { + .clkdm_name = "l3_2_clkdm", + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430) + }, + { + .clkdm_name = "l3_emif_clkdm", + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430) + }, + { + .clkdm_name = "l3_init_clkdm", + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430) + }, + { + .clkdm_name = "l4_cfg_clkdm", + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430) + }, + { + .clkdm_name = "l4_per_clkdm", + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430) + }, + { NULL }, +}; + +static struct clkdm_dep l3_dma_wkup_sleep_deps[] = { + { + .clkdm_name = "abe_clkdm", + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430) + }, + { + .clkdm_name = "ducati_clkdm", + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430) + }, + { + .clkdm_name = "ivahd_clkdm", + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430) + }, + { + .clkdm_name = "l3_1_clkdm", + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430) + }, + { + .clkdm_name = "l3_dss_clkdm", + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430) + }, + { + .clkdm_name = "l3_emif_clkdm", + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430) + }, + { + .clkdm_name = "l3_init_clkdm", + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430) + }, + { + .clkdm_name = "l4_cfg_clkdm", + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430) + }, + { + .clkdm_name = "l4_per_clkdm", + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430) + }, + { + .clkdm_name = "l4_secure_clkdm", + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430) + }, + { + .clkdm_name = "l4_wkup_clkdm", + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430) + }, + { NULL }, +}; + +static struct clkdm_dep l3_dss_wkup_sleep_deps[] = { + { + .clkdm_name = "ivahd_clkdm", + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430) + }, + { + .clkdm_name = "l3_2_clkdm", + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430) + }, + { + .clkdm_name = "l3_emif_clkdm", + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430) + }, + { NULL }, +}; + +static struct clkdm_dep l3_gfx_wkup_sleep_deps[] = { + { + .clkdm_name = "ivahd_clkdm", + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430) + }, + { + .clkdm_name = "l3_1_clkdm", + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430) + }, + { + .clkdm_name = "l3_emif_clkdm", + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430) + }, + { NULL }, +}; + +static struct clkdm_dep l3_init_wkup_sleep_deps[] = { + { + .clkdm_name = "abe_clkdm", + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430) + }, + { + .clkdm_name = "ivahd_clkdm", + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430) + }, + { + .clkdm_name = "l3_emif_clkdm", + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430) + }, + { + .clkdm_name = "l4_cfg_clkdm", + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430) + }, + { + .clkdm_name = "l4_per_clkdm", + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430) + }, + { + .clkdm_name = "l4_secure_clkdm", + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430) + }, + { + .clkdm_name = "l4_wkup_clkdm", + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430) + }, + { NULL }, +}; + +static struct clkdm_dep l4_secure_wkup_sleep_deps[] = { + { + .clkdm_name = "l3_1_clkdm", + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430) + }, + { + .clkdm_name = "l3_emif_clkdm", + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430) + }, + { + .clkdm_name = "l4_per_clkdm", + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430) + }, + { NULL }, +}; + +static struct clkdm_dep mpuss_wkup_sleep_deps[] = { + { + .clkdm_name = "abe_clkdm", + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430) + }, + { + .clkdm_name = "ducati_clkdm", + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430) + }, + { + .clkdm_name = "ivahd_clkdm", + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430) + }, + { + .clkdm_name = "l3_1_clkdm", + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430) + }, + { + .clkdm_name = "l3_2_clkdm", + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430) + }, + { + .clkdm_name = "l3_dss_clkdm", + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430) + }, + { + .clkdm_name = "l3_emif_clkdm", + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430) + }, + { + .clkdm_name = "l3_gfx_clkdm", + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430) + }, + { + .clkdm_name = "l3_init_clkdm", + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430) + }, + { + .clkdm_name = "l4_cfg_clkdm", + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430) + }, + { + .clkdm_name = "l4_per_clkdm", + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430) + }, + { + .clkdm_name = "l4_secure_clkdm", + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430) + }, + { + .clkdm_name = "l4_wkup_clkdm", + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430) + }, + { + .clkdm_name = "tesla_clkdm", + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430) + }, + { NULL }, +}; + +static struct clkdm_dep tesla_wkup_sleep_deps[] = { + { + .clkdm_name = "abe_clkdm", + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430) + }, + { + .clkdm_name = "ivahd_clkdm", + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430) + }, + { + .clkdm_name = "l3_1_clkdm", + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430) + }, + { + .clkdm_name = "l3_2_clkdm", + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430) + }, + { + .clkdm_name = "l3_emif_clkdm", + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430) + }, + { + .clkdm_name = "l3_init_clkdm", + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430) + }, + { + .clkdm_name = "l4_cfg_clkdm", + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430) + }, + { + .clkdm_name = "l4_per_clkdm", + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430) + }, + { + .clkdm_name = "l4_wkup_clkdm", + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430) + }, + { NULL }, +}; static struct clockdomain l4_cefuse_44xx_clkdm = { .name = "l4_cefuse_clkdm", @@ -52,6 +396,7 @@ static struct clockdomain l4_cfg_44xx_clkdm = { .prcm_partition = OMAP4430_CM2_PARTITION, .cm_inst = OMAP4430_CM2_CORE_INST, .clkdm_offs = OMAP4430_CM2_CORE_L4CFG_CDOFFS, + .dep_bit = OMAP4430_L4CFG_STATDEP_SHIFT, .flags = CLKDM_CAN_HWSUP, .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430), }; @@ -62,6 +407,9 @@ static struct clockdomain tesla_44xx_clkdm = { .prcm_partition = OMAP4430_CM1_PARTITION, .cm_inst = OMAP4430_CM1_TESLA_INST, .clkdm_offs = OMAP4430_CM1_TESLA_TESLA_CDOFFS, + .dep_bit = OMAP4430_TESLA_STATDEP_SHIFT, + .wkdep_srcs = tesla_wkup_sleep_deps, + .sleepdep_srcs = tesla_wkup_sleep_deps, .flags = CLKDM_CAN_HWSUP_SWSUP, .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430), }; @@ -72,6 +420,9 @@ static struct clockdomain l3_gfx_44xx_clkdm = { .prcm_partition = OMAP4430_CM2_PARTITION, .cm_inst = OMAP4430_CM2_GFX_INST, .clkdm_offs = OMAP4430_CM2_GFX_GFX_CDOFFS, + .dep_bit = OMAP4430_GFX_STATDEP_SHIFT, + .wkdep_srcs = l3_gfx_wkup_sleep_deps, + .sleepdep_srcs = l3_gfx_wkup_sleep_deps, .flags = CLKDM_CAN_HWSUP_SWSUP, .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430), }; @@ -82,6 +433,9 @@ static struct clockdomain ivahd_44xx_clkdm = { .prcm_partition = OMAP4430_CM2_PARTITION, .cm_inst = OMAP4430_CM2_IVAHD_INST, .clkdm_offs = OMAP4430_CM2_IVAHD_IVAHD_CDOFFS, + .dep_bit = OMAP4430_IVAHD_STATDEP_SHIFT, + .wkdep_srcs = ivahd_wkup_sleep_deps, + .sleepdep_srcs = ivahd_wkup_sleep_deps, .flags = CLKDM_CAN_HWSUP_SWSUP, .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430), }; @@ -92,6 +446,9 @@ static struct clockdomain l4_secure_44xx_clkdm = { .prcm_partition = OMAP4430_CM2_PARTITION, .cm_inst = OMAP4430_CM2_L4PER_INST, .clkdm_offs = OMAP4430_CM2_L4PER_L4SEC_CDOFFS, + .dep_bit = OMAP4430_L4SEC_STATDEP_SHIFT, + .wkdep_srcs = l4_secure_wkup_sleep_deps, + .sleepdep_srcs = l4_secure_wkup_sleep_deps, .flags = CLKDM_CAN_HWSUP_SWSUP, .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430), }; @@ -102,6 +459,7 @@ static struct clockdomain l4_per_44xx_clkdm = { .prcm_partition = OMAP4430_CM2_PARTITION, .cm_inst = OMAP4430_CM2_L4PER_INST, .clkdm_offs = OMAP4430_CM2_L4PER_L4PER_CDOFFS, + .dep_bit = OMAP4430_L4PER_STATDEP_SHIFT, .flags = CLKDM_CAN_HWSUP_SWSUP, .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430), }; @@ -112,6 +470,7 @@ static struct clockdomain abe_44xx_clkdm = { .prcm_partition = OMAP4430_CM1_PARTITION, .cm_inst = OMAP4430_CM1_ABE_INST, .clkdm_offs = OMAP4430_CM1_ABE_ABE_CDOFFS, + .dep_bit = OMAP4430_ABE_STATDEP_SHIFT, .flags = CLKDM_CAN_HWSUP_SWSUP, .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430), }; @@ -131,6 +490,9 @@ static struct clockdomain l3_init_44xx_clkdm = { .prcm_partition = OMAP4430_CM2_PARTITION, .cm_inst = OMAP4430_CM2_L3INIT_INST, .clkdm_offs = OMAP4430_CM2_L3INIT_L3INIT_CDOFFS, + .dep_bit = OMAP4430_L3INIT_STATDEP_SHIFT, + .wkdep_srcs = l3_init_wkup_sleep_deps, + .sleepdep_srcs = l3_init_wkup_sleep_deps, .flags = CLKDM_CAN_HWSUP_SWSUP, .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430), }; @@ -141,6 +503,8 @@ static struct clockdomain mpuss_44xx_clkdm = { .prcm_partition = OMAP4430_CM1_PARTITION, .cm_inst = OMAP4430_CM1_MPU_INST, .clkdm_offs = OMAP4430_CM1_MPU_MPU_CDOFFS, + .wkdep_srcs = mpuss_wkup_sleep_deps, + .sleepdep_srcs = mpuss_wkup_sleep_deps, .flags = CLKDM_CAN_FORCE_WAKEUP | CLKDM_CAN_HWSUP, .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430), }; @@ -150,7 +514,7 @@ static struct clockdomain mpu0_44xx_clkdm = { .pwrdm = { .name = "cpu0_pwrdm" }, .prcm_partition = OMAP4430_PRCM_MPU_PARTITION, .cm_inst = OMAP4430_PRCM_MPU_CPU0_INST, - .clkdm_offs = OMAP4430_PRCM_MPU_CPU0_MPU_CDOFFS, + .clkdm_offs = OMAP4430_PRCM_MPU_CPU0_CPU0_CDOFFS, .flags = CLKDM_CAN_FORCE_WAKEUP | CLKDM_CAN_HWSUP, .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430), }; @@ -160,7 +524,7 @@ static struct clockdomain mpu1_44xx_clkdm = { .pwrdm = { .name = "cpu1_pwrdm" }, .prcm_partition = OMAP4430_PRCM_MPU_PARTITION, .cm_inst = OMAP4430_PRCM_MPU_CPU1_INST, - .clkdm_offs = OMAP4430_PRCM_MPU_CPU1_MPU_CDOFFS, + .clkdm_offs = OMAP4430_PRCM_MPU_CPU1_CPU1_CDOFFS, .flags = CLKDM_CAN_FORCE_WAKEUP | CLKDM_CAN_HWSUP, .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430), }; @@ -171,6 +535,7 @@ static struct clockdomain l3_emif_44xx_clkdm = { .prcm_partition = OMAP4430_CM2_PARTITION, .cm_inst = OMAP4430_CM2_CORE_INST, .clkdm_offs = OMAP4430_CM2_CORE_MEMIF_CDOFFS, + .dep_bit = OMAP4430_MEMIF_STATDEP_SHIFT, .flags = CLKDM_CAN_FORCE_WAKEUP | CLKDM_CAN_HWSUP, .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430), }; @@ -191,6 +556,9 @@ static struct clockdomain ducati_44xx_clkdm = { .prcm_partition = OMAP4430_CM2_PARTITION, .cm_inst = OMAP4430_CM2_CORE_INST, .clkdm_offs = OMAP4430_CM2_CORE_DUCATI_CDOFFS, + .dep_bit = OMAP4430_DUCATI_STATDEP_SHIFT, + .wkdep_srcs = ducati_wkup_sleep_deps, + .sleepdep_srcs = ducati_wkup_sleep_deps, .flags = CLKDM_CAN_HWSUP_SWSUP, .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430), }; @@ -201,6 +569,7 @@ static struct clockdomain l3_2_44xx_clkdm = { .prcm_partition = OMAP4430_CM2_PARTITION, .cm_inst = OMAP4430_CM2_CORE_INST, .clkdm_offs = OMAP4430_CM2_CORE_L3_2_CDOFFS, + .dep_bit = OMAP4430_L3_2_STATDEP_SHIFT, .flags = CLKDM_CAN_HWSUP, .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430), }; @@ -211,6 +580,7 @@ static struct clockdomain l3_1_44xx_clkdm = { .prcm_partition = OMAP4430_CM2_PARTITION, .cm_inst = OMAP4430_CM2_CORE_INST, .clkdm_offs = OMAP4430_CM2_CORE_L3_1_CDOFFS, + .dep_bit = OMAP4430_L3_1_STATDEP_SHIFT, .flags = CLKDM_CAN_HWSUP, .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430), }; @@ -221,6 +591,8 @@ static struct clockdomain l3_d2d_44xx_clkdm = { .prcm_partition = OMAP4430_CM2_PARTITION, .cm_inst = OMAP4430_CM2_CORE_INST, .clkdm_offs = OMAP4430_CM2_CORE_D2D_CDOFFS, + .wkdep_srcs = l3_d2d_wkup_sleep_deps, + .sleepdep_srcs = l3_d2d_wkup_sleep_deps, .flags = CLKDM_CAN_FORCE_WAKEUP | CLKDM_CAN_HWSUP, .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430), }; @@ -231,6 +603,8 @@ static struct clockdomain iss_44xx_clkdm = { .prcm_partition = OMAP4430_CM2_PARTITION, .cm_inst = OMAP4430_CM2_CAM_INST, .clkdm_offs = OMAP4430_CM2_CAM_CAM_CDOFFS, + .wkdep_srcs = iss_wkup_sleep_deps, + .sleepdep_srcs = iss_wkup_sleep_deps, .flags = CLKDM_CAN_HWSUP_SWSUP, .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430), }; @@ -241,6 +615,9 @@ static struct clockdomain l3_dss_44xx_clkdm = { .prcm_partition = OMAP4430_CM2_PARTITION, .cm_inst = OMAP4430_CM2_DSS_INST, .clkdm_offs = OMAP4430_CM2_DSS_DSS_CDOFFS, + .dep_bit = OMAP4430_DSS_STATDEP_SHIFT, + .wkdep_srcs = l3_dss_wkup_sleep_deps, + .sleepdep_srcs = l3_dss_wkup_sleep_deps, .flags = CLKDM_CAN_HWSUP_SWSUP, .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430), }; @@ -251,6 +628,7 @@ static struct clockdomain l4_wkup_44xx_clkdm = { .prcm_partition = OMAP4430_PRM_PARTITION, .cm_inst = OMAP4430_PRM_WKUP_CM_INST, .clkdm_offs = OMAP4430_PRM_WKUP_CM_WKUP_CDOFFS, + .dep_bit = OMAP4430_L4WKUP_STATDEP_SHIFT, .flags = CLKDM_CAN_HWSUP, .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430), }; @@ -271,6 +649,8 @@ static struct clockdomain l3_dma_44xx_clkdm = { .prcm_partition = OMAP4430_CM2_PARTITION, .cm_inst = OMAP4430_CM2_CORE_INST, .clkdm_offs = OMAP4430_CM2_CORE_SDMA_CDOFFS, + .wkdep_srcs = l3_dma_wkup_sleep_deps, + .sleepdep_srcs = l3_dma_wkup_sleep_deps, .flags = CLKDM_CAN_FORCE_WAKEUP | CLKDM_CAN_HWSUP, .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430), }; @@ -305,5 +685,5 @@ static struct clockdomain *clockdomains_omap44xx[] __initdata = { void __init omap44xx_clockdomains_init(void) { - clkdm_init(clockdomains_omap44xx, NULL); + clkdm_init(clockdomains_omap44xx, NULL, &omap4_clkdm_operations); } diff --git a/arch/arm/mach-omap2/cm-regbits-24xx.h b/arch/arm/mach-omap2/cm-regbits-24xx.h index d70660e82fe..68629043756 100644 --- a/arch/arm/mach-omap2/cm-regbits-24xx.h +++ b/arch/arm/mach-omap2/cm-regbits-24xx.h @@ -210,8 +210,11 @@ #define OMAP24XX_AUTO_USB_MASK (1 << 0) /* CM_AUTOIDLE3_CORE */ +#define OMAP24XX_AUTO_SDRC_SHIFT 2 #define OMAP24XX_AUTO_SDRC_MASK (1 << 2) +#define OMAP24XX_AUTO_GPMC_SHIFT 1 #define OMAP24XX_AUTO_GPMC_MASK (1 << 1) +#define OMAP24XX_AUTO_SDMA_SHIFT 0 #define OMAP24XX_AUTO_SDMA_MASK (1 << 0) /* CM_AUTOIDLE4_CORE */ diff --git a/arch/arm/mach-omap2/cm2xxx_3xxx.c b/arch/arm/mach-omap2/cm2xxx_3xxx.c index 96954aa4867..9d0dec806e9 100644 --- a/arch/arm/mach-omap2/cm2xxx_3xxx.c +++ b/arch/arm/mach-omap2/cm2xxx_3xxx.c @@ -25,6 +25,14 @@ #include "cm-regbits-24xx.h" #include "cm-regbits-34xx.h" +/* CM_AUTOIDLE_PLL.AUTO_* bit values for DPLLs */ +#define DPLL_AUTOIDLE_DISABLE 0x0 +#define OMAP2XXX_DPLL_AUTOIDLE_LOW_POWER_STOP 0x3 + +/* CM_AUTOIDLE_PLL.AUTO_* bit values for APLLs (OMAP2xxx only) */ +#define OMAP2XXX_APLL_AUTOIDLE_DISABLE 0x0 +#define OMAP2XXX_APLL_AUTOIDLE_LOW_POWER_STOP 0x3 + static const u8 cm_idlest_offs[] = { CM_IDLEST1, CM_IDLEST2, OMAP2430_CM_IDLEST3 }; @@ -125,6 +133,67 @@ void omap3xxx_cm_clkdm_force_wakeup(s16 module, u32 mask) _write_clktrctrl(OMAP34XX_CLKSTCTRL_FORCE_WAKEUP, module, mask); } +/* + * DPLL autoidle control + */ + +static void _omap2xxx_set_dpll_autoidle(u8 m) +{ + u32 v; + + v = omap2_cm_read_mod_reg(PLL_MOD, CM_AUTOIDLE); + v &= ~OMAP24XX_AUTO_DPLL_MASK; + v |= m << OMAP24XX_AUTO_DPLL_SHIFT; + omap2_cm_write_mod_reg(v, PLL_MOD, CM_AUTOIDLE); +} + +void omap2xxx_cm_set_dpll_disable_autoidle(void) +{ + _omap2xxx_set_dpll_autoidle(OMAP2XXX_DPLL_AUTOIDLE_LOW_POWER_STOP); +} + +void omap2xxx_cm_set_dpll_auto_low_power_stop(void) +{ + _omap2xxx_set_dpll_autoidle(DPLL_AUTOIDLE_DISABLE); +} + +/* + * APLL autoidle control + */ + +static void _omap2xxx_set_apll_autoidle(u8 m, u32 mask) +{ + u32 v; + + v = omap2_cm_read_mod_reg(PLL_MOD, CM_AUTOIDLE); + v &= ~mask; + v |= m << __ffs(mask); + omap2_cm_write_mod_reg(v, PLL_MOD, CM_AUTOIDLE); +} + +void omap2xxx_cm_set_apll54_disable_autoidle(void) +{ + _omap2xxx_set_apll_autoidle(OMAP2XXX_APLL_AUTOIDLE_LOW_POWER_STOP, + OMAP24XX_AUTO_54M_MASK); +} + +void omap2xxx_cm_set_apll54_auto_low_power_stop(void) +{ + _omap2xxx_set_apll_autoidle(OMAP2XXX_APLL_AUTOIDLE_DISABLE, + OMAP24XX_AUTO_54M_MASK); +} + +void omap2xxx_cm_set_apll96_disable_autoidle(void) +{ + _omap2xxx_set_apll_autoidle(OMAP2XXX_APLL_AUTOIDLE_LOW_POWER_STOP, + OMAP24XX_AUTO_96M_MASK); +} + +void omap2xxx_cm_set_apll96_auto_low_power_stop(void) +{ + _omap2xxx_set_apll_autoidle(OMAP2XXX_APLL_AUTOIDLE_DISABLE, + OMAP24XX_AUTO_96M_MASK); +} /* * diff --git a/arch/arm/mach-omap2/cm2xxx_3xxx.h b/arch/arm/mach-omap2/cm2xxx_3xxx.h index 5e9ea5bd60b..088bbad73db 100644 --- a/arch/arm/mach-omap2/cm2xxx_3xxx.h +++ b/arch/arm/mach-omap2/cm2xxx_3xxx.h @@ -122,6 +122,14 @@ extern void omap3xxx_cm_clkdm_disable_hwsup(s16 module, u32 mask); extern void omap3xxx_cm_clkdm_force_sleep(s16 module, u32 mask); extern void omap3xxx_cm_clkdm_force_wakeup(s16 module, u32 mask); +extern void omap2xxx_cm_set_dpll_disable_autoidle(void); +extern void omap2xxx_cm_set_dpll_auto_low_power_stop(void); + +extern void omap2xxx_cm_set_apll54_disable_autoidle(void); +extern void omap2xxx_cm_set_apll54_auto_low_power_stop(void); +extern void omap2xxx_cm_set_apll96_disable_autoidle(void); +extern void omap2xxx_cm_set_apll96_auto_low_power_stop(void); + #endif /* CM register bits shared between 24XX and 3430 */ diff --git a/arch/arm/mach-omap2/cm44xx.h b/arch/arm/mach-omap2/cm44xx.h index 48fc3f426fb..0b87ec82b41 100644 --- a/arch/arm/mach-omap2/cm44xx.h +++ b/arch/arm/mach-omap2/cm44xx.h @@ -21,6 +21,7 @@ #include "cm.h" #define OMAP4_CM_CLKSTCTRL 0x0000 +#define OMAP4_CM_STATICDEP 0x0004 /* Function prototypes */ # ifndef __ASSEMBLER__ diff --git a/arch/arm/mach-omap2/cminst44xx.c b/arch/arm/mach-omap2/cminst44xx.c index c04bbbea17a..a482bfa0a95 100644 --- a/arch/arm/mach-omap2/cminst44xx.c +++ b/arch/arm/mach-omap2/cminst44xx.c @@ -73,6 +73,27 @@ u32 omap4_cminst_rmw_inst_reg_bits(u32 mask, u32 bits, u8 part, s16 inst, return v; } +u32 omap4_cminst_set_inst_reg_bits(u32 bits, u8 part, s16 inst, s16 idx) +{ + return omap4_cminst_rmw_inst_reg_bits(bits, bits, part, inst, idx); +} + +u32 omap4_cminst_clear_inst_reg_bits(u32 bits, u8 part, s16 inst, s16 idx) +{ + return omap4_cminst_rmw_inst_reg_bits(bits, 0x0, part, inst, idx); +} + +u32 omap4_cminst_read_inst_reg_bits(u8 part, u16 inst, s16 idx, u32 mask) +{ + u32 v; + + v = omap4_cminst_read_inst_reg(part, inst, idx); + v &= mask; + v >>= __ffs(mask); + + return v; +} + /* * */ diff --git a/arch/arm/mach-omap2/cminst44xx.h b/arch/arm/mach-omap2/cminst44xx.h index a6abd0a8cb8..2b32c181a2e 100644 --- a/arch/arm/mach-omap2/cminst44xx.h +++ b/arch/arm/mach-omap2/cminst44xx.h @@ -25,6 +25,12 @@ extern u32 omap4_cminst_read_inst_reg(u8 part, s16 inst, u16 idx); extern void omap4_cminst_write_inst_reg(u32 val, u8 part, s16 inst, u16 idx); extern u32 omap4_cminst_rmw_inst_reg_bits(u32 mask, u32 bits, u8 part, s16 inst, s16 idx); +extern u32 omap4_cminst_set_inst_reg_bits(u32 bits, u8 part, s16 inst, + s16 idx); +extern u32 omap4_cminst_clear_inst_reg_bits(u32 bits, u8 part, s16 inst, + s16 idx); +extern u32 omap4_cminst_read_inst_reg_bits(u8 part, u16 inst, s16 idx, + u32 mask); extern int omap4_cm_wait_module_ready(void __iomem *clkctrl_reg); diff --git a/arch/arm/mach-omap2/common.c b/arch/arm/mach-omap2/common.c index 778929f7e92..3f20cbb9967 100644 --- a/arch/arm/mach-omap2/common.c +++ b/arch/arm/mach-omap2/common.c @@ -40,7 +40,7 @@ static void __init __omap2_set_globals(struct omap_globals *omap2_globals) #endif -#if defined(CONFIG_ARCH_OMAP2420) +#if defined(CONFIG_SOC_OMAP2420) static struct omap_globals omap242x_globals = { .class = OMAP242X_CLASS, @@ -50,9 +50,6 @@ static struct omap_globals omap242x_globals = { .ctrl = OMAP242X_CTRL_BASE, .prm = OMAP2420_PRM_BASE, .cm = OMAP2420_CM_BASE, - .uart1_phys = OMAP2_UART1_BASE, - .uart2_phys = OMAP2_UART2_BASE, - .uart3_phys = OMAP2_UART3_BASE, }; void __init omap2_set_globals_242x(void) @@ -61,7 +58,7 @@ void __init omap2_set_globals_242x(void) } #endif -#if defined(CONFIG_ARCH_OMAP2430) +#if defined(CONFIG_SOC_OMAP2430) static struct omap_globals omap243x_globals = { .class = OMAP243X_CLASS, @@ -71,9 +68,6 @@ static struct omap_globals omap243x_globals = { .ctrl = OMAP243X_CTRL_BASE, .prm = OMAP2430_PRM_BASE, .cm = OMAP2430_CM_BASE, - .uart1_phys = OMAP2_UART1_BASE, - .uart2_phys = OMAP2_UART2_BASE, - .uart3_phys = OMAP2_UART3_BASE, }; void __init omap2_set_globals_243x(void) @@ -92,10 +86,6 @@ static struct omap_globals omap3_globals = { .ctrl = OMAP343X_CTRL_BASE, .prm = OMAP3430_PRM_BASE, .cm = OMAP3430_CM_BASE, - .uart1_phys = OMAP3_UART1_BASE, - .uart2_phys = OMAP3_UART2_BASE, - .uart3_phys = OMAP3_UART3_BASE, - .uart4_phys = OMAP3_UART4_BASE, /* Only on 3630 */ }; void __init omap2_set_globals_3xxx(void) @@ -108,6 +98,27 @@ void __init omap3_map_io(void) omap2_set_globals_3xxx(); omap34xx_map_common_io(); } + +/* + * Adjust TAP register base such that omap3_check_revision accesses the correct + * TI816X register for checking device ID (it adds 0x204 to tap base while + * TI816X DEVICE ID register is at offset 0x600 from control base). + */ +#define TI816X_TAP_BASE (TI816X_CTRL_BASE + \ + TI816X_CONTROL_DEVICE_ID - 0x204) + +static struct omap_globals ti816x_globals = { + .class = OMAP343X_CLASS, + .tap = OMAP2_L4_IO_ADDRESS(TI816X_TAP_BASE), + .ctrl = TI816X_CTRL_BASE, + .prm = TI816X_PRCM_BASE, + .cm = TI816X_PRCM_BASE, +}; + +void __init omap2_set_globals_ti816x(void) +{ + __omap2_set_globals(&ti816x_globals); +} #endif #if defined(CONFIG_ARCH_OMAP4) @@ -119,10 +130,6 @@ static struct omap_globals omap4_globals = { .prm = OMAP4430_PRM_BASE, .cm = OMAP4430_CM_BASE, .cm2 = OMAP4430_CM2_BASE, - .uart1_phys = OMAP4_UART1_BASE, - .uart2_phys = OMAP4_UART2_BASE, - .uart3_phys = OMAP4_UART3_BASE, - .uart4_phys = OMAP4_UART4_BASE, }; void __init omap2_set_globals_443x(void) diff --git a/arch/arm/mach-omap2/control.h b/arch/arm/mach-omap2/control.h index f0629ae0410..c2804c1c4ef 100644 --- a/arch/arm/mach-omap2/control.h +++ b/arch/arm/mach-omap2/control.h @@ -52,6 +52,9 @@ #define OMAP343X_CONTROL_PADCONFS_WKUP 0xa00 #define OMAP343X_CONTROL_GENERAL_WKUP 0xa60 +/* TI816X spefic control submodules */ +#define TI816X_CONTROL_DEVCONF 0x600 + /* Control register offsets - read/write with omap_ctrl_{read,write}{bwl}() */ #define OMAP2_CONTROL_SYSCONFIG (OMAP2_CONTROL_INTERFACE + 0x10) @@ -241,6 +244,9 @@ #define OMAP3_PADCONF_SAD2D_MSTANDBY 0x250 #define OMAP3_PADCONF_SAD2D_IDLEACK 0x254 +/* TI816X CONTROL_DEVCONF register offsets */ +#define TI816X_CONTROL_DEVICE_ID (TI816X_CONTROL_DEVCONF + 0x000) + /* * REVISIT: This list of registers is not comprehensive - there are more * that should be added. diff --git a/arch/arm/mach-omap2/cpuidle34xx.c b/arch/arm/mach-omap2/cpuidle34xx.c index f7b22a16f38..a44c5230340 100644 --- a/arch/arm/mach-omap2/cpuidle34xx.c +++ b/arch/arm/mach-omap2/cpuidle34xx.c @@ -58,6 +58,7 @@ struct omap3_processor_cx { u32 core_state; u32 threshold; u32 flags; + const char *desc; }; struct omap3_processor_cx omap3_power_states[OMAP3_MAX_STATES]; @@ -99,14 +100,14 @@ static int omap3_idle_bm_check(void) static int _cpuidle_allow_idle(struct powerdomain *pwrdm, struct clockdomain *clkdm) { - omap2_clkdm_allow_idle(clkdm); + clkdm_allow_idle(clkdm); return 0; } static int _cpuidle_deny_idle(struct powerdomain *pwrdm, struct clockdomain *clkdm) { - omap2_clkdm_deny_idle(clkdm); + clkdm_deny_idle(clkdm); return 0; } @@ -365,6 +366,7 @@ void omap_init_power_states(void) omap3_power_states[OMAP3_STATE_C1].mpu_state = PWRDM_POWER_ON; omap3_power_states[OMAP3_STATE_C1].core_state = PWRDM_POWER_ON; omap3_power_states[OMAP3_STATE_C1].flags = CPUIDLE_FLAG_TIME_VALID; + omap3_power_states[OMAP3_STATE_C1].desc = "MPU ON + CORE ON"; /* C2 . MPU WFI + Core inactive */ omap3_power_states[OMAP3_STATE_C2].valid = @@ -380,6 +382,7 @@ void omap_init_power_states(void) omap3_power_states[OMAP3_STATE_C2].core_state = PWRDM_POWER_ON; omap3_power_states[OMAP3_STATE_C2].flags = CPUIDLE_FLAG_TIME_VALID | CPUIDLE_FLAG_CHECK_BM; + omap3_power_states[OMAP3_STATE_C2].desc = "MPU ON + CORE ON"; /* C3 . MPU CSWR + Core inactive */ omap3_power_states[OMAP3_STATE_C3].valid = @@ -395,6 +398,7 @@ void omap_init_power_states(void) omap3_power_states[OMAP3_STATE_C3].core_state = PWRDM_POWER_ON; omap3_power_states[OMAP3_STATE_C3].flags = CPUIDLE_FLAG_TIME_VALID | CPUIDLE_FLAG_CHECK_BM; + omap3_power_states[OMAP3_STATE_C3].desc = "MPU RET + CORE ON"; /* C4 . MPU OFF + Core inactive */ omap3_power_states[OMAP3_STATE_C4].valid = @@ -410,6 +414,7 @@ void omap_init_power_states(void) omap3_power_states[OMAP3_STATE_C4].core_state = PWRDM_POWER_ON; omap3_power_states[OMAP3_STATE_C4].flags = CPUIDLE_FLAG_TIME_VALID | CPUIDLE_FLAG_CHECK_BM; + omap3_power_states[OMAP3_STATE_C4].desc = "MPU OFF + CORE ON"; /* C5 . MPU CSWR + Core CSWR*/ omap3_power_states[OMAP3_STATE_C5].valid = @@ -425,6 +430,7 @@ void omap_init_power_states(void) omap3_power_states[OMAP3_STATE_C5].core_state = PWRDM_POWER_RET; omap3_power_states[OMAP3_STATE_C5].flags = CPUIDLE_FLAG_TIME_VALID | CPUIDLE_FLAG_CHECK_BM; + omap3_power_states[OMAP3_STATE_C5].desc = "MPU RET + CORE RET"; /* C6 . MPU OFF + Core CSWR */ omap3_power_states[OMAP3_STATE_C6].valid = @@ -440,6 +446,7 @@ void omap_init_power_states(void) omap3_power_states[OMAP3_STATE_C6].core_state = PWRDM_POWER_RET; omap3_power_states[OMAP3_STATE_C6].flags = CPUIDLE_FLAG_TIME_VALID | CPUIDLE_FLAG_CHECK_BM; + omap3_power_states[OMAP3_STATE_C6].desc = "MPU OFF + CORE RET"; /* C7 . MPU OFF + Core OFF */ omap3_power_states[OMAP3_STATE_C7].valid = @@ -455,6 +462,7 @@ void omap_init_power_states(void) omap3_power_states[OMAP3_STATE_C7].core_state = PWRDM_POWER_OFF; omap3_power_states[OMAP3_STATE_C7].flags = CPUIDLE_FLAG_TIME_VALID | CPUIDLE_FLAG_CHECK_BM; + omap3_power_states[OMAP3_STATE_C7].desc = "MPU OFF + CORE OFF"; /* * Erratum i583: implementation for ES rev < Es1.2 on 3630. We cannot @@ -464,7 +472,7 @@ void omap_init_power_states(void) if (IS_PM34XX_ERRATUM(PM_SDRC_WAKEUP_ERRATUM_i583)) { omap3_power_states[OMAP3_STATE_C7].valid = 0; cpuidle_params_table[OMAP3_STATE_C7].valid = 0; - WARN_ONCE(1, "%s: core off state C7 disabled due to i583\n", + pr_warn("%s: core off state C7 disabled due to i583\n", __func__); } } @@ -512,6 +520,7 @@ int __init omap3_idle_init(void) if (cx->type == OMAP3_STATE_C1) dev->safe_state = state; sprintf(state->name, "C%d", count+1); + strncpy(state->desc, cx->desc, CPUIDLE_DESC_LEN); count++; } diff --git a/arch/arm/mach-omap2/devices.c b/arch/arm/mach-omap2/devices.c index 2c9c912f2c4..0d2d6a9c303 100644 --- a/arch/arm/mach-omap2/devices.c +++ b/arch/arm/mach-omap2/devices.c @@ -15,6 +15,7 @@ #include <linux/io.h> #include <linux/clk.h> #include <linux/err.h> +#include <linux/slab.h> #include <mach/hardware.h> #include <mach/irqs.h> @@ -30,10 +31,75 @@ #include <plat/dma.h> #include <plat/omap_hwmod.h> #include <plat/omap_device.h> +#include <plat/omap4-keypad.h> #include "mux.h" #include "control.h" +#define L3_MODULES_MAX_LEN 12 +#define L3_MODULES 3 + +static int __init omap3_l3_init(void) +{ + int l; + struct omap_hwmod *oh; + struct omap_device *od; + char oh_name[L3_MODULES_MAX_LEN]; + + /* + * To avoid code running on other OMAPs in + * multi-omap builds + */ + if (!(cpu_is_omap34xx())) + return -ENODEV; + + l = snprintf(oh_name, L3_MODULES_MAX_LEN, "l3_main"); + + oh = omap_hwmod_lookup(oh_name); + + if (!oh) + pr_err("could not look up %s\n", oh_name); + + od = omap_device_build("omap_l3_smx", 0, oh, NULL, 0, + NULL, 0, 0); + + WARN(IS_ERR(od), "could not build omap_device for %s\n", oh_name); + + return PTR_ERR(od); +} +postcore_initcall(omap3_l3_init); + +static int __init omap4_l3_init(void) +{ + int l, i; + struct omap_hwmod *oh[3]; + struct omap_device *od; + char oh_name[L3_MODULES_MAX_LEN]; + + /* + * To avoid code running on other OMAPs in + * multi-omap builds + */ + if (!(cpu_is_omap44xx())) + return -ENODEV; + + for (i = 0; i < L3_MODULES; i++) { + l = snprintf(oh_name, L3_MODULES_MAX_LEN, "l3_main_%d", i+1); + + oh[i] = omap_hwmod_lookup(oh_name); + if (!(oh[i])) + pr_err("could not look up %s\n", oh_name); + } + + od = omap_device_build_ss("omap_l3_noc", 0, oh, 3, NULL, + 0, NULL, 0, 0); + + WARN(IS_ERR(od), "could not build omap_device for %s\n", oh_name); + + return PTR_ERR(od); +} +postcore_initcall(omap4_l3_init); + #if defined(CONFIG_VIDEO_OMAP2) || defined(CONFIG_VIDEO_OMAP2_MODULE) static struct resource cam_resources[] = { @@ -141,96 +207,70 @@ static inline void omap_init_camera(void) } #endif -#if defined(CONFIG_OMAP_MBOX_FWK) || defined(CONFIG_OMAP_MBOX_FWK_MODULE) - -#define MBOX_REG_SIZE 0x120 - -#ifdef CONFIG_ARCH_OMAP2 -static struct resource omap2_mbox_resources[] = { - { - .start = OMAP24XX_MAILBOX_BASE, - .end = OMAP24XX_MAILBOX_BASE + MBOX_REG_SIZE - 1, - .flags = IORESOURCE_MEM, - }, - { - .start = INT_24XX_MAIL_U0_MPU, - .flags = IORESOURCE_IRQ, - .name = "dsp", - }, +struct omap_device_pm_latency omap_keyboard_latency[] = { { - .start = INT_24XX_MAIL_U3_MPU, - .flags = IORESOURCE_IRQ, - .name = "iva", + .deactivate_func = omap_device_idle_hwmods, + .activate_func = omap_device_enable_hwmods, + .flags = OMAP_DEVICE_LATENCY_AUTO_ADJUST, }, }; -static int omap2_mbox_resources_sz = ARRAY_SIZE(omap2_mbox_resources); -#else -#define omap2_mbox_resources NULL -#define omap2_mbox_resources_sz 0 -#endif -#ifdef CONFIG_ARCH_OMAP3 -static struct resource omap3_mbox_resources[] = { - { - .start = OMAP34XX_MAILBOX_BASE, - .end = OMAP34XX_MAILBOX_BASE + MBOX_REG_SIZE - 1, - .flags = IORESOURCE_MEM, - }, - { - .start = INT_24XX_MAIL_U0_MPU, - .flags = IORESOURCE_IRQ, - .name = "dsp", - }, -}; -static int omap3_mbox_resources_sz = ARRAY_SIZE(omap3_mbox_resources); -#else -#define omap3_mbox_resources NULL -#define omap3_mbox_resources_sz 0 -#endif +int __init omap4_keyboard_init(struct omap4_keypad_platform_data + *sdp4430_keypad_data) +{ + struct omap_device *od; + struct omap_hwmod *oh; + struct omap4_keypad_platform_data *keypad_data; + unsigned int id = -1; + char *oh_name = "kbd"; + char *name = "omap4-keypad"; -#ifdef CONFIG_ARCH_OMAP4 + oh = omap_hwmod_lookup(oh_name); + if (!oh) { + pr_err("Could not look up %s\n", oh_name); + return -ENODEV; + } -#define OMAP4_MBOX_REG_SIZE 0x130 -static struct resource omap4_mbox_resources[] = { - { - .start = OMAP44XX_MAILBOX_BASE, - .end = OMAP44XX_MAILBOX_BASE + - OMAP4_MBOX_REG_SIZE - 1, - .flags = IORESOURCE_MEM, - }, - { - .start = OMAP44XX_IRQ_MAIL_U0, - .flags = IORESOURCE_IRQ, - .name = "mbox", - }, -}; -static int omap4_mbox_resources_sz = ARRAY_SIZE(omap4_mbox_resources); -#else -#define omap4_mbox_resources NULL -#define omap4_mbox_resources_sz 0 -#endif + keypad_data = sdp4430_keypad_data; -static struct platform_device mbox_device = { - .name = "omap-mailbox", - .id = -1, + od = omap_device_build(name, id, oh, keypad_data, + sizeof(struct omap4_keypad_platform_data), + omap_keyboard_latency, + ARRAY_SIZE(omap_keyboard_latency), 0); + + if (IS_ERR(od)) { + WARN(1, "Cant build omap_device for %s:%s.\n", + name, oh->name); + return PTR_ERR(od); + } + + return 0; +} + +#if defined(CONFIG_OMAP_MBOX_FWK) || defined(CONFIG_OMAP_MBOX_FWK_MODULE) +static struct omap_device_pm_latency mbox_latencies[] = { + [0] = { + .activate_func = omap_device_enable_hwmods, + .deactivate_func = omap_device_idle_hwmods, + .flags = OMAP_DEVICE_LATENCY_AUTO_ADJUST, + }, }; static inline void omap_init_mbox(void) { - if (cpu_is_omap24xx()) { - mbox_device.resource = omap2_mbox_resources; - mbox_device.num_resources = omap2_mbox_resources_sz; - } else if (cpu_is_omap34xx()) { - mbox_device.resource = omap3_mbox_resources; - mbox_device.num_resources = omap3_mbox_resources_sz; - } else if (cpu_is_omap44xx()) { - mbox_device.resource = omap4_mbox_resources; - mbox_device.num_resources = omap4_mbox_resources_sz; - } else { - pr_err("%s: platform not supported\n", __func__); + struct omap_hwmod *oh; + struct omap_device *od; + + oh = omap_hwmod_lookup("mailbox"); + if (!oh) { + pr_err("%s: unable to find hwmod\n", __func__); return; } - platform_device_register(&mbox_device); + + od = omap_device_build("omap-mailbox", -1, oh, NULL, 0, + mbox_latencies, ARRAY_SIZE(mbox_latencies), 0); + WARN(IS_ERR(od), "%s: could not build device, err %ld\n", + __func__, PTR_ERR(od)); } #else static inline void omap_init_mbox(void) { } @@ -279,163 +319,55 @@ static inline void omap_init_audio(void) {} #include <plat/mcspi.h> -#define OMAP2_MCSPI1_BASE 0x48098000 -#define OMAP2_MCSPI2_BASE 0x4809a000 -#define OMAP2_MCSPI3_BASE 0x480b8000 -#define OMAP2_MCSPI4_BASE 0x480ba000 - -#define OMAP4_MCSPI1_BASE 0x48098100 -#define OMAP4_MCSPI2_BASE 0x4809a100 -#define OMAP4_MCSPI3_BASE 0x480b8100 -#define OMAP4_MCSPI4_BASE 0x480ba100 - -static struct omap2_mcspi_platform_config omap2_mcspi1_config = { - .num_cs = 4, -}; - -static struct resource omap2_mcspi1_resources[] = { - { - .start = OMAP2_MCSPI1_BASE, - .end = OMAP2_MCSPI1_BASE + 0xff, - .flags = IORESOURCE_MEM, - }, -}; - -static struct platform_device omap2_mcspi1 = { - .name = "omap2_mcspi", - .id = 1, - .num_resources = ARRAY_SIZE(omap2_mcspi1_resources), - .resource = omap2_mcspi1_resources, - .dev = { - .platform_data = &omap2_mcspi1_config, - }, -}; - -static struct omap2_mcspi_platform_config omap2_mcspi2_config = { - .num_cs = 2, -}; - -static struct resource omap2_mcspi2_resources[] = { - { - .start = OMAP2_MCSPI2_BASE, - .end = OMAP2_MCSPI2_BASE + 0xff, - .flags = IORESOURCE_MEM, - }, -}; - -static struct platform_device omap2_mcspi2 = { - .name = "omap2_mcspi", - .id = 2, - .num_resources = ARRAY_SIZE(omap2_mcspi2_resources), - .resource = omap2_mcspi2_resources, - .dev = { - .platform_data = &omap2_mcspi2_config, - }, -}; - -#if defined(CONFIG_ARCH_OMAP2430) || defined(CONFIG_ARCH_OMAP3) || \ - defined(CONFIG_ARCH_OMAP4) -static struct omap2_mcspi_platform_config omap2_mcspi3_config = { - .num_cs = 2, -}; - -static struct resource omap2_mcspi3_resources[] = { - { - .start = OMAP2_MCSPI3_BASE, - .end = OMAP2_MCSPI3_BASE + 0xff, - .flags = IORESOURCE_MEM, - }, -}; - -static struct platform_device omap2_mcspi3 = { - .name = "omap2_mcspi", - .id = 3, - .num_resources = ARRAY_SIZE(omap2_mcspi3_resources), - .resource = omap2_mcspi3_resources, - .dev = { - .platform_data = &omap2_mcspi3_config, - }, -}; -#endif - -#if defined(CONFIG_ARCH_OMAP3) || defined(CONFIG_ARCH_OMAP4) -static struct omap2_mcspi_platform_config omap2_mcspi4_config = { - .num_cs = 1, -}; - -static struct resource omap2_mcspi4_resources[] = { - { - .start = OMAP2_MCSPI4_BASE, - .end = OMAP2_MCSPI4_BASE + 0xff, - .flags = IORESOURCE_MEM, - }, -}; - -static struct platform_device omap2_mcspi4 = { - .name = "omap2_mcspi", - .id = 4, - .num_resources = ARRAY_SIZE(omap2_mcspi4_resources), - .resource = omap2_mcspi4_resources, - .dev = { - .platform_data = &omap2_mcspi4_config, +struct omap_device_pm_latency omap_mcspi_latency[] = { + [0] = { + .deactivate_func = omap_device_idle_hwmods, + .activate_func = omap_device_enable_hwmods, + .flags = OMAP_DEVICE_LATENCY_AUTO_ADJUST, }, }; -#endif -#ifdef CONFIG_ARCH_OMAP4 -static inline void omap4_mcspi_fixup(void) +static int omap_mcspi_init(struct omap_hwmod *oh, void *unused) { - omap2_mcspi1_resources[0].start = OMAP4_MCSPI1_BASE; - omap2_mcspi1_resources[0].end = OMAP4_MCSPI1_BASE + 0xff; - omap2_mcspi2_resources[0].start = OMAP4_MCSPI2_BASE; - omap2_mcspi2_resources[0].end = OMAP4_MCSPI2_BASE + 0xff; - omap2_mcspi3_resources[0].start = OMAP4_MCSPI3_BASE; - omap2_mcspi3_resources[0].end = OMAP4_MCSPI3_BASE + 0xff; - omap2_mcspi4_resources[0].start = OMAP4_MCSPI4_BASE; - omap2_mcspi4_resources[0].end = OMAP4_MCSPI4_BASE + 0xff; -} -#else -static inline void omap4_mcspi_fixup(void) -{ -} -#endif + struct omap_device *od; + char *name = "omap2_mcspi"; + struct omap2_mcspi_platform_config *pdata; + static int spi_num; + struct omap2_mcspi_dev_attr *mcspi_attrib = oh->dev_attr; + + pdata = kzalloc(sizeof(*pdata), GFP_KERNEL); + if (!pdata) { + pr_err("Memory allocation for McSPI device failed\n"); + return -ENOMEM; + } -#if defined(CONFIG_ARCH_OMAP2430) || defined(CONFIG_ARCH_OMAP3) || \ - defined(CONFIG_ARCH_OMAP4) -static inline void omap2_mcspi3_init(void) -{ - platform_device_register(&omap2_mcspi3); -} -#else -static inline void omap2_mcspi3_init(void) -{ -} -#endif + pdata->num_cs = mcspi_attrib->num_chipselect; + switch (oh->class->rev) { + case OMAP2_MCSPI_REV: + case OMAP3_MCSPI_REV: + pdata->regs_offset = 0; + break; + case OMAP4_MCSPI_REV: + pdata->regs_offset = OMAP4_MCSPI_REG_OFFSET; + break; + default: + pr_err("Invalid McSPI Revision value\n"); + return -EINVAL; + } -#if defined(CONFIG_ARCH_OMAP3) || defined(CONFIG_ARCH_OMAP4) -static inline void omap2_mcspi4_init(void) -{ - platform_device_register(&omap2_mcspi4); -} -#else -static inline void omap2_mcspi4_init(void) -{ + spi_num++; + od = omap_device_build(name, spi_num, oh, pdata, + sizeof(*pdata), omap_mcspi_latency, + ARRAY_SIZE(omap_mcspi_latency), 0); + WARN(IS_ERR(od), "Cant build omap_device for %s:%s\n", + name, oh->name); + kfree(pdata); + return 0; } -#endif static void omap_init_mcspi(void) { - if (cpu_is_omap44xx()) - omap4_mcspi_fixup(); - - platform_device_register(&omap2_mcspi1); - platform_device_register(&omap2_mcspi2); - - if (cpu_is_omap2430() || cpu_is_omap343x() || cpu_is_omap44xx()) - omap2_mcspi3_init(); - - if (cpu_is_omap343x() || cpu_is_omap44xx()) - omap2_mcspi4_init(); + omap_hwmod_for_each_by_class("mcspi", omap_mcspi_init, NULL); } #else @@ -610,117 +542,10 @@ static inline void omap_init_aes(void) { } /*-------------------------------------------------------------------------*/ -#if defined(CONFIG_ARCH_OMAP3) || defined(CONFIG_ARCH_OMAP4) - -#define MMCHS_SYSCONFIG 0x0010 -#define MMCHS_SYSCONFIG_SWRESET (1 << 1) -#define MMCHS_SYSSTATUS 0x0014 -#define MMCHS_SYSSTATUS_RESETDONE (1 << 0) - -static struct platform_device dummy_pdev = { - .dev = { - .bus = &platform_bus_type, - }, -}; - -/** - * omap_hsmmc_reset() - Full reset of each HS-MMC controller - * - * Ensure that each MMC controller is fully reset. Controllers - * left in an unknown state (by bootloader) may prevent retention - * or OFF-mode. This is especially important in cases where the - * MMC driver is not enabled, _or_ built as a module. - * - * In order for reset to work, interface, functional and debounce - * clocks must be enabled. The debounce clock comes from func_32k_clk - * and is not under SW control, so we only enable i- and f-clocks. - **/ -static void __init omap_hsmmc_reset(void) -{ - u32 i, nr_controllers; - struct clk *iclk, *fclk; - - if (cpu_is_omap242x()) - return; - - nr_controllers = cpu_is_omap44xx() ? OMAP44XX_NR_MMC : - (cpu_is_omap34xx() ? OMAP34XX_NR_MMC : OMAP24XX_NR_MMC); +#if defined(CONFIG_MMC_OMAP) || defined(CONFIG_MMC_OMAP_MODULE) - for (i = 0; i < nr_controllers; i++) { - u32 v, base = 0; - struct device *dev = &dummy_pdev.dev; - - switch (i) { - case 0: - base = OMAP2_MMC1_BASE; - break; - case 1: - base = OMAP2_MMC2_BASE; - break; - case 2: - base = OMAP3_MMC3_BASE; - break; - case 3: - if (!cpu_is_omap44xx()) - return; - base = OMAP4_MMC4_BASE; - break; - case 4: - if (!cpu_is_omap44xx()) - return; - base = OMAP4_MMC5_BASE; - break; - } - - if (cpu_is_omap44xx()) - base += OMAP4_MMC_REG_OFFSET; - - dummy_pdev.id = i; - dev_set_name(&dummy_pdev.dev, "mmci-omap-hs.%d", i); - iclk = clk_get(dev, "ick"); - if (IS_ERR(iclk)) - goto err1; - if (clk_enable(iclk)) - goto err2; - - fclk = clk_get(dev, "fck"); - if (IS_ERR(fclk)) - goto err3; - if (clk_enable(fclk)) - goto err4; - - omap_writel(MMCHS_SYSCONFIG_SWRESET, base + MMCHS_SYSCONFIG); - v = omap_readl(base + MMCHS_SYSSTATUS); - while (!(omap_readl(base + MMCHS_SYSSTATUS) & - MMCHS_SYSSTATUS_RESETDONE)) - cpu_relax(); - - clk_disable(fclk); - clk_put(fclk); - clk_disable(iclk); - clk_put(iclk); - } - return; - -err4: - clk_put(fclk); -err3: - clk_disable(iclk); -err2: - clk_put(iclk); -err1: - printk(KERN_WARNING "%s: Unable to enable clocks for MMC%d, " - "cannot reset.\n", __func__, i); -} -#else -static inline void omap_hsmmc_reset(void) {} -#endif - -#if defined(CONFIG_MMC_OMAP) || defined(CONFIG_MMC_OMAP_MODULE) || \ - defined(CONFIG_MMC_OMAP_HS) || defined(CONFIG_MMC_OMAP_HS_MODULE) - -static inline void omap2_mmc_mux(struct omap_mmc_platform_data *mmc_controller, - int controller_nr) +static inline void omap242x_mmc_mux(struct omap_mmc_platform_data + *mmc_controller) { if ((mmc_controller->slots[0].switch_pin > 0) && \ (mmc_controller->slots[0].switch_pin < OMAP_MAX_GPIO_LINES)) @@ -731,163 +556,44 @@ static inline void omap2_mmc_mux(struct omap_mmc_platform_data *mmc_controller, omap_mux_init_gpio(mmc_controller->slots[0].gpio_wp, OMAP_PIN_INPUT_PULLUP); - if (cpu_is_omap2420() && controller_nr == 0) { - omap_mux_init_signal("sdmmc_cmd", 0); - omap_mux_init_signal("sdmmc_clki", 0); - omap_mux_init_signal("sdmmc_clko", 0); - omap_mux_init_signal("sdmmc_dat0", 0); - omap_mux_init_signal("sdmmc_dat_dir0", 0); - omap_mux_init_signal("sdmmc_cmd_dir", 0); - if (mmc_controller->slots[0].caps & MMC_CAP_4_BIT_DATA) { - omap_mux_init_signal("sdmmc_dat1", 0); - omap_mux_init_signal("sdmmc_dat2", 0); - omap_mux_init_signal("sdmmc_dat3", 0); - omap_mux_init_signal("sdmmc_dat_dir1", 0); - omap_mux_init_signal("sdmmc_dat_dir2", 0); - omap_mux_init_signal("sdmmc_dat_dir3", 0); - } - - /* - * Use internal loop-back in MMC/SDIO Module Input Clock - * selection - */ - if (mmc_controller->slots[0].internal_clock) { - u32 v = omap_ctrl_readl(OMAP2_CONTROL_DEVCONF0); - v |= (1 << 24); - omap_ctrl_writel(v, OMAP2_CONTROL_DEVCONF0); - } + omap_mux_init_signal("sdmmc_cmd", 0); + omap_mux_init_signal("sdmmc_clki", 0); + omap_mux_init_signal("sdmmc_clko", 0); + omap_mux_init_signal("sdmmc_dat0", 0); + omap_mux_init_signal("sdmmc_dat_dir0", 0); + omap_mux_init_signal("sdmmc_cmd_dir", 0); + if (mmc_controller->slots[0].caps & MMC_CAP_4_BIT_DATA) { + omap_mux_init_signal("sdmmc_dat1", 0); + omap_mux_init_signal("sdmmc_dat2", 0); + omap_mux_init_signal("sdmmc_dat3", 0); + omap_mux_init_signal("sdmmc_dat_dir1", 0); + omap_mux_init_signal("sdmmc_dat_dir2", 0); + omap_mux_init_signal("sdmmc_dat_dir3", 0); } - if (cpu_is_omap34xx()) { - if (controller_nr == 0) { - omap_mux_init_signal("sdmmc1_clk", - OMAP_PIN_INPUT_PULLUP); - omap_mux_init_signal("sdmmc1_cmd", - OMAP_PIN_INPUT_PULLUP); - omap_mux_init_signal("sdmmc1_dat0", - OMAP_PIN_INPUT_PULLUP); - if (mmc_controller->slots[0].caps & - (MMC_CAP_4_BIT_DATA | MMC_CAP_8_BIT_DATA)) { - omap_mux_init_signal("sdmmc1_dat1", - OMAP_PIN_INPUT_PULLUP); - omap_mux_init_signal("sdmmc1_dat2", - OMAP_PIN_INPUT_PULLUP); - omap_mux_init_signal("sdmmc1_dat3", - OMAP_PIN_INPUT_PULLUP); - } - if (mmc_controller->slots[0].caps & - MMC_CAP_8_BIT_DATA) { - omap_mux_init_signal("sdmmc1_dat4", - OMAP_PIN_INPUT_PULLUP); - omap_mux_init_signal("sdmmc1_dat5", - OMAP_PIN_INPUT_PULLUP); - omap_mux_init_signal("sdmmc1_dat6", - OMAP_PIN_INPUT_PULLUP); - omap_mux_init_signal("sdmmc1_dat7", - OMAP_PIN_INPUT_PULLUP); - } - } - if (controller_nr == 1) { - /* MMC2 */ - omap_mux_init_signal("sdmmc2_clk", - OMAP_PIN_INPUT_PULLUP); - omap_mux_init_signal("sdmmc2_cmd", - OMAP_PIN_INPUT_PULLUP); - omap_mux_init_signal("sdmmc2_dat0", - OMAP_PIN_INPUT_PULLUP); - - /* - * For 8 wire configurations, Lines DAT4, 5, 6 and 7 need to be muxed - * in the board-*.c files - */ - if (mmc_controller->slots[0].caps & - (MMC_CAP_4_BIT_DATA | MMC_CAP_8_BIT_DATA)) { - omap_mux_init_signal("sdmmc2_dat1", - OMAP_PIN_INPUT_PULLUP); - omap_mux_init_signal("sdmmc2_dat2", - OMAP_PIN_INPUT_PULLUP); - omap_mux_init_signal("sdmmc2_dat3", - OMAP_PIN_INPUT_PULLUP); - } - if (mmc_controller->slots[0].caps & - MMC_CAP_8_BIT_DATA) { - omap_mux_init_signal("sdmmc2_dat4.sdmmc2_dat4", - OMAP_PIN_INPUT_PULLUP); - omap_mux_init_signal("sdmmc2_dat5.sdmmc2_dat5", - OMAP_PIN_INPUT_PULLUP); - omap_mux_init_signal("sdmmc2_dat6.sdmmc2_dat6", - OMAP_PIN_INPUT_PULLUP); - omap_mux_init_signal("sdmmc2_dat7.sdmmc2_dat7", - OMAP_PIN_INPUT_PULLUP); - } - } - - /* - * For MMC3 the pins need to be muxed in the board-*.c files - */ + /* + * Use internal loop-back in MMC/SDIO Module Input Clock + * selection + */ + if (mmc_controller->slots[0].internal_clock) { + u32 v = omap_ctrl_readl(OMAP2_CONTROL_DEVCONF0); + v |= (1 << 24); + omap_ctrl_writel(v, OMAP2_CONTROL_DEVCONF0); } } -void __init omap2_init_mmc(struct omap_mmc_platform_data **mmc_data, - int nr_controllers) +void __init omap242x_init_mmc(struct omap_mmc_platform_data **mmc_data) { - int i; - char *name; + char *name = "mmci-omap"; - for (i = 0; i < nr_controllers; i++) { - unsigned long base, size; - unsigned int irq = 0; - - if (!mmc_data[i]) - continue; - - omap2_mmc_mux(mmc_data[i], i); + if (!mmc_data[0]) { + pr_err("%s fails: Incomplete platform data\n", __func__); + return; + } - switch (i) { - case 0: - base = OMAP2_MMC1_BASE; - irq = INT_24XX_MMC_IRQ; - break; - case 1: - base = OMAP2_MMC2_BASE; - irq = INT_24XX_MMC2_IRQ; - break; - case 2: - if (!cpu_is_omap44xx() && !cpu_is_omap34xx()) - return; - base = OMAP3_MMC3_BASE; - irq = INT_34XX_MMC3_IRQ; - break; - case 3: - if (!cpu_is_omap44xx()) - return; - base = OMAP4_MMC4_BASE; - irq = OMAP44XX_IRQ_MMC4; - break; - case 4: - if (!cpu_is_omap44xx()) - return; - base = OMAP4_MMC5_BASE; - irq = OMAP44XX_IRQ_MMC5; - break; - default: - continue; - } - - if (cpu_is_omap2420()) { - size = OMAP2420_MMC_SIZE; - name = "mmci-omap"; - } else if (cpu_is_omap44xx()) { - if (i < 3) - irq += OMAP44XX_IRQ_GIC_START; - size = OMAP4_HSMMC_SIZE; - name = "mmci-omap-hs"; - } else { - size = OMAP3_HSMMC_SIZE; - name = "mmci-omap-hs"; - } - omap_mmc_add(name, i, base, size, irq, mmc_data[i]); - }; + omap242x_mmc_mux(mmc_data[0]); + omap_mmc_add(name, 0, OMAP2_MMC1_BASE, OMAP2420_MMC_SIZE, + INT_24XX_MMC_IRQ, mmc_data[0]); } #endif @@ -895,7 +601,7 @@ void __init omap2_init_mmc(struct omap_mmc_platform_data **mmc_data, /*-------------------------------------------------------------------------*/ #if defined(CONFIG_HDQ_MASTER_OMAP) || defined(CONFIG_HDQ_MASTER_OMAP_MODULE) -#if defined(CONFIG_ARCH_OMAP2430) || defined(CONFIG_ARCH_OMAP3430) +#if defined(CONFIG_SOC_OMAP2430) || defined(CONFIG_SOC_OMAP3430) #define OMAP_HDQ_BASE 0x480B2000 #endif static struct resource omap_hdq_resources[] = { @@ -961,7 +667,6 @@ static int __init omap2_init_devices(void) * please keep these calls, and their implementations above, * in alphabetical order so they're easier to sort through. */ - omap_hsmmc_reset(); omap_init_audio(); omap_init_camera(); omap_init_mbox(); diff --git a/arch/arm/mach-omap2/display.c b/arch/arm/mach-omap2/display.c new file mode 100644 index 00000000000..b18db84b034 --- /dev/null +++ b/arch/arm/mach-omap2/display.c @@ -0,0 +1,45 @@ +/* + * OMAP2plus display device setup / initialization. + * + * Copyright (C) 2010 Texas Instruments Incorporated - http://www.ti.com/ + * Senthilvadivu Guruswamy + * Sumit Semwal + * + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License version 2 as + * published by the Free Software Foundation. + * + * This program is distributed "as is" WITHOUT ANY WARRANTY of any + * kind, whether express or implied; without even the implied warranty + * of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + */ + +#include <linux/kernel.h> +#include <linux/init.h> +#include <linux/platform_device.h> +#include <linux/io.h> +#include <linux/clk.h> +#include <linux/err.h> + +#include <plat/display.h> + +static struct platform_device omap_display_device = { + .name = "omapdss", + .id = -1, + .dev = { + .platform_data = NULL, + }, +}; + +int __init omap_display_init(struct omap_dss_board_info *board_data) +{ + int r = 0; + omap_display_device.dev.platform_data = board_data; + + r = platform_device_register(&omap_display_device); + if (r < 0) + printk(KERN_ERR "Unable to register OMAP-Display device\n"); + + return r; +} diff --git a/arch/arm/mach-omap2/dpll44xx.c b/arch/arm/mach-omap2/dpll44xx.c new file mode 100644 index 00000000000..4e4da6160d0 --- /dev/null +++ b/arch/arm/mach-omap2/dpll44xx.c @@ -0,0 +1,84 @@ +/* + * OMAP4-specific DPLL control functions + * + * Copyright (C) 2011 Texas Instruments, Inc. + * Rajendra Nayak + * + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License version 2 as + * published by the Free Software Foundation. + */ + +#include <linux/kernel.h> +#include <linux/errno.h> +#include <linux/clk.h> +#include <linux/io.h> +#include <linux/bitops.h> + +#include <plat/cpu.h> +#include <plat/clock.h> + +#include "clock.h" +#include "cm-regbits-44xx.h" + +/* Supported only on OMAP4 */ +int omap4_dpllmx_gatectrl_read(struct clk *clk) +{ + u32 v; + u32 mask; + + if (!clk || !clk->clksel_reg || !cpu_is_omap44xx()) + return -EINVAL; + + mask = clk->flags & CLOCK_CLKOUTX2 ? + OMAP4430_DPLL_CLKOUTX2_GATE_CTRL_MASK : + OMAP4430_DPLL_CLKOUT_GATE_CTRL_MASK; + + v = __raw_readl(clk->clksel_reg); + v &= mask; + v >>= __ffs(mask); + + return v; +} + +void omap4_dpllmx_allow_gatectrl(struct clk *clk) +{ + u32 v; + u32 mask; + + if (!clk || !clk->clksel_reg || !cpu_is_omap44xx()) + return; + + mask = clk->flags & CLOCK_CLKOUTX2 ? + OMAP4430_DPLL_CLKOUTX2_GATE_CTRL_MASK : + OMAP4430_DPLL_CLKOUT_GATE_CTRL_MASK; + + v = __raw_readl(clk->clksel_reg); + /* Clear the bit to allow gatectrl */ + v &= ~mask; + __raw_writel(v, clk->clksel_reg); +} + +void omap4_dpllmx_deny_gatectrl(struct clk *clk) +{ + u32 v; + u32 mask; + + if (!clk || !clk->clksel_reg || !cpu_is_omap44xx()) + return; + + mask = clk->flags & CLOCK_CLKOUTX2 ? + OMAP4430_DPLL_CLKOUTX2_GATE_CTRL_MASK : + OMAP4430_DPLL_CLKOUT_GATE_CTRL_MASK; + + v = __raw_readl(clk->clksel_reg); + /* Set the bit to deny gatectrl */ + v |= mask; + __raw_writel(v, clk->clksel_reg); +} + +const struct clkops clkops_omap4_dpllmx_ops = { + .allow_idle = omap4_dpllmx_allow_gatectrl, + .deny_idle = omap4_dpllmx_deny_gatectrl, +}; + diff --git a/arch/arm/mach-omap2/gpmc-nand.c b/arch/arm/mach-omap2/gpmc-nand.c index 2bb29c16070..c1791d08ae5 100644 --- a/arch/arm/mach-omap2/gpmc-nand.c +++ b/arch/arm/mach-omap2/gpmc-nand.c @@ -12,6 +12,7 @@ #include <linux/kernel.h> #include <linux/platform_device.h> #include <linux/io.h> +#include <linux/mtd/nand.h> #include <asm/mach/flash.h> @@ -69,8 +70,10 @@ static int omap2_nand_gpmc_retime(void) t.wr_cycle = gpmc_round_ns_to_ticks(gpmc_nand_data->gpmc_t->wr_cycle); /* Configure GPMC */ - gpmc_cs_configure(gpmc_nand_data->cs, - GPMC_CONFIG_DEV_SIZE, gpmc_nand_data->devsize); + if (gpmc_nand_data->devsize == NAND_BUSWIDTH_16) + gpmc_cs_configure(gpmc_nand_data->cs, GPMC_CONFIG_DEV_SIZE, 1); + else + gpmc_cs_configure(gpmc_nand_data->cs, GPMC_CONFIG_DEV_SIZE, 0); gpmc_cs_configure(gpmc_nand_data->cs, GPMC_CONFIG_DEV_TYPE, GPMC_DEVICETYPE_NAND); err = gpmc_cs_set_timings(gpmc_nand_data->cs, &t); diff --git a/arch/arm/mach-omap2/gpmc-onenand.c b/arch/arm/mach-omap2/gpmc-onenand.c index 3a7d25fb00e..d776ded9830 100644 --- a/arch/arm/mach-omap2/gpmc-onenand.c +++ b/arch/arm/mach-omap2/gpmc-onenand.c @@ -94,7 +94,7 @@ static int omap2_onenand_set_async_mode(int cs, void __iomem *onenand_base) } static void set_onenand_cfg(void __iomem *onenand_base, int latency, - int sync_read, int sync_write, int hf) + int sync_read, int sync_write, int hf, int vhf) { u32 reg; @@ -114,12 +114,57 @@ static void set_onenand_cfg(void __iomem *onenand_base, int latency, reg |= ONENAND_SYS_CFG1_HF; else reg &= ~ONENAND_SYS_CFG1_HF; + if (vhf) + reg |= ONENAND_SYS_CFG1_VHF; + else + reg &= ~ONENAND_SYS_CFG1_VHF; writew(reg, onenand_base + ONENAND_REG_SYS_CFG1); } +static int omap2_onenand_get_freq(struct omap_onenand_platform_data *cfg, + void __iomem *onenand_base, bool *clk_dep) +{ + u16 ver = readw(onenand_base + ONENAND_REG_VERSION_ID); + int freq = 0; + + if (cfg->get_freq) { + struct onenand_freq_info fi; + + fi.maf_id = readw(onenand_base + ONENAND_REG_MANUFACTURER_ID); + fi.dev_id = readw(onenand_base + ONENAND_REG_DEVICE_ID); + fi.ver_id = ver; + freq = cfg->get_freq(&fi, clk_dep); + if (freq) + return freq; + } + + switch ((ver >> 4) & 0xf) { + case 0: + freq = 40; + break; + case 1: + freq = 54; + break; + case 2: + freq = 66; + break; + case 3: + freq = 83; + break; + case 4: + freq = 104; + break; + default: + freq = 54; + break; + } + + return freq; +} + static int omap2_onenand_set_sync_mode(struct omap_onenand_platform_data *cfg, void __iomem *onenand_base, - int freq) + int *freq_ptr) { struct gpmc_timings t; const int t_cer = 15; @@ -130,10 +175,11 @@ static int omap2_onenand_set_sync_mode(struct omap_onenand_platform_data *cfg, const int t_wph = 30; int min_gpmc_clk_period, t_ces, t_avds, t_avdh, t_ach, t_aavdh, t_rdyo; int tick_ns, div, fclk_offset_ns, fclk_offset, gpmc_clk_ns, latency; - int first_time = 0, hf = 0, sync_read = 0, sync_write = 0; + int first_time = 0, hf = 0, vhf = 0, sync_read = 0, sync_write = 0; int err, ticks_cez; - int cs = cfg->cs; + int cs = cfg->cs, freq = *freq_ptr; u32 reg; + bool clk_dep = false; if (cfg->flags & ONENAND_SYNC_READ) { sync_read = 1; @@ -148,27 +194,7 @@ static int omap2_onenand_set_sync_mode(struct omap_onenand_platform_data *cfg, err = omap2_onenand_set_async_mode(cs, onenand_base); if (err) return err; - reg = readw(onenand_base + ONENAND_REG_VERSION_ID); - switch ((reg >> 4) & 0xf) { - case 0: - freq = 40; - break; - case 1: - freq = 54; - break; - case 2: - freq = 66; - break; - case 3: - freq = 83; - break; - case 4: - freq = 104; - break; - default: - freq = 54; - break; - } + freq = omap2_onenand_get_freq(cfg, onenand_base, &clk_dep); first_time = 1; } @@ -180,7 +206,7 @@ static int omap2_onenand_set_sync_mode(struct omap_onenand_platform_data *cfg, t_avdh = 2; t_ach = 3; t_aavdh = 6; - t_rdyo = 9; + t_rdyo = 6; break; case 83: min_gpmc_clk_period = 12000; /* 83 MHz */ @@ -217,16 +243,36 @@ static int omap2_onenand_set_sync_mode(struct omap_onenand_platform_data *cfg, gpmc_clk_ns = gpmc_ticks_to_ns(div); if (gpmc_clk_ns < 15) /* >66Mhz */ hf = 1; - if (hf) + if (gpmc_clk_ns < 12) /* >83Mhz */ + vhf = 1; + if (vhf) + latency = 8; + else if (hf) latency = 6; else if (gpmc_clk_ns >= 25) /* 40 MHz*/ latency = 3; else latency = 4; + if (clk_dep) { + if (gpmc_clk_ns < 12) { /* >83Mhz */ + t_ces = 3; + t_avds = 4; + } else if (gpmc_clk_ns < 15) { /* >66Mhz */ + t_ces = 5; + t_avds = 4; + } else if (gpmc_clk_ns < 25) { /* >40Mhz */ + t_ces = 6; + t_avds = 5; + } else { + t_ces = 7; + t_avds = 7; + } + } + if (first_time) set_onenand_cfg(onenand_base, latency, - sync_read, sync_write, hf); + sync_read, sync_write, hf, vhf); if (div == 1) { reg = gpmc_cs_read_reg(cs, GPMC_CS_CONFIG2); @@ -264,6 +310,9 @@ static int omap2_onenand_set_sync_mode(struct omap_onenand_platform_data *cfg, /* Read */ t.adv_rd_off = gpmc_ticks_to_ns(fclk_offset + gpmc_ns_to_ticks(t_avdh)); t.oe_on = gpmc_ticks_to_ns(fclk_offset + gpmc_ns_to_ticks(t_ach)); + /* Force at least 1 clk between AVD High to OE Low */ + if (t.oe_on <= t.adv_rd_off) + t.oe_on = t.adv_rd_off + gpmc_round_ns_to_ticks(1); t.access = gpmc_ticks_to_ns(fclk_offset + (latency + 1) * div); t.oe_off = t.access + gpmc_round_ns_to_ticks(1); t.cs_rd_off = t.oe_off; @@ -317,18 +366,20 @@ static int omap2_onenand_set_sync_mode(struct omap_onenand_platform_data *cfg, if (err) return err; - set_onenand_cfg(onenand_base, latency, sync_read, sync_write, hf); + set_onenand_cfg(onenand_base, latency, sync_read, sync_write, hf, vhf); + + *freq_ptr = freq; return 0; } -static int gpmc_onenand_setup(void __iomem *onenand_base, int freq) +static int gpmc_onenand_setup(void __iomem *onenand_base, int *freq_ptr) { struct device *dev = &gpmc_onenand_device.dev; /* Set sync timings in GPMC */ if (omap2_onenand_set_sync_mode(gpmc_onenand_data, onenand_base, - freq) < 0) { + freq_ptr) < 0) { dev_err(dev, "Unable to set synchronous mode\n"); return -EINVAL; } diff --git a/arch/arm/mach-omap2/gpmc.c b/arch/arm/mach-omap2/gpmc.c index 1b7b3e7d02f..674174365f7 100644 --- a/arch/arm/mach-omap2/gpmc.c +++ b/arch/arm/mach-omap2/gpmc.c @@ -14,6 +14,7 @@ */ #undef DEBUG +#include <linux/irq.h> #include <linux/kernel.h> #include <linux/init.h> #include <linux/err.h> @@ -22,6 +23,7 @@ #include <linux/spinlock.h> #include <linux/io.h> #include <linux/module.h> +#include <linux/interrupt.h> #include <asm/mach-types.h> #include <plat/gpmc.h> @@ -58,7 +60,6 @@ #define GPMC_CHUNK_SHIFT 24 /* 16 MB */ #define GPMC_SECTION_SHIFT 28 /* 128 MB */ -#define PREFETCH_FIFOTHRESHOLD (0x40 << 8) #define CS_NUM_SHIFT 24 #define ENABLE_PREFETCH (0x1 << 7) #define DMA_MPU_MODE 2 @@ -100,6 +101,8 @@ static void __iomem *gpmc_base; static struct clk *gpmc_l3_clk; +static irqreturn_t gpmc_handle_irq(int irq, void *dev); + static void gpmc_write_reg(int idx, u32 val) { __raw_writel(val, gpmc_base + idx); @@ -497,6 +500,10 @@ int gpmc_cs_configure(int cs, int cmd, int wval) u32 regval = 0; switch (cmd) { + case GPMC_ENABLE_IRQ: + gpmc_write_reg(GPMC_IRQENABLE, wval); + break; + case GPMC_SET_IRQ_STATUS: gpmc_write_reg(GPMC_IRQSTATUS, wval); break; @@ -598,15 +605,19 @@ EXPORT_SYMBOL(gpmc_nand_write); /** * gpmc_prefetch_enable - configures and starts prefetch transfer * @cs: cs (chip select) number + * @fifo_th: fifo threshold to be used for read/ write * @dma_mode: dma mode enable (1) or disable (0) * @u32_count: number of bytes to be transferred * @is_write: prefetch read(0) or write post(1) mode */ -int gpmc_prefetch_enable(int cs, int dma_mode, +int gpmc_prefetch_enable(int cs, int fifo_th, int dma_mode, unsigned int u32_count, int is_write) { - if (!(gpmc_read_reg(GPMC_PREFETCH_CONTROL))) { + if (fifo_th > PREFETCH_FIFOTHRESHOLD_MAX) { + pr_err("gpmc: fifo threshold is not supported\n"); + return -1; + } else if (!(gpmc_read_reg(GPMC_PREFETCH_CONTROL))) { /* Set the amount of bytes to be prefetched */ gpmc_write_reg(GPMC_PREFETCH_CONFIG2, u32_count); @@ -614,7 +625,7 @@ int gpmc_prefetch_enable(int cs, int dma_mode, * enable the engine. Set which cs is has requested for. */ gpmc_write_reg(GPMC_PREFETCH_CONFIG1, ((cs << CS_NUM_SHIFT) | - PREFETCH_FIFOTHRESHOLD | + PREFETCH_FIFOTHRESHOLD(fifo_th) | ENABLE_PREFETCH | (dma_mode << DMA_MPU_MODE) | (0x1 & is_write))); @@ -678,9 +689,10 @@ static void __init gpmc_mem_init(void) } } -void __init gpmc_init(void) +static int __init gpmc_init(void) { - u32 l; + u32 l, irq; + int cs, ret = -EINVAL; char *ck = NULL; if (cpu_is_omap24xx()) { @@ -698,7 +710,7 @@ void __init gpmc_init(void) } if (WARN_ON(!ck)) - return; + return ret; gpmc_l3_clk = clk_get(NULL, ck); if (IS_ERR(gpmc_l3_clk)) { @@ -723,6 +735,36 @@ void __init gpmc_init(void) l |= (0x02 << 3) | (1 << 0); gpmc_write_reg(GPMC_SYSCONFIG, l); gpmc_mem_init(); + + /* initalize the irq_chained */ + irq = OMAP_GPMC_IRQ_BASE; + for (cs = 0; cs < GPMC_CS_NUM; cs++) { + set_irq_handler(irq, handle_simple_irq); + set_irq_flags(irq, IRQF_VALID); + irq++; + } + + ret = request_irq(INT_34XX_GPMC_IRQ, + gpmc_handle_irq, IRQF_SHARED, "gpmc", gpmc_base); + if (ret) + pr_err("gpmc: irq-%d could not claim: err %d\n", + INT_34XX_GPMC_IRQ, ret); + return ret; +} +postcore_initcall(gpmc_init); + +static irqreturn_t gpmc_handle_irq(int irq, void *dev) +{ + u8 cs; + + if (irq != INT_34XX_GPMC_IRQ) + return IRQ_HANDLED; + /* check cs to invoke the irq */ + cs = ((gpmc_read_reg(GPMC_PREFETCH_CONFIG1)) >> CS_NUM_SHIFT) & 0x7; + if (OMAP_GPMC_IRQ_BASE+cs <= OMAP_GPMC_IRQ_END) + generic_handle_irq(OMAP_GPMC_IRQ_BASE+cs); + + return IRQ_HANDLED; } #ifdef CONFIG_ARCH_OMAP3 diff --git a/arch/arm/mach-omap2/hsmmc.c b/arch/arm/mach-omap2/hsmmc.c index 34272e4863f..137e1a5f3d8 100644 --- a/arch/arm/mach-omap2/hsmmc.c +++ b/arch/arm/mach-omap2/hsmmc.c @@ -16,7 +16,10 @@ #include <mach/hardware.h> #include <plat/mmc.h> #include <plat/omap-pm.h> +#include <plat/mux.h> +#include <plat/omap_device.h> +#include "mux.h" #include "hsmmc.h" #include "control.h" @@ -28,10 +31,6 @@ static u16 control_mmc1; #define HSMMC_NAME_LEN 9 -static struct hsmmc_controller { - char name[HSMMC_NAME_LEN + 1]; -} hsmmc[OMAP34XX_NR_MMC]; - #if defined(CONFIG_ARCH_OMAP3) && defined(CONFIG_PM) static int hsmmc_get_context_loss(struct device *dev) @@ -204,174 +203,312 @@ static int nop_mmc_set_power(struct device *dev, int slot, int power_on, return 0; } -static struct omap_mmc_platform_data *hsmmc_data[OMAP34XX_NR_MMC] __initdata; - -void __init omap2_hsmmc_init(struct omap2_hsmmc_info *controllers) +static inline void omap_hsmmc_mux(struct omap_mmc_platform_data *mmc_controller, + int controller_nr) { - struct omap2_hsmmc_info *c; - int nr_hsmmc = ARRAY_SIZE(hsmmc_data); - int i; - u32 reg; - - if (!cpu_is_omap44xx()) { - if (cpu_is_omap2430()) { - control_pbias_offset = OMAP243X_CONTROL_PBIAS_LITE; - control_devconf1_offset = OMAP243X_CONTROL_DEVCONF1; - } else { - control_pbias_offset = OMAP343X_CONTROL_PBIAS_LITE; - control_devconf1_offset = OMAP343X_CONTROL_DEVCONF1; - } - } else { - control_pbias_offset = - OMAP4_CTRL_MODULE_PAD_CORE_CONTROL_PBIASLITE; - control_mmc1 = OMAP4_CTRL_MODULE_PAD_CORE_CONTROL_MMC1; - reg = omap4_ctrl_pad_readl(control_mmc1); - reg |= (OMAP4_SDMMC1_PUSTRENGTH_GRP0_MASK | - OMAP4_SDMMC1_PUSTRENGTH_GRP1_MASK); - reg &= ~(OMAP4_SDMMC1_PUSTRENGTH_GRP2_MASK | - OMAP4_SDMMC1_PUSTRENGTH_GRP3_MASK); - reg |= (OMAP4_USBC1_DR0_SPEEDCTRL_MASK| - OMAP4_SDMMC1_DR1_SPEEDCTRL_MASK | - OMAP4_SDMMC1_DR2_SPEEDCTRL_MASK); - omap4_ctrl_pad_writel(reg, control_mmc1); - } - - for (c = controllers; c->mmc; c++) { - struct hsmmc_controller *hc = hsmmc + c->mmc - 1; - struct omap_mmc_platform_data *mmc = hsmmc_data[c->mmc - 1]; - - if (!c->mmc || c->mmc > nr_hsmmc) { - pr_debug("MMC%d: no such controller\n", c->mmc); - continue; - } - if (mmc) { - pr_debug("MMC%d: already configured\n", c->mmc); - continue; + if ((mmc_controller->slots[0].switch_pin > 0) && \ + (mmc_controller->slots[0].switch_pin < OMAP_MAX_GPIO_LINES)) + omap_mux_init_gpio(mmc_controller->slots[0].switch_pin, + OMAP_PIN_INPUT_PULLUP); + if ((mmc_controller->slots[0].gpio_wp > 0) && \ + (mmc_controller->slots[0].gpio_wp < OMAP_MAX_GPIO_LINES)) + omap_mux_init_gpio(mmc_controller->slots[0].gpio_wp, + OMAP_PIN_INPUT_PULLUP); + if (cpu_is_omap34xx()) { + if (controller_nr == 0) { + omap_mux_init_signal("sdmmc1_clk", + OMAP_PIN_INPUT_PULLUP); + omap_mux_init_signal("sdmmc1_cmd", + OMAP_PIN_INPUT_PULLUP); + omap_mux_init_signal("sdmmc1_dat0", + OMAP_PIN_INPUT_PULLUP); + if (mmc_controller->slots[0].caps & + (MMC_CAP_4_BIT_DATA | MMC_CAP_8_BIT_DATA)) { + omap_mux_init_signal("sdmmc1_dat1", + OMAP_PIN_INPUT_PULLUP); + omap_mux_init_signal("sdmmc1_dat2", + OMAP_PIN_INPUT_PULLUP); + omap_mux_init_signal("sdmmc1_dat3", + OMAP_PIN_INPUT_PULLUP); + } + if (mmc_controller->slots[0].caps & + MMC_CAP_8_BIT_DATA) { + omap_mux_init_signal("sdmmc1_dat4", + OMAP_PIN_INPUT_PULLUP); + omap_mux_init_signal("sdmmc1_dat5", + OMAP_PIN_INPUT_PULLUP); + omap_mux_init_signal("sdmmc1_dat6", + OMAP_PIN_INPUT_PULLUP); + omap_mux_init_signal("sdmmc1_dat7", + OMAP_PIN_INPUT_PULLUP); + } } - - mmc = kzalloc(sizeof(struct omap_mmc_platform_data), - GFP_KERNEL); - if (!mmc) { - pr_err("Cannot allocate memory for mmc device!\n"); - goto done; + if (controller_nr == 1) { + /* MMC2 */ + omap_mux_init_signal("sdmmc2_clk", + OMAP_PIN_INPUT_PULLUP); + omap_mux_init_signal("sdmmc2_cmd", + OMAP_PIN_INPUT_PULLUP); + omap_mux_init_signal("sdmmc2_dat0", + OMAP_PIN_INPUT_PULLUP); + + /* + * For 8 wire configurations, Lines DAT4, 5, 6 and 7 + * need to be muxed in the board-*.c files + */ + if (mmc_controller->slots[0].caps & + (MMC_CAP_4_BIT_DATA | MMC_CAP_8_BIT_DATA)) { + omap_mux_init_signal("sdmmc2_dat1", + OMAP_PIN_INPUT_PULLUP); + omap_mux_init_signal("sdmmc2_dat2", + OMAP_PIN_INPUT_PULLUP); + omap_mux_init_signal("sdmmc2_dat3", + OMAP_PIN_INPUT_PULLUP); + } + if (mmc_controller->slots[0].caps & + MMC_CAP_8_BIT_DATA) { + omap_mux_init_signal("sdmmc2_dat4.sdmmc2_dat4", + OMAP_PIN_INPUT_PULLUP); + omap_mux_init_signal("sdmmc2_dat5.sdmmc2_dat5", + OMAP_PIN_INPUT_PULLUP); + omap_mux_init_signal("sdmmc2_dat6.sdmmc2_dat6", + OMAP_PIN_INPUT_PULLUP); + omap_mux_init_signal("sdmmc2_dat7.sdmmc2_dat7", + OMAP_PIN_INPUT_PULLUP); + } } - if (c->name) - strncpy(hc->name, c->name, HSMMC_NAME_LEN); - else - snprintf(hc->name, ARRAY_SIZE(hc->name), - "mmc%islot%i", c->mmc, 1); - mmc->slots[0].name = hc->name; - mmc->nr_slots = 1; - mmc->slots[0].caps = c->caps; - mmc->slots[0].internal_clock = !c->ext_clock; - mmc->dma_mask = 0xffffffff; - if (cpu_is_omap44xx()) - mmc->reg_offset = OMAP4_MMC_REG_OFFSET; - else - mmc->reg_offset = 0; + /* + * For MMC3 the pins need to be muxed in the board-*.c files + */ + } +} - mmc->get_context_loss_count = hsmmc_get_context_loss; +static int __init omap_hsmmc_pdata_init(struct omap2_hsmmc_info *c, + struct omap_mmc_platform_data *mmc) +{ + char *hc_name; - mmc->slots[0].switch_pin = c->gpio_cd; - mmc->slots[0].gpio_wp = c->gpio_wp; + hc_name = kzalloc(sizeof(char) * (HSMMC_NAME_LEN + 1), GFP_KERNEL); + if (!hc_name) { + pr_err("Cannot allocate memory for controller slot name\n"); + kfree(hc_name); + return -ENOMEM; + } - mmc->slots[0].remux = c->remux; - mmc->slots[0].init_card = c->init_card; + if (c->name) + strncpy(hc_name, c->name, HSMMC_NAME_LEN); + else + snprintf(hc_name, (HSMMC_NAME_LEN + 1), "mmc%islot%i", + c->mmc, 1); + mmc->slots[0].name = hc_name; + mmc->nr_slots = 1; + mmc->slots[0].caps = c->caps; + mmc->slots[0].internal_clock = !c->ext_clock; + mmc->dma_mask = 0xffffffff; + if (cpu_is_omap44xx()) + mmc->reg_offset = OMAP4_MMC_REG_OFFSET; + else + mmc->reg_offset = 0; - if (c->cover_only) - mmc->slots[0].cover = 1; + mmc->get_context_loss_count = hsmmc_get_context_loss; - if (c->nonremovable) - mmc->slots[0].nonremovable = 1; + mmc->slots[0].switch_pin = c->gpio_cd; + mmc->slots[0].gpio_wp = c->gpio_wp; - if (c->power_saving) - mmc->slots[0].power_saving = 1; + mmc->slots[0].remux = c->remux; + mmc->slots[0].init_card = c->init_card; - if (c->no_off) - mmc->slots[0].no_off = 1; + if (c->cover_only) + mmc->slots[0].cover = 1; - if (c->vcc_aux_disable_is_sleep) - mmc->slots[0].vcc_aux_disable_is_sleep = 1; + if (c->nonremovable) + mmc->slots[0].nonremovable = 1; - /* NOTE: MMC slots should have a Vcc regulator set up. - * This may be from a TWL4030-family chip, another - * controllable regulator, or a fixed supply. - * - * temporary HACK: ocr_mask instead of fixed supply - */ - mmc->slots[0].ocr_mask = c->ocr_mask; + if (c->power_saving) + mmc->slots[0].power_saving = 1; - if (cpu_is_omap3517() || cpu_is_omap3505()) - mmc->slots[0].set_power = nop_mmc_set_power; - else - mmc->slots[0].features |= HSMMC_HAS_PBIAS; + if (c->no_off) + mmc->slots[0].no_off = 1; - if (cpu_is_omap44xx() && (omap_rev() > OMAP4430_REV_ES1_0)) - mmc->slots[0].features |= HSMMC_HAS_UPDATED_RESET; + if (c->vcc_aux_disable_is_sleep) + mmc->slots[0].vcc_aux_disable_is_sleep = 1; - switch (c->mmc) { - case 1: - if (mmc->slots[0].features & HSMMC_HAS_PBIAS) { - /* on-chip level shifting via PBIAS0/PBIAS1 */ - if (cpu_is_omap44xx()) { - mmc->slots[0].before_set_reg = + /* + * NOTE: MMC slots should have a Vcc regulator set up. + * This may be from a TWL4030-family chip, another + * controllable regulator, or a fixed supply. + * + * temporary HACK: ocr_mask instead of fixed supply + */ + mmc->slots[0].ocr_mask = c->ocr_mask; + + if (cpu_is_omap3517() || cpu_is_omap3505()) + mmc->slots[0].set_power = nop_mmc_set_power; + else + mmc->slots[0].features |= HSMMC_HAS_PBIAS; + + if (cpu_is_omap44xx() && (omap_rev() > OMAP4430_REV_ES1_0)) + mmc->slots[0].features |= HSMMC_HAS_UPDATED_RESET; + + switch (c->mmc) { + case 1: + if (mmc->slots[0].features & HSMMC_HAS_PBIAS) { + /* on-chip level shifting via PBIAS0/PBIAS1 */ + if (cpu_is_omap44xx()) { + mmc->slots[0].before_set_reg = omap4_hsmmc1_before_set_reg; - mmc->slots[0].after_set_reg = + mmc->slots[0].after_set_reg = omap4_hsmmc1_after_set_reg; - } else { - mmc->slots[0].before_set_reg = + } else { + mmc->slots[0].before_set_reg = omap_hsmmc1_before_set_reg; - mmc->slots[0].after_set_reg = + mmc->slots[0].after_set_reg = omap_hsmmc1_after_set_reg; - } } + } - /* Omap3630 HSMMC1 supports only 4-bit */ - if (cpu_is_omap3630() && - (c->caps & MMC_CAP_8_BIT_DATA)) { - c->caps &= ~MMC_CAP_8_BIT_DATA; - c->caps |= MMC_CAP_4_BIT_DATA; - mmc->slots[0].caps = c->caps; - } - break; - case 2: - if (c->ext_clock) - c->transceiver = 1; - if (c->transceiver && (c->caps & MMC_CAP_8_BIT_DATA)) { - c->caps &= ~MMC_CAP_8_BIT_DATA; - c->caps |= MMC_CAP_4_BIT_DATA; - } - /* FALLTHROUGH */ - case 3: - if (mmc->slots[0].features & HSMMC_HAS_PBIAS) { - /* off-chip level shifting, or none */ - mmc->slots[0].before_set_reg = hsmmc23_before_set_reg; - mmc->slots[0].after_set_reg = NULL; - } - break; - default: - pr_err("MMC%d configuration not supported!\n", c->mmc); - kfree(mmc); - continue; + /* OMAP3630 HSMMC1 supports only 4-bit */ + if (cpu_is_omap3630() && + (c->caps & MMC_CAP_8_BIT_DATA)) { + c->caps &= ~MMC_CAP_8_BIT_DATA; + c->caps |= MMC_CAP_4_BIT_DATA; + mmc->slots[0].caps = c->caps; + } + break; + case 2: + if (c->ext_clock) + c->transceiver = 1; + if (c->transceiver && (c->caps & MMC_CAP_8_BIT_DATA)) { + c->caps &= ~MMC_CAP_8_BIT_DATA; + c->caps |= MMC_CAP_4_BIT_DATA; } - hsmmc_data[c->mmc - 1] = mmc; + /* FALLTHROUGH */ + case 3: + if (mmc->slots[0].features & HSMMC_HAS_PBIAS) { + /* off-chip level shifting, or none */ + mmc->slots[0].before_set_reg = hsmmc23_before_set_reg; + mmc->slots[0].after_set_reg = NULL; + } + break; + case 4: + case 5: + mmc->slots[0].before_set_reg = NULL; + mmc->slots[0].after_set_reg = NULL; + break; + default: + pr_err("MMC%d configuration not supported!\n", c->mmc); + kfree(hc_name); + return -ENODEV; + } + return 0; +} + +static struct omap_device_pm_latency omap_hsmmc_latency[] = { + [0] = { + .deactivate_func = omap_device_idle_hwmods, + .activate_func = omap_device_enable_hwmods, + .flags = OMAP_DEVICE_LATENCY_AUTO_ADJUST, + }, + /* + * XXX There should also be an entry here to power off/on the + * MMC regulators/PBIAS cells, etc. + */ +}; + +#define MAX_OMAP_MMC_HWMOD_NAME_LEN 16 + +void __init omap_init_hsmmc(struct omap2_hsmmc_info *hsmmcinfo, int ctrl_nr) +{ + struct omap_hwmod *oh; + struct omap_device *od; + struct omap_device_pm_latency *ohl; + char oh_name[MAX_OMAP_MMC_HWMOD_NAME_LEN]; + struct omap_mmc_platform_data *mmc_data; + struct omap_mmc_dev_attr *mmc_dev_attr; + char *name; + int l; + int ohl_cnt = 0; + + mmc_data = kzalloc(sizeof(struct omap_mmc_platform_data), GFP_KERNEL); + if (!mmc_data) { + pr_err("Cannot allocate memory for mmc device!\n"); + goto done; } - omap2_init_mmc(hsmmc_data, OMAP34XX_NR_MMC); + if (omap_hsmmc_pdata_init(hsmmcinfo, mmc_data) < 0) { + pr_err("%s fails!\n", __func__); + goto done; + } + omap_hsmmc_mux(mmc_data, (ctrl_nr - 1)); + + name = "omap_hsmmc"; + ohl = omap_hsmmc_latency; + ohl_cnt = ARRAY_SIZE(omap_hsmmc_latency); + + l = snprintf(oh_name, MAX_OMAP_MMC_HWMOD_NAME_LEN, + "mmc%d", ctrl_nr); + WARN(l >= MAX_OMAP_MMC_HWMOD_NAME_LEN, + "String buffer overflow in MMC%d device setup\n", ctrl_nr); + oh = omap_hwmod_lookup(oh_name); + if (!oh) { + pr_err("Could not look up %s\n", oh_name); + kfree(mmc_data->slots[0].name); + goto done; + } - /* pass the device nodes back to board setup code */ - for (c = controllers; c->mmc; c++) { - struct omap_mmc_platform_data *mmc = hsmmc_data[c->mmc - 1]; + if (oh->dev_attr != NULL) { + mmc_dev_attr = oh->dev_attr; + mmc_data->controller_flags = mmc_dev_attr->flags; + } - if (!c->mmc || c->mmc > nr_hsmmc) - continue; - c->dev = mmc->dev; + od = omap_device_build(name, ctrl_nr - 1, oh, mmc_data, + sizeof(struct omap_mmc_platform_data), ohl, ohl_cnt, false); + if (IS_ERR(od)) { + WARN(1, "Cant build omap_device for %s:%s.\n", name, oh->name); + kfree(mmc_data->slots[0].name); + goto done; } + /* + * return device handle to board setup code + * required to populate for regulator framework structure + */ + hsmmcinfo->dev = &od->pdev.dev; done: - for (i = 0; i < nr_hsmmc; i++) - kfree(hsmmc_data[i]); + kfree(mmc_data); +} + +void __init omap2_hsmmc_init(struct omap2_hsmmc_info *controllers) +{ + u32 reg; + + if (!cpu_is_omap44xx()) { + if (cpu_is_omap2430()) { + control_pbias_offset = OMAP243X_CONTROL_PBIAS_LITE; + control_devconf1_offset = OMAP243X_CONTROL_DEVCONF1; + } else { + control_pbias_offset = OMAP343X_CONTROL_PBIAS_LITE; + control_devconf1_offset = OMAP343X_CONTROL_DEVCONF1; + } + } else { + control_pbias_offset = + OMAP4_CTRL_MODULE_PAD_CORE_CONTROL_PBIASLITE; + control_mmc1 = OMAP4_CTRL_MODULE_PAD_CORE_CONTROL_MMC1; + reg = omap4_ctrl_pad_readl(control_mmc1); + reg |= (OMAP4_SDMMC1_PUSTRENGTH_GRP0_MASK | + OMAP4_SDMMC1_PUSTRENGTH_GRP1_MASK); + reg &= ~(OMAP4_SDMMC1_PUSTRENGTH_GRP2_MASK | + OMAP4_SDMMC1_PUSTRENGTH_GRP3_MASK); + reg |= (OMAP4_USBC1_DR0_SPEEDCTRL_MASK| + OMAP4_SDMMC1_DR1_SPEEDCTRL_MASK | + OMAP4_SDMMC1_DR2_SPEEDCTRL_MASK); + omap4_ctrl_pad_writel(reg, control_mmc1); + } + + for (; controllers->mmc; controllers++) + omap_init_hsmmc(controllers, controllers->mmc); + } #endif diff --git a/arch/arm/mach-omap2/hwspinlock.c b/arch/arm/mach-omap2/hwspinlock.c new file mode 100644 index 00000000000..06d4a80660a --- /dev/null +++ b/arch/arm/mach-omap2/hwspinlock.c @@ -0,0 +1,63 @@ +/* + * OMAP hardware spinlock device initialization + * + * Copyright (C) 2010 Texas Instruments Incorporated - http://www.ti.com + * + * Contact: Simon Que <sque@ti.com> + * Hari Kanigeri <h-kanigeri2@ti.com> + * + * This program is free software; you can redistribute it and/or + * modify it under the terms of the GNU General Public License + * version 2 as published by the Free Software Foundation. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * General Public License for more details. + */ + +#include <linux/kernel.h> +#include <linux/init.h> +#include <linux/err.h> + +#include <plat/omap_hwmod.h> +#include <plat/omap_device.h> + +struct omap_device_pm_latency omap_spinlock_latency[] = { + { + .deactivate_func = omap_device_idle_hwmods, + .activate_func = omap_device_enable_hwmods, + .flags = OMAP_DEVICE_LATENCY_AUTO_ADJUST, + } +}; + +int __init hwspinlocks_init(void) +{ + int retval = 0; + struct omap_hwmod *oh; + struct omap_device *od; + const char *oh_name = "spinlock"; + const char *dev_name = "omap_hwspinlock"; + + /* + * Hwmod lookup will fail in case our platform doesn't support the + * hardware spinlock module, so it is safe to run this initcall + * on all omaps + */ + oh = omap_hwmod_lookup(oh_name); + if (oh == NULL) + return -EINVAL; + + od = omap_device_build(dev_name, 0, oh, NULL, 0, + omap_spinlock_latency, + ARRAY_SIZE(omap_spinlock_latency), false); + if (IS_ERR(od)) { + pr_err("Can't build omap_device for %s:%s\n", dev_name, + oh_name); + retval = PTR_ERR(od); + } + + return retval; +} +/* early board code might need to reserve specific hwspinlock instances */ +postcore_initcall(hwspinlocks_init); diff --git a/arch/arm/mach-omap2/id.c b/arch/arm/mach-omap2/id.c index 5f9086c65e4..2537090aa33 100644 --- a/arch/arm/mach-omap2/id.c +++ b/arch/arm/mach-omap2/id.c @@ -6,7 +6,7 @@ * Copyright (C) 2005 Nokia Corporation * Written by Tony Lindgren <tony@atomide.com> * - * Copyright (C) 2009 Texas Instruments + * Copyright (C) 2009-11 Texas Instruments * Added OMAP4 support - Santosh Shilimkar <santosh.shilimkar@ti.com> * * This program is free software; you can redistribute it and/or modify @@ -84,6 +84,11 @@ EXPORT_SYMBOL(omap_type); #define OMAP_TAP_DIE_ID_2 0x0220 #define OMAP_TAP_DIE_ID_3 0x0224 +#define OMAP_TAP_DIE_ID_44XX_0 0x0200 +#define OMAP_TAP_DIE_ID_44XX_1 0x0208 +#define OMAP_TAP_DIE_ID_44XX_2 0x020c +#define OMAP_TAP_DIE_ID_44XX_3 0x0210 + #define read_tap_reg(reg) __raw_readl(tap_base + (reg)) struct omap_id { @@ -107,6 +112,14 @@ static u16 tap_prod_id; void omap_get_die_id(struct omap_die_id *odi) { + if (cpu_is_omap44xx()) { + odi->id_0 = read_tap_reg(OMAP_TAP_DIE_ID_44XX_0); + odi->id_1 = read_tap_reg(OMAP_TAP_DIE_ID_44XX_1); + odi->id_2 = read_tap_reg(OMAP_TAP_DIE_ID_44XX_2); + odi->id_3 = read_tap_reg(OMAP_TAP_DIE_ID_44XX_3); + + return; + } odi->id_0 = read_tap_reg(OMAP_TAP_DIE_ID_0); odi->id_1 = read_tap_reg(OMAP_TAP_DIE_ID_1); odi->id_2 = read_tap_reg(OMAP_TAP_DIE_ID_2); @@ -191,12 +204,19 @@ static void __init omap3_check_features(void) if (!cpu_is_omap3505() && !cpu_is_omap3517()) omap3_features |= OMAP3_HAS_IO_WAKEUP; + omap3_features |= OMAP3_HAS_SDRC; + /* * TODO: Get additional info (where applicable) * e.g. Size of L2 cache. */ } +static void __init ti816x_check_features(void) +{ + omap3_features = OMAP3_HAS_NEON; +} + static void __init omap3_check_revision(void) { u32 cpuid, idcode; @@ -287,6 +307,20 @@ static void __init omap3_check_revision(void) omap_chip.oc |= CHIP_IS_OMAP3630ES1_2; } break; + case 0xb81e: + omap_chip.oc = CHIP_IS_TI816X; + + switch (rev) { + case 0: + omap_revision = TI8168_REV_ES1_0; + break; + case 1: + omap_revision = TI8168_REV_ES1_1; + break; + default: + omap_revision = TI8168_REV_ES1_1; + } + break; default: /* Unknown default to latest silicon rev as default*/ omap_revision = OMAP3630_REV_ES1_2; @@ -307,7 +341,7 @@ static void __init omap4_check_revision(void) */ idcode = read_tap_reg(OMAP_TAP_IDCODE); hawkeye = (idcode >> 12) & 0xffff; - rev = (idcode >> 28) & 0xff; + rev = (idcode >> 28) & 0xf; /* * Few initial ES2.0 samples IDCODE is same as ES1.0 @@ -326,22 +360,31 @@ static void __init omap4_check_revision(void) omap_chip.oc |= CHIP_IS_OMAP4430ES1; break; case 1: + default: omap_revision = OMAP4430_REV_ES2_0; omap_chip.oc |= CHIP_IS_OMAP4430ES2; + } + break; + case 0xb95c: + switch (rev) { + case 3: + omap_revision = OMAP4430_REV_ES2_1; + omap_chip.oc |= CHIP_IS_OMAP4430ES2_1; break; + case 4: default: - omap_revision = OMAP4430_REV_ES2_0; - omap_chip.oc |= CHIP_IS_OMAP4430ES2; - } - break; + omap_revision = OMAP4430_REV_ES2_2; + omap_chip.oc |= CHIP_IS_OMAP4430ES2_2; + } + break; default: - /* Unknown default to latest silicon rev as default*/ - omap_revision = OMAP4430_REV_ES2_0; - omap_chip.oc |= CHIP_IS_OMAP4430ES2; + /* Unknown default to latest silicon rev as default */ + omap_revision = OMAP4430_REV_ES2_2; + omap_chip.oc |= CHIP_IS_OMAP4430ES2_2; } - pr_info("OMAP%04x ES%d.0\n", - omap_rev() >> 16, ((omap_rev() >> 12) & 0xf) + 1); + pr_info("OMAP%04x ES%d.%d\n", omap_rev() >> 16, + ((omap_rev() >> 12) & 0xf), ((omap_rev() >> 8) & 0xf)); } #define OMAP3_SHOW_FEATURE(feat) \ @@ -372,6 +415,8 @@ static void __init omap3_cpuinfo(void) /* Already set in omap3_check_revision() */ strcpy(cpu_name, "AM3505"); } + } else if (cpu_is_ti816x()) { + strcpy(cpu_name, "TI816X"); } else if (omap3_has_iva() && omap3_has_sgx()) { /* OMAP3430, OMAP3525, OMAP3515, OMAP3503 devices */ strcpy(cpu_name, "OMAP3430/3530"); @@ -386,7 +431,7 @@ static void __init omap3_cpuinfo(void) strcpy(cpu_name, "OMAP3503"); } - if (cpu_is_omap3630()) { + if (cpu_is_omap3630() || cpu_is_ti816x()) { switch (rev) { case OMAP_REVBITS_00: strcpy(cpu_rev, "1.0"); @@ -462,7 +507,13 @@ void __init omap2_check_revision(void) omap24xx_check_revision(); } else if (cpu_is_omap34xx()) { omap3_check_revision(); - omap3_check_features(); + + /* TI816X doesn't have feature register */ + if (!cpu_is_ti816x()) + omap3_check_features(); + else + ti816x_check_features(); + omap3_cpuinfo(); return; } else if (cpu_is_omap44xx()) { diff --git a/arch/arm/mach-omap2/include/mach/debug-macro.S b/arch/arm/mach-omap2/include/mach/debug-macro.S index 6049f465ec8..48adfe9fe4f 100644 --- a/arch/arm/mach-omap2/include/mach/debug-macro.S +++ b/arch/arm/mach-omap2/include/mach/debug-macro.S @@ -72,6 +72,12 @@ omap_uart_lsr: .word 0 beq 34f @ configure OMAP3UART4 cmp \rp, #OMAP4UART4 @ only on 44xx beq 44f @ configure OMAP4UART4 + cmp \rp, #TI816XUART1 @ ti816x UART offsets different + beq 81f @ configure UART1 + cmp \rp, #TI816XUART2 @ ti816x UART offsets different + beq 82f @ configure UART2 + cmp \rp, #TI816XUART3 @ ti816x UART offsets different + beq 83f @ configure UART3 cmp \rp, #ZOOM_UART @ only on zoom2/3 beq 95f @ configure ZOOM_UART @@ -94,6 +100,12 @@ omap_uart_lsr: .word 0 b 98f 44: mov \rp, #UART_OFFSET(OMAP4_UART4_BASE) b 98f +81: mov \rp, #UART_OFFSET(TI816X_UART1_BASE) + b 98f +82: mov \rp, #UART_OFFSET(TI816X_UART2_BASE) + b 98f +83: mov \rp, #UART_OFFSET(TI816X_UART3_BASE) + b 98f 95: ldr \rp, =ZOOM_UART_BASE mrc p15, 0, \rv, c1, c0 tst \rv, #1 @ MMU enabled? diff --git a/arch/arm/mach-omap2/include/mach/entry-macro.S b/arch/arm/mach-omap2/include/mach/entry-macro.S index 81985a665cb..a48690b9099 100644 --- a/arch/arm/mach-omap2/include/mach/entry-macro.S +++ b/arch/arm/mach-omap2/include/mach/entry-macro.S @@ -61,6 +61,14 @@ bne 9998f ldr \irqnr, [\base, #0xd8] /* IRQ pending reg 3 */ cmp \irqnr, #0x0 + bne 9998f + + /* + * ti816x has additional IRQ pending register. Checking this + * register on omap2 & omap3 has no effect (read as 0). + */ + ldr \irqnr, [\base, #0xf8] /* IRQ pending reg 4 */ + cmp \irqnr, #0x0 9998: ldrne \irqnr, [\base, #INTCPS_SIR_IRQ_OFFSET] and \irqnr, \irqnr, #ACTIVEIRQ_MASK /* Clear spurious bits */ @@ -133,6 +141,11 @@ bne 9999f ldr \irqnr, [\base, #0xd8] /* IRQ pending reg 3 */ cmp \irqnr, #0x0 +#ifdef CONFIG_SOC_OMAPTI816X + bne 9999f + ldr \irqnr, [\base, #0xf8] /* IRQ pending reg 4 */ + cmp \irqnr, #0x0 +#endif 9999: ldrne \irqnr, [\base, #INTCPS_SIR_IRQ_OFFSET] and \irqnr, \irqnr, #ACTIVEIRQ_MASK /* Clear spurious bits */ diff --git a/arch/arm/mach-omap2/include/mach/omap4-common.h b/arch/arm/mach-omap2/include/mach/omap4-common.h index 5b0270b2893..de441c05a6a 100644 --- a/arch/arm/mach-omap2/include/mach/omap4-common.h +++ b/arch/arm/mach-omap2/include/mach/omap4-common.h @@ -17,8 +17,12 @@ * wfi used in low power code. Directly opcode is used instead * of instruction to avoid mulit-omap build break */ +#ifdef CONFIG_THUMB2_KERNEL +#define do_wfi() __asm__ __volatile__ ("wfi" : : : "memory") +#else #define do_wfi() \ __asm__ __volatile__ (".word 0xe320f003" : : : "memory") +#endif #ifdef CONFIG_CACHE_L2X0 extern void __iomem *l2cache_base; diff --git a/arch/arm/mach-omap2/io.c b/arch/arm/mach-omap2/io.c index c2032041d26..441e79d043a 100644 --- a/arch/arm/mach-omap2/io.c +++ b/arch/arm/mach-omap2/io.c @@ -30,7 +30,6 @@ #include <plat/sram.h> #include <plat/sdrc.h> -#include <plat/gpmc.h> #include <plat/serial.h> #include "clock2xxx.h" @@ -66,7 +65,7 @@ static struct map_desc omap24xx_io_desc[] __initdata = { }, }; -#ifdef CONFIG_ARCH_OMAP2420 +#ifdef CONFIG_SOC_OMAP2420 static struct map_desc omap242x_io_desc[] __initdata = { { .virtual = DSP_MEM_2420_VIRT, @@ -90,7 +89,7 @@ static struct map_desc omap242x_io_desc[] __initdata = { #endif -#ifdef CONFIG_ARCH_OMAP2430 +#ifdef CONFIG_SOC_OMAP2430 static struct map_desc omap243x_io_desc[] __initdata = { { .virtual = L4_WK_243X_VIRT, @@ -175,6 +174,18 @@ static struct map_desc omap34xx_io_desc[] __initdata = { #endif }; #endif + +#ifdef CONFIG_SOC_OMAPTI816X +static struct map_desc omapti816x_io_desc[] __initdata = { + { + .virtual = L4_34XX_VIRT, + .pfn = __phys_to_pfn(L4_34XX_PHYS), + .length = L4_34XX_SIZE, + .type = MT_DEVICE + }, +}; +#endif + #ifdef CONFIG_ARCH_OMAP4 static struct map_desc omap44xx_io_desc[] __initdata = { { @@ -241,7 +252,7 @@ static void __init _omap2_map_common_io(void) omap_sram_init(); } -#ifdef CONFIG_ARCH_OMAP2420 +#ifdef CONFIG_SOC_OMAP2420 void __init omap242x_map_common_io(void) { iotable_init(omap24xx_io_desc, ARRAY_SIZE(omap24xx_io_desc)); @@ -250,7 +261,7 @@ void __init omap242x_map_common_io(void) } #endif -#ifdef CONFIG_ARCH_OMAP2430 +#ifdef CONFIG_SOC_OMAP2430 void __init omap243x_map_common_io(void) { iotable_init(omap24xx_io_desc, ARRAY_SIZE(omap24xx_io_desc)); @@ -267,6 +278,14 @@ void __init omap34xx_map_common_io(void) } #endif +#ifdef CONFIG_SOC_OMAPTI816X +void __init omapti816x_map_common_io(void) +{ + iotable_init(omapti816x_io_desc, ARRAY_SIZE(omapti816x_io_desc)); + _omap2_map_common_io(); +} +#endif + #ifdef CONFIG_ARCH_OMAP4 void __init omap44xx_map_common_io(void) { @@ -337,15 +356,15 @@ void __init omap2_init_common_infrastructure(void) if (cpu_is_omap242x()) { omap2xxx_powerdomains_init(); - omap2_clockdomains_init(); + omap2xxx_clockdomains_init(); omap2420_hwmod_init(); } else if (cpu_is_omap243x()) { omap2xxx_powerdomains_init(); - omap2_clockdomains_init(); + omap2xxx_clockdomains_init(); omap2430_hwmod_init(); } else if (cpu_is_omap34xx()) { omap3xxx_powerdomains_init(); - omap2_clockdomains_init(); + omap3xxx_clockdomains_init(); omap3xxx_hwmod_init(); } else if (cpu_is_omap44xx()) { omap44xx_powerdomains_init(); @@ -398,15 +417,10 @@ void __init omap2_init_common_infrastructure(void) void __init omap2_init_common_devices(struct omap_sdrc_params *sdrc_cs0, struct omap_sdrc_params *sdrc_cs1) { - omap_serial_early_init(); - - omap_hwmod_late_init(); - - if (cpu_is_omap24xx() || cpu_is_omap34xx()) { + if (cpu_is_omap24xx() || omap3_has_sdrc()) { omap2_sdrc_init(sdrc_cs0, sdrc_cs1); _omap2_init_reprogram_sdrc(); } - gpmc_init(); omap_irq_base_init(); } diff --git a/arch/arm/mach-omap2/iommu2.c b/arch/arm/mach-omap2/iommu2.c index 14ee686b649..adb083e41ac 100644 --- a/arch/arm/mach-omap2/iommu2.c +++ b/arch/arm/mach-omap2/iommu2.c @@ -145,35 +145,32 @@ static void omap2_iommu_set_twl(struct iommu *obj, bool on) static u32 omap2_iommu_fault_isr(struct iommu *obj, u32 *ra) { - int i; u32 stat, da; - const char *err_msg[] = { - "tlb miss", - "translation fault", - "emulation miss", - "table walk fault", - "multi hit fault", - }; + u32 errs = 0; stat = iommu_read_reg(obj, MMU_IRQSTATUS); stat &= MMU_IRQ_MASK; - if (!stat) + if (!stat) { + *ra = 0; return 0; + } da = iommu_read_reg(obj, MMU_FAULT_AD); *ra = da; - dev_err(obj->dev, "%s:\tda:%08x ", __func__, da); - - for (i = 0; i < ARRAY_SIZE(err_msg); i++) { - if (stat & (1 << i)) - printk("%s ", err_msg[i]); - } - printk("\n"); - + if (stat & MMU_IRQ_TLBMISS) + errs |= OMAP_IOMMU_ERR_TLB_MISS; + if (stat & MMU_IRQ_TRANSLATIONFAULT) + errs |= OMAP_IOMMU_ERR_TRANS_FAULT; + if (stat & MMU_IRQ_EMUMISS) + errs |= OMAP_IOMMU_ERR_EMU_MISS; + if (stat & MMU_IRQ_TABLEWALKFAULT) + errs |= OMAP_IOMMU_ERR_TBLWALK_FAULT; + if (stat & MMU_IRQ_MULTIHITFAULT) + errs |= OMAP_IOMMU_ERR_MULTIHIT_FAULT; iommu_write_reg(obj, stat, MMU_IRQSTATUS); - return stat; + return errs; } static void omap2_tlb_read_cr(struct iommu *obj, struct cr_regs *cr) diff --git a/arch/arm/mach-omap2/irq.c b/arch/arm/mach-omap2/irq.c index 23049c487c4..bc524b94fd5 100644 --- a/arch/arm/mach-omap2/irq.c +++ b/arch/arm/mach-omap2/irq.c @@ -61,8 +61,6 @@ struct omap3_intc_regs { u32 mir[INTCPS_NR_MIR_REGS]; }; -static struct omap3_intc_regs intc_context[ARRAY_SIZE(irq_banks)]; - /* INTC bank register get/set */ static void intc_bank_write_reg(u32 val, struct omap_irq_bank *bank, u16 reg) @@ -110,7 +108,7 @@ static void omap_mask_irq(struct irq_data *d) unsigned int irq = d->irq; int offset = irq & (~(IRQ_BITS_PER_REG - 1)); - if (cpu_is_omap34xx()) { + if (cpu_is_omap34xx() && !cpu_is_ti816x()) { int spurious = 0; /* @@ -205,6 +203,9 @@ void __init omap_init_irq(void) BUG_ON(!base); + if (cpu_is_ti816x()) + bank->nr_irqs = 128; + /* Static mapping, never released */ bank->base_reg = ioremap(base, SZ_4K); if (!bank->base_reg) { @@ -229,6 +230,8 @@ void __init omap_init_irq(void) } #ifdef CONFIG_ARCH_OMAP3 +static struct omap3_intc_regs intc_context[ARRAY_SIZE(irq_banks)]; + void omap_intc_save_context(void) { int ind = 0, i = 0; diff --git a/arch/arm/mach-omap2/mailbox.c b/arch/arm/mach-omap2/mailbox.c index 24b88504df0..86d564a640b 100644 --- a/arch/arm/mach-omap2/mailbox.c +++ b/arch/arm/mach-omap2/mailbox.c @@ -14,12 +14,11 @@ #include <linux/err.h> #include <linux/platform_device.h> #include <linux/io.h> +#include <linux/pm_runtime.h> #include <plat/mailbox.h> #include <mach/irqs.h> #define MAILBOX_REVISION 0x000 -#define MAILBOX_SYSCONFIG 0x010 -#define MAILBOX_SYSSTATUS 0x014 #define MAILBOX_MESSAGE(m) (0x040 + 4 * (m)) #define MAILBOX_FIFOSTATUS(m) (0x080 + 4 * (m)) #define MAILBOX_MSGSTATUS(m) (0x0c0 + 4 * (m)) @@ -33,17 +32,6 @@ #define MAILBOX_IRQ_NEWMSG(m) (1 << (2 * (m))) #define MAILBOX_IRQ_NOTFULL(m) (1 << (2 * (m) + 1)) -/* SYSCONFIG: register bit definition */ -#define AUTOIDLE (1 << 0) -#define SOFTRESET (1 << 1) -#define SMARTIDLE (2 << 3) -#define OMAP4_SOFTRESET (1 << 0) -#define OMAP4_NOIDLE (1 << 2) -#define OMAP4_SMARTIDLE (2 << 2) - -/* SYSSTATUS: register bit definition */ -#define RESETDONE (1 << 0) - #define MBOX_REG_SIZE 0x120 #define OMAP4_MBOX_REG_SIZE 0x130 @@ -70,8 +58,6 @@ struct omap_mbox2_priv { unsigned long irqdisable; }; -static struct clk *mbox_ick_handle; - static void omap2_mbox_enable_irq(struct omap_mbox *mbox, omap_mbox_type_t irq); @@ -89,53 +75,13 @@ static inline void mbox_write_reg(u32 val, size_t ofs) static int omap2_mbox_startup(struct omap_mbox *mbox) { u32 l; - unsigned long timeout; - mbox_ick_handle = clk_get(NULL, "mailboxes_ick"); - if (IS_ERR(mbox_ick_handle)) { - printk(KERN_ERR "Could not get mailboxes_ick: %ld\n", - PTR_ERR(mbox_ick_handle)); - return PTR_ERR(mbox_ick_handle); - } - clk_enable(mbox_ick_handle); - - if (cpu_is_omap44xx()) { - mbox_write_reg(OMAP4_SOFTRESET, MAILBOX_SYSCONFIG); - timeout = jiffies + msecs_to_jiffies(20); - do { - l = mbox_read_reg(MAILBOX_SYSCONFIG); - if (!(l & OMAP4_SOFTRESET)) - break; - } while (!time_after(jiffies, timeout)); - - if (l & OMAP4_SOFTRESET) { - pr_err("Can't take mailbox out of reset\n"); - return -ENODEV; - } - } else { - mbox_write_reg(SOFTRESET, MAILBOX_SYSCONFIG); - timeout = jiffies + msecs_to_jiffies(20); - do { - l = mbox_read_reg(MAILBOX_SYSSTATUS); - if (l & RESETDONE) - break; - } while (!time_after(jiffies, timeout)); - - if (!(l & RESETDONE)) { - pr_err("Can't take mailbox out of reset\n"); - return -ENODEV; - } - } + pm_runtime_enable(mbox->dev->parent); + pm_runtime_get_sync(mbox->dev->parent); l = mbox_read_reg(MAILBOX_REVISION); pr_debug("omap mailbox rev %d.%d\n", (l & 0xf0) >> 4, (l & 0x0f)); - if (cpu_is_omap44xx()) - l = OMAP4_SMARTIDLE; - else - l = SMARTIDLE | AUTOIDLE; - mbox_write_reg(l, MAILBOX_SYSCONFIG); - omap2_mbox_enable_irq(mbox, IRQ_RX); return 0; @@ -143,9 +89,8 @@ static int omap2_mbox_startup(struct omap_mbox *mbox) static void omap2_mbox_shutdown(struct omap_mbox *mbox) { - clk_disable(mbox_ick_handle); - clk_put(mbox_ick_handle); - mbox_ick_handle = NULL; + pm_runtime_put_sync(mbox->dev->parent); + pm_runtime_disable(mbox->dev->parent); } /* Mailbox FIFO handle functions */ @@ -312,7 +257,7 @@ struct omap_mbox mbox_dsp_info = { struct omap_mbox *omap3_mboxes[] = { &mbox_dsp_info, NULL }; #endif -#if defined(CONFIG_ARCH_OMAP2420) +#if defined(CONFIG_SOC_OMAP2420) /* IVA */ static struct omap_mbox2_priv omap2_mbox_iva_priv = { .tx_fifo = { @@ -400,14 +345,14 @@ static int __devinit omap2_mbox_probe(struct platform_device *pdev) else if (cpu_is_omap34xx()) { list = omap3_mboxes; - list[0]->irq = platform_get_irq_byname(pdev, "dsp"); + list[0]->irq = platform_get_irq(pdev, 0); } #endif #if defined(CONFIG_ARCH_OMAP2) else if (cpu_is_omap2430()) { list = omap2_mboxes; - list[0]->irq = platform_get_irq_byname(pdev, "dsp"); + list[0]->irq = platform_get_irq(pdev, 0); } else if (cpu_is_omap2420()) { list = omap2_mboxes; @@ -419,8 +364,7 @@ static int __devinit omap2_mbox_probe(struct platform_device *pdev) else if (cpu_is_omap44xx()) { list = omap4_mboxes; - list[0]->irq = list[1]->irq = - platform_get_irq_byname(pdev, "mbox"); + list[0]->irq = list[1]->irq = platform_get_irq(pdev, 0); } #endif else { diff --git a/arch/arm/mach-omap2/mcbsp.c b/arch/arm/mach-omap2/mcbsp.c index f9c9df5b5ff..565b9064a32 100644 --- a/arch/arm/mach-omap2/mcbsp.c +++ b/arch/arm/mach-omap2/mcbsp.c @@ -22,10 +22,11 @@ #include <plat/dma.h> #include <plat/cpu.h> #include <plat/mcbsp.h> +#include <plat/omap_device.h> +#include <linux/pm_runtime.h> #include "control.h" - /* McBSP internal signal muxing functions */ void omap2_mcbsp1_mux_clkr_src(u8 mux) @@ -83,7 +84,7 @@ int omap2_mcbsp_set_clks_src(u8 id, u8 fck_src_id) return -EINVAL; } - clk_disable(mcbsp->fclk); + pm_runtime_put_sync(mcbsp->dev); r = clk_set_parent(mcbsp->fclk, fck_src); if (IS_ERR_VALUE(r)) { @@ -93,7 +94,7 @@ int omap2_mcbsp_set_clks_src(u8 id, u8 fck_src_id) return -EINVAL; } - clk_enable(mcbsp->fclk); + pm_runtime_get_sync(mcbsp->dev); clk_put(fck_src); @@ -101,196 +102,70 @@ int omap2_mcbsp_set_clks_src(u8 id, u8 fck_src_id) } EXPORT_SYMBOL(omap2_mcbsp_set_clks_src); - -/* Platform data */ - -#ifdef CONFIG_ARCH_OMAP2420 -static struct omap_mcbsp_platform_data omap2420_mcbsp_pdata[] = { +struct omap_device_pm_latency omap2_mcbsp_latency[] = { { - .phys_base = OMAP24XX_MCBSP1_BASE, - .dma_rx_sync = OMAP24XX_DMA_MCBSP1_RX, - .dma_tx_sync = OMAP24XX_DMA_MCBSP1_TX, - .rx_irq = INT_24XX_MCBSP1_IRQ_RX, - .tx_irq = INT_24XX_MCBSP1_IRQ_TX, - }, - { - .phys_base = OMAP24XX_MCBSP2_BASE, - .dma_rx_sync = OMAP24XX_DMA_MCBSP2_RX, - .dma_tx_sync = OMAP24XX_DMA_MCBSP2_TX, - .rx_irq = INT_24XX_MCBSP2_IRQ_RX, - .tx_irq = INT_24XX_MCBSP2_IRQ_TX, + .deactivate_func = omap_device_idle_hwmods, + .activate_func = omap_device_enable_hwmods, + .flags = OMAP_DEVICE_LATENCY_AUTO_ADJUST, }, }; -#define OMAP2420_MCBSP_PDATA_SZ ARRAY_SIZE(omap2420_mcbsp_pdata) -#define OMAP2420_MCBSP_REG_NUM (OMAP_MCBSP_REG_RCCR / sizeof(u32) + 1) -#else -#define omap2420_mcbsp_pdata NULL -#define OMAP2420_MCBSP_PDATA_SZ 0 -#define OMAP2420_MCBSP_REG_NUM 0 -#endif -#ifdef CONFIG_ARCH_OMAP2430 -static struct omap_mcbsp_platform_data omap2430_mcbsp_pdata[] = { - { - .phys_base = OMAP24XX_MCBSP1_BASE, - .dma_rx_sync = OMAP24XX_DMA_MCBSP1_RX, - .dma_tx_sync = OMAP24XX_DMA_MCBSP1_TX, - .rx_irq = INT_24XX_MCBSP1_IRQ_RX, - .tx_irq = INT_24XX_MCBSP1_IRQ_TX, - }, - { - .phys_base = OMAP24XX_MCBSP2_BASE, - .dma_rx_sync = OMAP24XX_DMA_MCBSP2_RX, - .dma_tx_sync = OMAP24XX_DMA_MCBSP2_TX, - .rx_irq = INT_24XX_MCBSP2_IRQ_RX, - .tx_irq = INT_24XX_MCBSP2_IRQ_TX, - }, - { - .phys_base = OMAP2430_MCBSP3_BASE, - .dma_rx_sync = OMAP24XX_DMA_MCBSP3_RX, - .dma_tx_sync = OMAP24XX_DMA_MCBSP3_TX, - .rx_irq = INT_24XX_MCBSP3_IRQ_RX, - .tx_irq = INT_24XX_MCBSP3_IRQ_TX, - }, - { - .phys_base = OMAP2430_MCBSP4_BASE, - .dma_rx_sync = OMAP24XX_DMA_MCBSP4_RX, - .dma_tx_sync = OMAP24XX_DMA_MCBSP4_TX, - .rx_irq = INT_24XX_MCBSP4_IRQ_RX, - .tx_irq = INT_24XX_MCBSP4_IRQ_TX, - }, - { - .phys_base = OMAP2430_MCBSP5_BASE, - .dma_rx_sync = OMAP24XX_DMA_MCBSP5_RX, - .dma_tx_sync = OMAP24XX_DMA_MCBSP5_TX, - .rx_irq = INT_24XX_MCBSP5_IRQ_RX, - .tx_irq = INT_24XX_MCBSP5_IRQ_TX, - }, -}; -#define OMAP2430_MCBSP_PDATA_SZ ARRAY_SIZE(omap2430_mcbsp_pdata) -#define OMAP2430_MCBSP_REG_NUM (OMAP_MCBSP_REG_RCCR / sizeof(u32) + 1) -#else -#define omap2430_mcbsp_pdata NULL -#define OMAP2430_MCBSP_PDATA_SZ 0 -#define OMAP2430_MCBSP_REG_NUM 0 -#endif +static int omap_init_mcbsp(struct omap_hwmod *oh, void *unused) +{ + int id, count = 1; + char *name = "omap-mcbsp"; + struct omap_hwmod *oh_device[2]; + struct omap_mcbsp_platform_data *pdata = NULL; + struct omap_device *od; -#ifdef CONFIG_ARCH_OMAP3 -static struct omap_mcbsp_platform_data omap34xx_mcbsp_pdata[] = { - { - .phys_base = OMAP34XX_MCBSP1_BASE, - .dma_rx_sync = OMAP24XX_DMA_MCBSP1_RX, - .dma_tx_sync = OMAP24XX_DMA_MCBSP1_TX, - .rx_irq = INT_24XX_MCBSP1_IRQ_RX, - .tx_irq = INT_24XX_MCBSP1_IRQ_TX, - .buffer_size = 0x80, /* The FIFO has 128 locations */ - }, - { - .phys_base = OMAP34XX_MCBSP2_BASE, - .phys_base_st = OMAP34XX_MCBSP2_ST_BASE, - .dma_rx_sync = OMAP24XX_DMA_MCBSP2_RX, - .dma_tx_sync = OMAP24XX_DMA_MCBSP2_TX, - .rx_irq = INT_24XX_MCBSP2_IRQ_RX, - .tx_irq = INT_24XX_MCBSP2_IRQ_TX, - .buffer_size = 0x500, /* The FIFO has 1024 + 256 locations */ - }, - { - .phys_base = OMAP34XX_MCBSP3_BASE, - .phys_base_st = OMAP34XX_MCBSP3_ST_BASE, - .dma_rx_sync = OMAP24XX_DMA_MCBSP3_RX, - .dma_tx_sync = OMAP24XX_DMA_MCBSP3_TX, - .rx_irq = INT_24XX_MCBSP3_IRQ_RX, - .tx_irq = INT_24XX_MCBSP3_IRQ_TX, - .buffer_size = 0x80, /* The FIFO has 128 locations */ - }, - { - .phys_base = OMAP34XX_MCBSP4_BASE, - .dma_rx_sync = OMAP24XX_DMA_MCBSP4_RX, - .dma_tx_sync = OMAP24XX_DMA_MCBSP4_TX, - .rx_irq = INT_24XX_MCBSP4_IRQ_RX, - .tx_irq = INT_24XX_MCBSP4_IRQ_TX, - .buffer_size = 0x80, /* The FIFO has 128 locations */ - }, - { - .phys_base = OMAP34XX_MCBSP5_BASE, - .dma_rx_sync = OMAP24XX_DMA_MCBSP5_RX, - .dma_tx_sync = OMAP24XX_DMA_MCBSP5_TX, - .rx_irq = INT_24XX_MCBSP5_IRQ_RX, - .tx_irq = INT_24XX_MCBSP5_IRQ_TX, - .buffer_size = 0x80, /* The FIFO has 128 locations */ - }, -}; -#define OMAP34XX_MCBSP_PDATA_SZ ARRAY_SIZE(omap34xx_mcbsp_pdata) -#define OMAP34XX_MCBSP_REG_NUM (OMAP_MCBSP_REG_RCCR / sizeof(u32) + 1) -#else -#define omap34xx_mcbsp_pdata NULL -#define OMAP34XX_MCBSP_PDATA_SZ 0 -#define OMAP34XX_MCBSP_REG_NUM 0 -#endif + sscanf(oh->name, "mcbsp%d", &id); -static struct omap_mcbsp_platform_data omap44xx_mcbsp_pdata[] = { - { - .phys_base = OMAP44XX_MCBSP1_BASE, - .dma_rx_sync = OMAP44XX_DMA_MCBSP1_RX, - .dma_tx_sync = OMAP44XX_DMA_MCBSP1_TX, - .tx_irq = OMAP44XX_IRQ_MCBSP1, - }, - { - .phys_base = OMAP44XX_MCBSP2_BASE, - .dma_rx_sync = OMAP44XX_DMA_MCBSP2_RX, - .dma_tx_sync = OMAP44XX_DMA_MCBSP2_TX, - .tx_irq = OMAP44XX_IRQ_MCBSP2, - }, - { - .phys_base = OMAP44XX_MCBSP3_BASE, - .dma_rx_sync = OMAP44XX_DMA_MCBSP3_RX, - .dma_tx_sync = OMAP44XX_DMA_MCBSP3_TX, - .tx_irq = OMAP44XX_IRQ_MCBSP3, - }, - { - .phys_base = OMAP44XX_MCBSP4_BASE, - .dma_rx_sync = OMAP44XX_DMA_MCBSP4_RX, - .dma_tx_sync = OMAP44XX_DMA_MCBSP4_TX, - .tx_irq = OMAP44XX_IRQ_MCBSP4, - }, -}; -#define OMAP44XX_MCBSP_PDATA_SZ ARRAY_SIZE(omap44xx_mcbsp_pdata) -#define OMAP44XX_MCBSP_REG_NUM (OMAP_MCBSP_REG_RCCR / sizeof(u32) + 1) + pdata = kzalloc(sizeof(struct omap_mcbsp_platform_data), GFP_KERNEL); + if (!pdata) { + pr_err("%s: No memory for mcbsp\n", __func__); + return -ENOMEM; + } + + pdata->mcbsp_config_type = oh->class->rev; + + if (oh->class->rev == MCBSP_CONFIG_TYPE3) { + if (id == 2) + /* The FIFO has 1024 + 256 locations */ + pdata->buffer_size = 0x500; + else + /* The FIFO has 128 locations */ + pdata->buffer_size = 0x80; + } + + oh_device[0] = oh; + + if (oh->dev_attr) { + oh_device[1] = omap_hwmod_lookup(( + (struct omap_mcbsp_dev_attr *)(oh->dev_attr))->sidetone); + count++; + } + od = omap_device_build_ss(name, id, oh_device, count, pdata, + sizeof(*pdata), omap2_mcbsp_latency, + ARRAY_SIZE(omap2_mcbsp_latency), false); + kfree(pdata); + if (IS_ERR(od)) { + pr_err("%s: Cant build omap_device for %s:%s.\n", __func__, + name, oh->name); + return PTR_ERR(od); + } + omap_mcbsp_count++; + return 0; +} static int __init omap2_mcbsp_init(void) { - if (cpu_is_omap2420()) { - omap_mcbsp_count = OMAP2420_MCBSP_PDATA_SZ; - omap_mcbsp_cache_size = OMAP2420_MCBSP_REG_NUM * sizeof(u16); - } else if (cpu_is_omap2430()) { - omap_mcbsp_count = OMAP2430_MCBSP_PDATA_SZ; - omap_mcbsp_cache_size = OMAP2430_MCBSP_REG_NUM * sizeof(u32); - } else if (cpu_is_omap34xx()) { - omap_mcbsp_count = OMAP34XX_MCBSP_PDATA_SZ; - omap_mcbsp_cache_size = OMAP34XX_MCBSP_REG_NUM * sizeof(u32); - } else if (cpu_is_omap44xx()) { - omap_mcbsp_count = OMAP44XX_MCBSP_PDATA_SZ; - omap_mcbsp_cache_size = OMAP44XX_MCBSP_REG_NUM * sizeof(u32); - } + omap_hwmod_for_each_by_class("mcbsp", omap_init_mcbsp, NULL); mcbsp_ptr = kzalloc(omap_mcbsp_count * sizeof(struct omap_mcbsp *), GFP_KERNEL); if (!mcbsp_ptr) return -ENOMEM; - if (cpu_is_omap2420()) - omap_mcbsp_register_board_cfg(omap2420_mcbsp_pdata, - OMAP2420_MCBSP_PDATA_SZ); - if (cpu_is_omap2430()) - omap_mcbsp_register_board_cfg(omap2430_mcbsp_pdata, - OMAP2430_MCBSP_PDATA_SZ); - if (cpu_is_omap34xx()) - omap_mcbsp_register_board_cfg(omap34xx_mcbsp_pdata, - OMAP34XX_MCBSP_PDATA_SZ); - if (cpu_is_omap44xx()) - omap_mcbsp_register_board_cfg(omap44xx_mcbsp_pdata, - OMAP44XX_MCBSP_PDATA_SZ); - return omap_mcbsp_init(); } arch_initcall(omap2_mcbsp_init); diff --git a/arch/arm/mach-omap2/mux.c b/arch/arm/mach-omap2/mux.c index 6c84659cf84..bb043cbb388 100644 --- a/arch/arm/mach-omap2/mux.c +++ b/arch/arm/mach-omap2/mux.c @@ -258,7 +258,7 @@ struct omap_hwmod_mux_info * __init omap_hwmod_mux_init(struct omap_device_pad *bpads, int nr_pads) { struct omap_hwmod_mux_info *hmux; - int i; + int i, nr_pads_dynamic = 0; if (!bpads || nr_pads < 1) return NULL; @@ -302,9 +302,40 @@ omap_hwmod_mux_init(struct omap_device_pad *bpads, int nr_pads) pad->enable = bpad->enable; pad->idle = bpad->idle; pad->off = bpad->off; + + if (pad->flags & OMAP_DEVICE_PAD_REMUX) + nr_pads_dynamic++; + pr_debug("%s: Initialized %s\n", __func__, pad->name); } + if (!nr_pads_dynamic) + return hmux; + + /* + * Add pads that need dynamic muxing into a separate list + */ + + hmux->nr_pads_dynamic = nr_pads_dynamic; + hmux->pads_dynamic = kzalloc(sizeof(struct omap_device_pad *) * + nr_pads_dynamic, GFP_KERNEL); + if (!hmux->pads_dynamic) { + pr_err("%s: Could not allocate dynamic pads\n", __func__); + return hmux; + } + + nr_pads_dynamic = 0; + for (i = 0; i < hmux->nr_pads; i++) { + struct omap_device_pad *pad = &hmux->pads[i]; + + if (pad->flags & OMAP_DEVICE_PAD_REMUX) { + pr_debug("%s: pad %s tagged dynamic\n", + __func__, pad->name); + hmux->pads_dynamic[nr_pads_dynamic] = pad; + nr_pads_dynamic++; + } + } + return hmux; err3: @@ -322,6 +353,36 @@ void omap_hwmod_mux(struct omap_hwmod_mux_info *hmux, u8 state) { int i; + /* Runtime idling of dynamic pads */ + if (state == _HWMOD_STATE_IDLE && hmux->enabled) { + for (i = 0; i < hmux->nr_pads_dynamic; i++) { + struct omap_device_pad *pad = hmux->pads_dynamic[i]; + int val = -EINVAL; + + val = pad->idle; + omap_mux_write(pad->partition, val, + pad->mux->reg_offset); + } + + return; + } + + /* Runtime enabling of dynamic pads */ + if ((state == _HWMOD_STATE_ENABLED) && hmux->pads_dynamic + && hmux->enabled) { + for (i = 0; i < hmux->nr_pads_dynamic; i++) { + struct omap_device_pad *pad = hmux->pads_dynamic[i]; + int val = -EINVAL; + + val = pad->enable; + omap_mux_write(pad->partition, val, + pad->mux->reg_offset); + } + + return; + } + + /* Enabling or disabling of all pads */ for (i = 0; i < hmux->nr_pads; i++) { struct omap_device_pad *pad = &hmux->pads[i]; int flags, val = -EINVAL; @@ -330,31 +391,22 @@ void omap_hwmod_mux(struct omap_hwmod_mux_info *hmux, u8 state) switch (state) { case _HWMOD_STATE_ENABLED: - if (flags & OMAP_DEVICE_PAD_ENABLED) - break; - flags |= OMAP_DEVICE_PAD_ENABLED; val = pad->enable; pr_debug("%s: Enabling %s %x\n", __func__, pad->name, val); break; - case _HWMOD_STATE_IDLE: - if (!(flags & OMAP_DEVICE_PAD_REMUX)) - break; - flags &= ~OMAP_DEVICE_PAD_ENABLED; - val = pad->idle; - pr_debug("%s: Idling %s %x\n", __func__, - pad->name, val); - break; case _HWMOD_STATE_DISABLED: - default: /* Use safe mode unless OMAP_DEVICE_PAD_REMUX */ if (flags & OMAP_DEVICE_PAD_REMUX) val = pad->off; else val = OMAP_MUX_MODE7; - flags &= ~OMAP_DEVICE_PAD_ENABLED; pr_debug("%s: Disabling %s %x\n", __func__, pad->name, val); + break; + default: + /* Nothing to be done */ + break; }; if (val >= 0) { @@ -363,6 +415,11 @@ void omap_hwmod_mux(struct omap_hwmod_mux_info *hmux, u8 state) pad->flags = flags; } } + + if (state == _HWMOD_STATE_ENABLED) + hmux->enabled = true; + else + hmux->enabled = false; } #ifdef CONFIG_DEBUG_FS diff --git a/arch/arm/mach-omap2/mux.h b/arch/arm/mach-omap2/mux.h index a4ab17a737a..137f321c029 100644 --- a/arch/arm/mach-omap2/mux.h +++ b/arch/arm/mach-omap2/mux.h @@ -159,7 +159,6 @@ struct omap_board_mux { u16 value; }; -#define OMAP_DEVICE_PAD_ENABLED BIT(7) /* Not needed for board-*.c */ #define OMAP_DEVICE_PAD_REMUX BIT(1) /* Dynamically remux a pad, needs enable, idle and off values */ @@ -187,6 +186,12 @@ struct omap_device_pad { struct omap_hwmod_mux_info; +#define OMAP_MUX_STATIC(signal, mode) \ +{ \ + .name = (signal), \ + .enable = (mode), \ +} + #if defined(CONFIG_OMAP_MUX) /** diff --git a/arch/arm/mach-omap2/mux44xx.c b/arch/arm/mach-omap2/mux44xx.c index c322e7bdaa1..9a66445112a 100644 --- a/arch/arm/mach-omap2/mux44xx.c +++ b/arch/arm/mach-omap2/mux44xx.c @@ -755,25 +755,9 @@ static struct omap_ball __initdata omap4_core_cbl_ball[] = { #endif /* - * Superset of all mux modes for omap4 ES2.0 + * Signals different on ES2.0 compared to superset */ -static struct omap_mux __initdata omap4_es2_core_muxmodes[] = { - _OMAP4_MUXENTRY(GPMC_AD0, 0, "gpmc_ad0", "sdmmc2_dat0", NULL, NULL, - NULL, NULL, NULL, NULL), - _OMAP4_MUXENTRY(GPMC_AD1, 0, "gpmc_ad1", "sdmmc2_dat1", NULL, NULL, - NULL, NULL, NULL, NULL), - _OMAP4_MUXENTRY(GPMC_AD2, 0, "gpmc_ad2", "sdmmc2_dat2", NULL, NULL, - NULL, NULL, NULL, NULL), - _OMAP4_MUXENTRY(GPMC_AD3, 0, "gpmc_ad3", "sdmmc2_dat3", NULL, NULL, - NULL, NULL, NULL, NULL), - _OMAP4_MUXENTRY(GPMC_AD4, 0, "gpmc_ad4", "sdmmc2_dat4", - "sdmmc2_dir_dat0", NULL, NULL, NULL, NULL, NULL), - _OMAP4_MUXENTRY(GPMC_AD5, 0, "gpmc_ad5", "sdmmc2_dat5", - "sdmmc2_dir_dat1", NULL, NULL, NULL, NULL, NULL), - _OMAP4_MUXENTRY(GPMC_AD6, 0, "gpmc_ad6", "sdmmc2_dat6", - "sdmmc2_dir_cmd", NULL, NULL, NULL, NULL, NULL), - _OMAP4_MUXENTRY(GPMC_AD7, 0, "gpmc_ad7", "sdmmc2_dat7", - "sdmmc2_clk_fdbk", NULL, NULL, NULL, NULL, NULL), +static struct omap_mux __initdata omap4_es2_core_subset[] = { _OMAP4_MUXENTRY(GPMC_AD8, 32, "gpmc_ad8", "kpd_row0", "c2c_data15", "gpio_32", NULL, "sdmmc1_dat0", NULL, NULL), _OMAP4_MUXENTRY(GPMC_AD9, 33, "gpmc_ad9", "kpd_row1", "c2c_data14", @@ -792,52 +776,15 @@ static struct omap_mux __initdata omap4_es2_core_muxmodes[] = { "gpio_39", NULL, "sdmmc1_dat7", NULL, NULL), _OMAP4_MUXENTRY(GPMC_A16, 40, "gpmc_a16", "kpd_row4", "c2c_datain0", "gpio_40", "venc_656_data0", NULL, NULL, "safe_mode"), - _OMAP4_MUXENTRY(GPMC_A17, 41, "gpmc_a17", "kpd_row5", "c2c_datain1", - "gpio_41", "venc_656_data1", NULL, NULL, "safe_mode"), - _OMAP4_MUXENTRY(GPMC_A18, 42, "gpmc_a18", "kpd_row6", "c2c_datain2", - "gpio_42", "venc_656_data2", NULL, NULL, "safe_mode"), - _OMAP4_MUXENTRY(GPMC_A19, 43, "gpmc_a19", "kpd_row7", "c2c_datain3", - "gpio_43", "venc_656_data3", NULL, NULL, "safe_mode"), - _OMAP4_MUXENTRY(GPMC_A20, 44, "gpmc_a20", "kpd_col4", "c2c_datain4", - "gpio_44", "venc_656_data4", NULL, NULL, "safe_mode"), - _OMAP4_MUXENTRY(GPMC_A21, 45, "gpmc_a21", "kpd_col5", "c2c_datain5", - "gpio_45", "venc_656_data5", NULL, NULL, "safe_mode"), - _OMAP4_MUXENTRY(GPMC_A22, 46, "gpmc_a22", "kpd_col6", "c2c_datain6", - "gpio_46", "venc_656_data6", NULL, NULL, "safe_mode"), - _OMAP4_MUXENTRY(GPMC_A23, 47, "gpmc_a23", "kpd_col7", "c2c_datain7", - "gpio_47", "venc_656_data7", NULL, NULL, "safe_mode"), _OMAP4_MUXENTRY(GPMC_A24, 48, "gpmc_a24", "kpd_col8", "c2c_clkout0", "gpio_48", NULL, NULL, NULL, "safe_mode"), - _OMAP4_MUXENTRY(GPMC_A25, 49, "gpmc_a25", NULL, "c2c_clkout1", - "gpio_49", NULL, NULL, NULL, "safe_mode"), - _OMAP4_MUXENTRY(GPMC_NCS0, 50, "gpmc_ncs0", NULL, NULL, "gpio_50", - "sys_ndmareq0", NULL, NULL, NULL), - _OMAP4_MUXENTRY(GPMC_NCS1, 51, "gpmc_ncs1", NULL, "c2c_dataout6", - "gpio_51", NULL, NULL, NULL, "safe_mode"), _OMAP4_MUXENTRY(GPMC_NCS2, 52, "gpmc_ncs2", "kpd_row8", "c2c_dataout7", "gpio_52", NULL, NULL, NULL, "safe_mode"), - _OMAP4_MUXENTRY(GPMC_NCS3, 53, "gpmc_ncs3", "gpmc_dir", - "c2c_dataout4", "gpio_53", NULL, NULL, NULL, - "safe_mode"), - _OMAP4_MUXENTRY(GPMC_NWP, 54, "gpmc_nwp", "dsi1_te0", NULL, "gpio_54", - "sys_ndmareq1", NULL, NULL, NULL), _OMAP4_MUXENTRY(GPMC_CLK, 55, "gpmc_clk", NULL, NULL, "gpio_55", "sys_ndmareq2", "sdmmc1_cmd", NULL, NULL), _OMAP4_MUXENTRY(GPMC_NADV_ALE, 56, "gpmc_nadv_ale", "dsi1_te1", NULL, "gpio_56", "sys_ndmareq3", "sdmmc1_clk", NULL, NULL), - _OMAP4_MUXENTRY(GPMC_NOE, 0, "gpmc_noe", "sdmmc2_clk", NULL, NULL, - NULL, NULL, NULL, NULL), - _OMAP4_MUXENTRY(GPMC_NWE, 0, "gpmc_nwe", "sdmmc2_cmd", NULL, NULL, - NULL, NULL, NULL, NULL), - _OMAP4_MUXENTRY(GPMC_NBE0_CLE, 59, "gpmc_nbe0_cle", "dsi2_te0", NULL, - "gpio_59", NULL, NULL, NULL, NULL), - _OMAP4_MUXENTRY(GPMC_NBE1, 60, "gpmc_nbe1", NULL, "c2c_dataout5", - "gpio_60", NULL, NULL, NULL, "safe_mode"), - _OMAP4_MUXENTRY(GPMC_WAIT0, 61, "gpmc_wait0", "dsi2_te1", NULL, - "gpio_61", NULL, NULL, NULL, NULL), - _OMAP4_MUXENTRY(GPMC_WAIT1, 62, "gpmc_wait1", NULL, "c2c_dataout2", - "gpio_62", NULL, NULL, NULL, "safe_mode"), _OMAP4_MUXENTRY(GPMC_WAIT2, 100, "gpmc_wait2", "usbc1_icusb_txen", "c2c_dataout3", "gpio_100", "sys_ndmareq0", NULL, NULL, "safe_mode"), @@ -851,62 +798,6 @@ static struct omap_mux __initdata omap4_es2_core_muxmodes[] = { _OMAP4_MUXENTRY(GPMC_NCS7, 104, "gpmc_ncs7", "dsi2_te1", "c2c_dataout1", "gpio_104", NULL, NULL, NULL, "safe_mode"), - _OMAP4_MUXENTRY(HDMI_HPD, 63, "hdmi_hpd", NULL, NULL, "gpio_63", NULL, - NULL, NULL, "safe_mode"), - _OMAP4_MUXENTRY(HDMI_CEC, 64, "hdmi_cec", NULL, NULL, "gpio_64", NULL, - NULL, NULL, "safe_mode"), - _OMAP4_MUXENTRY(HDMI_DDC_SCL, 65, "hdmi_ddc_scl", NULL, NULL, - "gpio_65", NULL, NULL, NULL, "safe_mode"), - _OMAP4_MUXENTRY(HDMI_DDC_SDA, 66, "hdmi_ddc_sda", NULL, NULL, - "gpio_66", NULL, NULL, NULL, "safe_mode"), - _OMAP4_MUXENTRY(CSI21_DX0, 0, "csi21_dx0", NULL, NULL, "gpi_67", NULL, - NULL, NULL, "safe_mode"), - _OMAP4_MUXENTRY(CSI21_DY0, 0, "csi21_dy0", NULL, NULL, "gpi_68", NULL, - NULL, NULL, "safe_mode"), - _OMAP4_MUXENTRY(CSI21_DX1, 0, "csi21_dx1", NULL, NULL, "gpi_69", NULL, - NULL, NULL, "safe_mode"), - _OMAP4_MUXENTRY(CSI21_DY1, 0, "csi21_dy1", NULL, NULL, "gpi_70", NULL, - NULL, NULL, "safe_mode"), - _OMAP4_MUXENTRY(CSI21_DX2, 0, "csi21_dx2", NULL, NULL, "gpi_71", NULL, - NULL, NULL, "safe_mode"), - _OMAP4_MUXENTRY(CSI21_DY2, 0, "csi21_dy2", NULL, NULL, "gpi_72", NULL, - NULL, NULL, "safe_mode"), - _OMAP4_MUXENTRY(CSI21_DX3, 0, "csi21_dx3", NULL, NULL, "gpi_73", NULL, - NULL, NULL, "safe_mode"), - _OMAP4_MUXENTRY(CSI21_DY3, 0, "csi21_dy3", NULL, NULL, "gpi_74", NULL, - NULL, NULL, "safe_mode"), - _OMAP4_MUXENTRY(CSI21_DX4, 0, "csi21_dx4", NULL, NULL, "gpi_75", NULL, - NULL, NULL, "safe_mode"), - _OMAP4_MUXENTRY(CSI21_DY4, 0, "csi21_dy4", NULL, NULL, "gpi_76", NULL, - NULL, NULL, "safe_mode"), - _OMAP4_MUXENTRY(CSI22_DX0, 0, "csi22_dx0", NULL, NULL, "gpi_77", NULL, - NULL, NULL, "safe_mode"), - _OMAP4_MUXENTRY(CSI22_DY0, 0, "csi22_dy0", NULL, NULL, "gpi_78", NULL, - NULL, NULL, "safe_mode"), - _OMAP4_MUXENTRY(CSI22_DX1, 0, "csi22_dx1", NULL, NULL, "gpi_79", NULL, - NULL, NULL, "safe_mode"), - _OMAP4_MUXENTRY(CSI22_DY1, 0, "csi22_dy1", NULL, NULL, "gpi_80", NULL, - NULL, NULL, "safe_mode"), - _OMAP4_MUXENTRY(CAM_SHUTTER, 81, "cam_shutter", NULL, NULL, "gpio_81", - NULL, NULL, NULL, "safe_mode"), - _OMAP4_MUXENTRY(CAM_STROBE, 82, "cam_strobe", NULL, NULL, "gpio_82", - NULL, NULL, NULL, "safe_mode"), - _OMAP4_MUXENTRY(CAM_GLOBALRESET, 83, "cam_globalreset", NULL, NULL, - "gpio_83", NULL, NULL, NULL, "safe_mode"), - _OMAP4_MUXENTRY(USBB1_ULPITLL_CLK, 84, "usbb1_ulpitll_clk", - "hsi1_cawake", NULL, "gpio_84", "usbb1_ulpiphy_clk", - NULL, "hw_dbg20", "safe_mode"), - _OMAP4_MUXENTRY(USBB1_ULPITLL_STP, 85, "usbb1_ulpitll_stp", - "hsi1_cadata", "mcbsp4_clkr", "gpio_85", - "usbb1_ulpiphy_stp", "usbb1_mm_rxdp", "hw_dbg21", - "safe_mode"), - _OMAP4_MUXENTRY(USBB1_ULPITLL_DIR, 86, "usbb1_ulpitll_dir", - "hsi1_caflag", "mcbsp4_fsr", "gpio_86", - "usbb1_ulpiphy_dir", NULL, "hw_dbg22", "safe_mode"), - _OMAP4_MUXENTRY(USBB1_ULPITLL_NXT, 87, "usbb1_ulpitll_nxt", - "hsi1_acready", "mcbsp4_fsx", "gpio_87", - "usbb1_ulpiphy_nxt", "usbb1_mm_rxdm", "hw_dbg23", - "safe_mode"), _OMAP4_MUXENTRY(USBB1_ULPITLL_DAT0, 88, "usbb1_ulpitll_dat0", "hsi1_acwake", "mcbsp4_clkx", "gpio_88", "usbb1_ulpiphy_dat0", "usbb1_mm_txen", "hw_dbg24", @@ -922,84 +813,6 @@ static struct omap_mux __initdata omap4_es2_core_muxmodes[] = { _OMAP4_MUXENTRY(USBB1_ULPITLL_DAT3, 91, "usbb1_ulpitll_dat3", "hsi1_caready", NULL, "gpio_91", "usbb1_ulpiphy_dat3", "usbb1_mm_rxrcv", "hw_dbg27", "safe_mode"), - _OMAP4_MUXENTRY(USBB1_ULPITLL_DAT4, 92, "usbb1_ulpitll_dat4", - "dmtimer8_pwm_evt", "abe_mcbsp3_dr", "gpio_92", - "usbb1_ulpiphy_dat4", NULL, "hw_dbg28", "safe_mode"), - _OMAP4_MUXENTRY(USBB1_ULPITLL_DAT5, 93, "usbb1_ulpitll_dat5", - "dmtimer9_pwm_evt", "abe_mcbsp3_dx", "gpio_93", - "usbb1_ulpiphy_dat5", NULL, "hw_dbg29", "safe_mode"), - _OMAP4_MUXENTRY(USBB1_ULPITLL_DAT6, 94, "usbb1_ulpitll_dat6", - "dmtimer10_pwm_evt", "abe_mcbsp3_clkx", "gpio_94", - "usbb1_ulpiphy_dat6", "abe_dmic_din3", "hw_dbg30", - "safe_mode"), - _OMAP4_MUXENTRY(USBB1_ULPITLL_DAT7, 95, "usbb1_ulpitll_dat7", - "dmtimer11_pwm_evt", "abe_mcbsp3_fsx", "gpio_95", - "usbb1_ulpiphy_dat7", "abe_dmic_clk3", "hw_dbg31", - "safe_mode"), - _OMAP4_MUXENTRY(USBB1_HSIC_DATA, 96, "usbb1_hsic_data", NULL, NULL, - "gpio_96", NULL, NULL, NULL, "safe_mode"), - _OMAP4_MUXENTRY(USBB1_HSIC_STROBE, 97, "usbb1_hsic_strobe", NULL, - NULL, "gpio_97", NULL, NULL, NULL, "safe_mode"), - _OMAP4_MUXENTRY(USBC1_ICUSB_DP, 98, "usbc1_icusb_dp", NULL, NULL, - "gpio_98", NULL, NULL, NULL, "safe_mode"), - _OMAP4_MUXENTRY(USBC1_ICUSB_DM, 99, "usbc1_icusb_dm", NULL, NULL, - "gpio_99", NULL, NULL, NULL, "safe_mode"), - _OMAP4_MUXENTRY(SDMMC1_CLK, 100, "sdmmc1_clk", NULL, "dpm_emu19", - "gpio_100", NULL, NULL, NULL, "safe_mode"), - _OMAP4_MUXENTRY(SDMMC1_CMD, 101, "sdmmc1_cmd", NULL, "uart1_rx", - "gpio_101", NULL, NULL, NULL, "safe_mode"), - _OMAP4_MUXENTRY(SDMMC1_DAT0, 102, "sdmmc1_dat0", NULL, "dpm_emu18", - "gpio_102", NULL, NULL, NULL, "safe_mode"), - _OMAP4_MUXENTRY(SDMMC1_DAT1, 103, "sdmmc1_dat1", NULL, "dpm_emu17", - "gpio_103", NULL, NULL, NULL, "safe_mode"), - _OMAP4_MUXENTRY(SDMMC1_DAT2, 104, "sdmmc1_dat2", NULL, "dpm_emu16", - "gpio_104", "jtag_tms_tmsc", NULL, NULL, "safe_mode"), - _OMAP4_MUXENTRY(SDMMC1_DAT3, 105, "sdmmc1_dat3", NULL, "dpm_emu15", - "gpio_105", "jtag_tck", NULL, NULL, "safe_mode"), - _OMAP4_MUXENTRY(SDMMC1_DAT4, 106, "sdmmc1_dat4", NULL, NULL, - "gpio_106", NULL, NULL, NULL, "safe_mode"), - _OMAP4_MUXENTRY(SDMMC1_DAT5, 107, "sdmmc1_dat5", NULL, NULL, - "gpio_107", NULL, NULL, NULL, "safe_mode"), - _OMAP4_MUXENTRY(SDMMC1_DAT6, 108, "sdmmc1_dat6", NULL, NULL, - "gpio_108", NULL, NULL, NULL, "safe_mode"), - _OMAP4_MUXENTRY(SDMMC1_DAT7, 109, "sdmmc1_dat7", NULL, NULL, - "gpio_109", NULL, NULL, NULL, "safe_mode"), - _OMAP4_MUXENTRY(ABE_MCBSP2_CLKX, 110, "abe_mcbsp2_clkx", "mcspi2_clk", - "abe_mcasp_ahclkx", "gpio_110", "usbb2_mm_rxdm", - NULL, NULL, "safe_mode"), - _OMAP4_MUXENTRY(ABE_MCBSP2_DR, 111, "abe_mcbsp2_dr", "mcspi2_somi", - "abe_mcasp_axr", "gpio_111", "usbb2_mm_rxdp", NULL, - NULL, "safe_mode"), - _OMAP4_MUXENTRY(ABE_MCBSP2_DX, 112, "abe_mcbsp2_dx", "mcspi2_simo", - "abe_mcasp_amute", "gpio_112", "usbb2_mm_rxrcv", NULL, - NULL, "safe_mode"), - _OMAP4_MUXENTRY(ABE_MCBSP2_FSX, 113, "abe_mcbsp2_fsx", "mcspi2_cs0", - "abe_mcasp_afsx", "gpio_113", "usbb2_mm_txen", NULL, - NULL, "safe_mode"), - _OMAP4_MUXENTRY(ABE_MCBSP1_CLKX, 114, "abe_mcbsp1_clkx", - "abe_slimbus1_clock", NULL, "gpio_114", NULL, NULL, - NULL, "safe_mode"), - _OMAP4_MUXENTRY(ABE_MCBSP1_DR, 115, "abe_mcbsp1_dr", - "abe_slimbus1_data", NULL, "gpio_115", NULL, NULL, - NULL, "safe_mode"), - _OMAP4_MUXENTRY(ABE_MCBSP1_DX, 116, "abe_mcbsp1_dx", "sdmmc3_dat2", - "abe_mcasp_aclkx", "gpio_116", NULL, NULL, NULL, - "safe_mode"), - _OMAP4_MUXENTRY(ABE_MCBSP1_FSX, 117, "abe_mcbsp1_fsx", "sdmmc3_dat3", - "abe_mcasp_amutein", "gpio_117", NULL, NULL, NULL, - "safe_mode"), - _OMAP4_MUXENTRY(ABE_PDM_UL_DATA, 0, "abe_pdm_ul_data", - "abe_mcbsp3_dr", NULL, NULL, NULL, NULL, NULL, - "safe_mode"), - _OMAP4_MUXENTRY(ABE_PDM_DL_DATA, 0, "abe_pdm_dl_data", - "abe_mcbsp3_dx", NULL, NULL, NULL, NULL, NULL, - "safe_mode"), - _OMAP4_MUXENTRY(ABE_PDM_FRAME, 0, "abe_pdm_frame", "abe_mcbsp3_clkx", - NULL, NULL, NULL, NULL, NULL, "safe_mode"), - _OMAP4_MUXENTRY(ABE_PDM_LB_CLK, 0, "abe_pdm_lb_clk", "abe_mcbsp3_fsx", - NULL, NULL, NULL, NULL, NULL, "safe_mode"), - _OMAP4_MUXENTRY(ABE_CLKS, 118, "abe_clks", NULL, NULL, "gpio_118", - NULL, NULL, NULL, "safe_mode"), _OMAP4_MUXENTRY(ABE_DMIC_CLK1, 119, "abe_dmic_clk1", NULL, NULL, "gpio_119", "usbb2_mm_txse0", "uart4_cts", NULL, "safe_mode"), @@ -1012,58 +825,6 @@ static struct omap_mux __initdata omap4_es2_core_muxmodes[] = { _OMAP4_MUXENTRY(ABE_DMIC_DIN3, 122, "abe_dmic_din3", "slimbus2_data", "abe_dmic_clk2", "gpio_122", NULL, "dmtimer9_pwm_evt", NULL, "safe_mode"), - _OMAP4_MUXENTRY(UART2_CTS, 123, "uart2_cts", "sdmmc3_clk", NULL, - "gpio_123", NULL, NULL, NULL, "safe_mode"), - _OMAP4_MUXENTRY(UART2_RTS, 124, "uart2_rts", "sdmmc3_cmd", NULL, - "gpio_124", NULL, NULL, NULL, "safe_mode"), - _OMAP4_MUXENTRY(UART2_RX, 125, "uart2_rx", "sdmmc3_dat0", NULL, - "gpio_125", NULL, NULL, NULL, "safe_mode"), - _OMAP4_MUXENTRY(UART2_TX, 126, "uart2_tx", "sdmmc3_dat1", NULL, - "gpio_126", NULL, NULL, NULL, "safe_mode"), - _OMAP4_MUXENTRY(HDQ_SIO, 127, "hdq_sio", "i2c3_sccb", "i2c2_sccb", - "gpio_127", NULL, NULL, NULL, "safe_mode"), - _OMAP4_MUXENTRY(I2C1_SCL, 0, "i2c1_scl", NULL, NULL, NULL, NULL, NULL, - NULL, NULL), - _OMAP4_MUXENTRY(I2C1_SDA, 0, "i2c1_sda", NULL, NULL, NULL, NULL, NULL, - NULL, NULL), - _OMAP4_MUXENTRY(I2C2_SCL, 128, "i2c2_scl", "uart1_rx", NULL, - "gpio_128", NULL, NULL, NULL, "safe_mode"), - _OMAP4_MUXENTRY(I2C2_SDA, 129, "i2c2_sda", "uart1_tx", NULL, - "gpio_129", NULL, NULL, NULL, "safe_mode"), - _OMAP4_MUXENTRY(I2C3_SCL, 130, "i2c3_scl", NULL, NULL, "gpio_130", - NULL, NULL, NULL, "safe_mode"), - _OMAP4_MUXENTRY(I2C3_SDA, 131, "i2c3_sda", NULL, NULL, "gpio_131", - NULL, NULL, NULL, "safe_mode"), - _OMAP4_MUXENTRY(I2C4_SCL, 132, "i2c4_scl", NULL, NULL, "gpio_132", - NULL, NULL, NULL, "safe_mode"), - _OMAP4_MUXENTRY(I2C4_SDA, 133, "i2c4_sda", NULL, NULL, "gpio_133", - NULL, NULL, NULL, "safe_mode"), - _OMAP4_MUXENTRY(MCSPI1_CLK, 134, "mcspi1_clk", NULL, NULL, "gpio_134", - NULL, NULL, NULL, "safe_mode"), - _OMAP4_MUXENTRY(MCSPI1_SOMI, 135, "mcspi1_somi", NULL, NULL, - "gpio_135", NULL, NULL, NULL, "safe_mode"), - _OMAP4_MUXENTRY(MCSPI1_SIMO, 136, "mcspi1_simo", NULL, NULL, - "gpio_136", NULL, NULL, NULL, "safe_mode"), - _OMAP4_MUXENTRY(MCSPI1_CS0, 137, "mcspi1_cs0", NULL, NULL, "gpio_137", - NULL, NULL, NULL, "safe_mode"), - _OMAP4_MUXENTRY(MCSPI1_CS1, 138, "mcspi1_cs1", "uart1_rx", NULL, - "gpio_138", NULL, NULL, NULL, "safe_mode"), - _OMAP4_MUXENTRY(MCSPI1_CS2, 139, "mcspi1_cs2", "uart1_cts", - "slimbus2_clock", "gpio_139", NULL, NULL, NULL, - "safe_mode"), - _OMAP4_MUXENTRY(MCSPI1_CS3, 140, "mcspi1_cs3", "uart1_rts", - "slimbus2_data", "gpio_140", NULL, NULL, NULL, - "safe_mode"), - _OMAP4_MUXENTRY(UART3_CTS_RCTX, 141, "uart3_cts_rctx", "uart1_tx", - NULL, "gpio_141", NULL, NULL, NULL, "safe_mode"), - _OMAP4_MUXENTRY(UART3_RTS_SD, 142, "uart3_rts_sd", NULL, NULL, - "gpio_142", NULL, NULL, NULL, "safe_mode"), - _OMAP4_MUXENTRY(UART3_RX_IRRX, 143, "uart3_rx_irrx", - "dmtimer8_pwm_evt", NULL, "gpio_143", NULL, NULL, - NULL, "safe_mode"), - _OMAP4_MUXENTRY(UART3_TX_IRTX, 144, "uart3_tx_irtx", - "dmtimer9_pwm_evt", NULL, "gpio_144", NULL, NULL, - NULL, "safe_mode"), _OMAP4_MUXENTRY(SDMMC5_CLK, 145, "sdmmc5_clk", "mcspi2_clk", "usbc1_icusb_dp", "gpio_145", NULL, "sdmmc2_clk", NULL, "safe_mode"), @@ -1096,9 +857,6 @@ static struct omap_mux __initdata omap4_es2_core_muxmodes[] = { "gpio_155", NULL, NULL, NULL, "safe_mode"), _OMAP4_MUXENTRY(UART4_TX, 156, "uart4_tx", "sdmmc4_dat1", "kpd_col8", "gpio_156", NULL, NULL, NULL, "safe_mode"), - _OMAP4_MUXENTRY(USBB2_ULPITLL_CLK, 157, "usbb2_ulpitll_clk", - "usbb2_ulpiphy_clk", "sdmmc4_cmd", "gpio_157", - "hsi2_cawake", NULL, NULL, "safe_mode"), _OMAP4_MUXENTRY(USBB2_ULPITLL_STP, 158, "usbb2_ulpitll_stp", "usbb2_ulpiphy_stp", "sdmmc4_clk", "gpio_158", "hsi2_cadata", "dispc2_data23", NULL, "safe_mode"), @@ -1140,10 +898,6 @@ static struct omap_mux __initdata omap4_es2_core_muxmodes[] = { "usbb2_ulpiphy_dat7", "sdmmc3_clk", "gpio_168", "mcspi3_clk", "dispc2_data11", "rfbi_data11", "safe_mode"), - _OMAP4_MUXENTRY(USBB2_HSIC_DATA, 169, "usbb2_hsic_data", NULL, NULL, - "gpio_169", NULL, NULL, NULL, "safe_mode"), - _OMAP4_MUXENTRY(USBB2_HSIC_STROBE, 170, "usbb2_hsic_strobe", NULL, - NULL, "gpio_170", NULL, NULL, NULL, "safe_mode"), _OMAP4_MUXENTRY(KPD_COL3, 171, "kpd_col3", "kpd_col0", NULL, "gpio_171", NULL, NULL, NULL, "safe_mode"), _OMAP4_MUXENTRY(KPD_COL4, 172, "kpd_col4", "kpd_col1", NULL, @@ -1168,36 +922,10 @@ static struct omap_mux __initdata omap4_es2_core_muxmodes[] = { NULL, NULL, NULL, "safe_mode"), _OMAP4_MUXENTRY(KPD_ROW2, 3, "kpd_row2", "kpd_row5", NULL, "gpio_3", NULL, NULL, NULL, "safe_mode"), - _OMAP4_MUXENTRY(USBA0_OTG_CE, 0, "usba0_otg_ce", NULL, NULL, NULL, - NULL, NULL, NULL, NULL), _OMAP4_MUXENTRY(USBA0_OTG_DP, 0, "usba0_otg_dp", "uart3_rx_irrx", "uart2_rx", NULL, NULL, NULL, NULL, "safe_mode"), _OMAP4_MUXENTRY(USBA0_OTG_DM, 0, "usba0_otg_dm", "uart3_tx_irtx", "uart2_tx", NULL, NULL, NULL, NULL, "safe_mode"), - _OMAP4_MUXENTRY(FREF_CLK1_OUT, 181, "fref_clk1_out", NULL, NULL, - "gpio_181", NULL, NULL, NULL, "safe_mode"), - _OMAP4_MUXENTRY(FREF_CLK2_OUT, 182, "fref_clk2_out", NULL, NULL, - "gpio_182", NULL, NULL, NULL, "safe_mode"), - _OMAP4_MUXENTRY(SYS_NIRQ1, 0, "sys_nirq1", NULL, NULL, NULL, NULL, - NULL, NULL, "safe_mode"), - _OMAP4_MUXENTRY(SYS_NIRQ2, 183, "sys_nirq2", NULL, NULL, "gpio_183", - NULL, NULL, NULL, "safe_mode"), - _OMAP4_MUXENTRY(SYS_BOOT0, 184, "sys_boot0", NULL, NULL, "gpio_184", - NULL, NULL, NULL, "safe_mode"), - _OMAP4_MUXENTRY(SYS_BOOT1, 185, "sys_boot1", NULL, NULL, "gpio_185", - NULL, NULL, NULL, "safe_mode"), - _OMAP4_MUXENTRY(SYS_BOOT2, 186, "sys_boot2", NULL, NULL, "gpio_186", - NULL, NULL, NULL, "safe_mode"), - _OMAP4_MUXENTRY(SYS_BOOT3, 187, "sys_boot3", NULL, NULL, "gpio_187", - NULL, NULL, NULL, "safe_mode"), - _OMAP4_MUXENTRY(SYS_BOOT4, 188, "sys_boot4", NULL, NULL, "gpio_188", - NULL, NULL, NULL, "safe_mode"), - _OMAP4_MUXENTRY(SYS_BOOT5, 189, "sys_boot5", NULL, NULL, "gpio_189", - NULL, NULL, NULL, "safe_mode"), - _OMAP4_MUXENTRY(DPM_EMU0, 11, "dpm_emu0", NULL, NULL, "gpio_11", NULL, - NULL, "hw_dbg0", "safe_mode"), - _OMAP4_MUXENTRY(DPM_EMU1, 12, "dpm_emu1", NULL, NULL, "gpio_12", NULL, - NULL, "hw_dbg1", "safe_mode"), _OMAP4_MUXENTRY(DPM_EMU2, 13, "dpm_emu2", "usba0_ulpiphy_clk", NULL, "gpio_13", NULL, "dispc2_fid", "hw_dbg2", "safe_mode"), @@ -1586,6 +1314,7 @@ int __init omap4_mux_init(struct omap_board_mux *board_subset, int flags) struct omap_ball *package_balls_core; struct omap_ball *package_balls_wkup = omap4_wkup_cbl_cbs_ball; struct omap_mux *core_muxmodes; + struct omap_mux *core_subset = NULL; int ret; switch (flags & OMAP_PACKAGE_MASK) { @@ -1597,7 +1326,8 @@ int __init omap4_mux_init(struct omap_board_mux *board_subset, int flags) case OMAP_PACKAGE_CBS: pr_debug("%s: OMAP4430 ES2.X -> OMAP_PACKAGE_CBS\n", __func__); package_balls_core = omap4_core_cbs_ball; - core_muxmodes = omap4_es2_core_muxmodes; + core_muxmodes = omap4_core_muxmodes; + core_subset = omap4_es2_core_subset; break; default: pr_err("%s: Unknown omap package, mux disabled\n", __func__); @@ -1608,7 +1338,7 @@ int __init omap4_mux_init(struct omap_board_mux *board_subset, int flags) OMAP_MUX_GPIO_IN_MODE3, OMAP4_CTRL_MODULE_PAD_CORE_MUX_PBASE, OMAP4_CTRL_MODULE_PAD_CORE_MUX_SIZE, - core_muxmodes, NULL, board_subset, + core_muxmodes, core_subset, board_subset, package_balls_core); if (ret) return ret; diff --git a/arch/arm/mach-omap2/omap-headsmp.S b/arch/arm/mach-omap2/omap-headsmp.S index 6ae937a06cc..4ee6aeca885 100644 --- a/arch/arm/mach-omap2/omap-headsmp.S +++ b/arch/arm/mach-omap2/omap-headsmp.S @@ -45,5 +45,5 @@ hold: ldr r12,=0x103 * should now contain the SVC stack for this core */ b secondary_startup -END(omap_secondary_startup) +ENDPROC(omap_secondary_startup) diff --git a/arch/arm/mach-omap2/omap44xx-smc.S b/arch/arm/mach-omap2/omap44xx-smc.S index 1980dc31a1a..e69d37d9520 100644 --- a/arch/arm/mach-omap2/omap44xx-smc.S +++ b/arch/arm/mach-omap2/omap44xx-smc.S @@ -29,7 +29,7 @@ ENTRY(omap_smc1) dsb smc #0 ldmfd sp!, {r2-r12, pc} -END(omap_smc1) +ENDPROC(omap_smc1) ENTRY(omap_modify_auxcoreboot0) stmfd sp!, {r1-r12, lr} @@ -37,7 +37,7 @@ ENTRY(omap_modify_auxcoreboot0) dsb smc #0 ldmfd sp!, {r1-r12, pc} -END(omap_modify_auxcoreboot0) +ENDPROC(omap_modify_auxcoreboot0) ENTRY(omap_auxcoreboot_addr) stmfd sp!, {r2-r12, lr} @@ -45,7 +45,7 @@ ENTRY(omap_auxcoreboot_addr) dsb smc #0 ldmfd sp!, {r2-r12, pc} -END(omap_auxcoreboot_addr) +ENDPROC(omap_auxcoreboot_addr) ENTRY(omap_read_auxcoreboot0) stmfd sp!, {r2-r12, lr} @@ -54,4 +54,4 @@ ENTRY(omap_read_auxcoreboot0) smc #0 mov r0, r0, lsr #9 ldmfd sp!, {r2-r12, pc} -END(omap_read_auxcoreboot0) +ENDPROC(omap_read_auxcoreboot0) diff --git a/arch/arm/mach-omap2/omap_hwmod.c b/arch/arm/mach-omap2/omap_hwmod.c index e282e35769f..e03429453ce 100644 --- a/arch/arm/mach-omap2/omap_hwmod.c +++ b/arch/arm/mach-omap2/omap_hwmod.c @@ -1,7 +1,7 @@ /* * omap_hwmod implementation for OMAP2/3/4 * - * Copyright (C) 2009-2010 Nokia Corporation + * Copyright (C) 2009-2011 Nokia Corporation * * Paul Walmsley, Benoît Cousson, Kevin Hilman * @@ -162,9 +162,6 @@ static LIST_HEAD(omap_hwmod_list); /* mpu_oh: used to add/remove MPU initiator from sleepdep list */ static struct omap_hwmod *mpu_oh; -/* inited: 0 if omap_hwmod_init() has not yet been called; 1 otherwise */ -static u8 inited; - /* Private functions */ @@ -373,7 +370,7 @@ static int _set_module_autoidle(struct omap_hwmod *oh, u8 autoidle, } autoidle_shift = oh->class->sysc->sysc_fields->autoidle_shift; - autoidle_mask = (0x3 << autoidle_shift); + autoidle_mask = (0x1 << autoidle_shift); *v &= ~autoidle_mask; *v |= autoidle << autoidle_shift; @@ -460,14 +457,18 @@ static int _disable_wakeup(struct omap_hwmod *oh, u32 *v) * will be accessed by a particular initiator (e.g., if a module will * be accessed by the IVA, there should be a sleepdep between the IVA * initiator and the module). Only applies to modules in smart-idle - * mode. Returns -EINVAL upon error or passes along - * clkdm_add_sleepdep() value upon success. + * mode. If the clockdomain is marked as not needing autodeps, return + * 0 without doing anything. Otherwise, returns -EINVAL upon error or + * passes along clkdm_add_sleepdep() value upon success. */ static int _add_initiator_dep(struct omap_hwmod *oh, struct omap_hwmod *init_oh) { if (!oh->_clk) return -EINVAL; + if (oh->_clk->clkdm && oh->_clk->clkdm->flags & CLKDM_NO_AUTODEPS) + return 0; + return clkdm_add_sleepdep(oh->_clk->clkdm, init_oh->_clk->clkdm); } @@ -480,14 +481,18 @@ static int _add_initiator_dep(struct omap_hwmod *oh, struct omap_hwmod *init_oh) * be accessed by a particular initiator (e.g., if a module will not * be accessed by the IVA, there should be no sleepdep between the IVA * initiator and the module). Only applies to modules in smart-idle - * mode. Returns -EINVAL upon error or passes along - * clkdm_del_sleepdep() value upon success. + * mode. If the clockdomain is marked as not needing autodeps, return + * 0 without doing anything. Returns -EINVAL upon error or passes + * along clkdm_del_sleepdep() value upon success. */ static int _del_initiator_dep(struct omap_hwmod *oh, struct omap_hwmod *init_oh) { if (!oh->_clk) return -EINVAL; + if (oh->_clk->clkdm && oh->_clk->clkdm->flags & CLKDM_NO_AUTODEPS) + return 0; + return clkdm_del_sleepdep(oh->_clk->clkdm, init_oh->_clk->clkdm); } @@ -904,18 +909,16 @@ static struct omap_hwmod *_lookup(const char *name) * @oh: struct omap_hwmod * * @data: not used; pass NULL * - * Called by omap_hwmod_late_init() (after omap2_clk_init()). - * Resolves all clock names embedded in the hwmod. Returns -EINVAL if - * the omap_hwmod has not yet been registered or if the clocks have - * already been initialized, 0 on success, or a non-zero error on - * failure. + * Called by omap_hwmod_setup_*() (after omap2_clk_init()). + * Resolves all clock names embedded in the hwmod. Returns 0 on + * success, or a negative error code on failure. */ static int _init_clocks(struct omap_hwmod *oh, void *data) { int ret = 0; - if (!oh || (oh->_state != _HWMOD_STATE_REGISTERED)) - return -EINVAL; + if (oh->_state != _HWMOD_STATE_REGISTERED) + return 0; pr_debug("omap_hwmod: %s: looking up clocks\n", oh->name); @@ -926,7 +929,7 @@ static int _init_clocks(struct omap_hwmod *oh, void *data) if (!ret) oh->_state = _HWMOD_STATE_CLKS_INITED; - return 0; + return ret; } /** @@ -972,25 +975,29 @@ static int _wait_target_ready(struct omap_hwmod *oh) } /** - * _lookup_hardreset - return the register bit shift for this hwmod/reset line + * _lookup_hardreset - fill register bit info for this hwmod/reset line * @oh: struct omap_hwmod * * @name: name of the reset line in the context of this hwmod + * @ohri: struct omap_hwmod_rst_info * that this function will fill in * * Return the bit position of the reset line that match the * input name. Return -ENOENT if not found. */ -static u8 _lookup_hardreset(struct omap_hwmod *oh, const char *name) +static u8 _lookup_hardreset(struct omap_hwmod *oh, const char *name, + struct omap_hwmod_rst_info *ohri) { int i; for (i = 0; i < oh->rst_lines_cnt; i++) { const char *rst_line = oh->rst_lines[i].name; if (!strcmp(rst_line, name)) { - u8 shift = oh->rst_lines[i].rst_shift; - pr_debug("omap_hwmod: %s: _lookup_hardreset: %s: %d\n", - oh->name, rst_line, shift); + ohri->rst_shift = oh->rst_lines[i].rst_shift; + ohri->st_shift = oh->rst_lines[i].st_shift; + pr_debug("omap_hwmod: %s: %s: %s: rst %d st %d\n", + oh->name, __func__, rst_line, ohri->rst_shift, + ohri->st_shift); - return shift; + return 0; } } @@ -1009,21 +1016,22 @@ static u8 _lookup_hardreset(struct omap_hwmod *oh, const char *name) */ static int _assert_hardreset(struct omap_hwmod *oh, const char *name) { - u8 shift; + struct omap_hwmod_rst_info ohri; + u8 ret; if (!oh) return -EINVAL; - shift = _lookup_hardreset(oh, name); - if (IS_ERR_VALUE(shift)) - return shift; + ret = _lookup_hardreset(oh, name, &ohri); + if (IS_ERR_VALUE(ret)) + return ret; if (cpu_is_omap24xx() || cpu_is_omap34xx()) return omap2_prm_assert_hardreset(oh->prcm.omap2.module_offs, - shift); + ohri.rst_shift); else if (cpu_is_omap44xx()) return omap4_prm_assert_hardreset(oh->prcm.omap4.rstctrl_reg, - shift); + ohri.rst_shift); else return -EINVAL; } @@ -1040,29 +1048,34 @@ static int _assert_hardreset(struct omap_hwmod *oh, const char *name) */ static int _deassert_hardreset(struct omap_hwmod *oh, const char *name) { - u8 shift; - int r; + struct omap_hwmod_rst_info ohri; + int ret; if (!oh) return -EINVAL; - shift = _lookup_hardreset(oh, name); - if (IS_ERR_VALUE(shift)) - return shift; + ret = _lookup_hardreset(oh, name, &ohri); + if (IS_ERR_VALUE(ret)) + return ret; - if (cpu_is_omap24xx() || cpu_is_omap34xx()) - r = omap2_prm_deassert_hardreset(oh->prcm.omap2.module_offs, - shift); - else if (cpu_is_omap44xx()) - r = omap4_prm_deassert_hardreset(oh->prcm.omap4.rstctrl_reg, - shift); - else + if (cpu_is_omap24xx() || cpu_is_omap34xx()) { + ret = omap2_prm_deassert_hardreset(oh->prcm.omap2.module_offs, + ohri.rst_shift, + ohri.st_shift); + } else if (cpu_is_omap44xx()) { + if (ohri.st_shift) + pr_err("omap_hwmod: %s: %s: hwmod data error: OMAP4 does not support st_shift\n", + oh->name, name); + ret = omap4_prm_deassert_hardreset(oh->prcm.omap4.rstctrl_reg, + ohri.rst_shift); + } else { return -EINVAL; + } - if (r == -EBUSY) + if (ret == -EBUSY) pr_warning("omap_hwmod: %s: failed to hardreset\n", oh->name); - return r; + return ret; } /** @@ -1075,21 +1088,22 @@ static int _deassert_hardreset(struct omap_hwmod *oh, const char *name) */ static int _read_hardreset(struct omap_hwmod *oh, const char *name) { - u8 shift; + struct omap_hwmod_rst_info ohri; + u8 ret; if (!oh) return -EINVAL; - shift = _lookup_hardreset(oh, name); - if (IS_ERR_VALUE(shift)) - return shift; + ret = _lookup_hardreset(oh, name, &ohri); + if (IS_ERR_VALUE(ret)) + return ret; if (cpu_is_omap24xx() || cpu_is_omap34xx()) { return omap2_prm_is_hardreset_asserted(oh->prcm.omap2.module_offs, - shift); + ohri.st_shift); } else if (cpu_is_omap44xx()) { return omap4_prm_is_hardreset_asserted(oh->prcm.omap4.rstctrl_reg, - shift); + ohri.rst_shift); } else { return -EINVAL; } @@ -1230,7 +1244,9 @@ static int _enable(struct omap_hwmod *oh) _deassert_hardreset(oh, oh->rst_lines[0].name); /* Mux pins for device runtime if populated */ - if (oh->mux) + if (oh->mux && (!oh->mux->enabled || + ((oh->_state == _HWMOD_STATE_IDLE) && + oh->mux->pads_dynamic))) omap_hwmod_mux(oh->mux, _HWMOD_STATE_ENABLED); _add_initiator_dep(oh, mpu_oh); @@ -1279,7 +1295,7 @@ static int _idle(struct omap_hwmod *oh) _disable_clocks(oh); /* Mux pins for device idle if populated */ - if (oh->mux) + if (oh->mux && oh->mux->pads_dynamic) omap_hwmod_mux(oh->mux, _HWMOD_STATE_IDLE); oh->_state = _HWMOD_STATE_IDLE; @@ -1288,6 +1304,42 @@ static int _idle(struct omap_hwmod *oh) } /** + * omap_hwmod_set_ocp_autoidle - set the hwmod's OCP autoidle bit + * @oh: struct omap_hwmod * + * @autoidle: desired AUTOIDLE bitfield value (0 or 1) + * + * Sets the IP block's OCP autoidle bit in hardware, and updates our + * local copy. Intended to be used by drivers that require + * direct manipulation of the AUTOIDLE bits. + * Returns -EINVAL if @oh is null or is not in the ENABLED state, or passes + * along the return value from _set_module_autoidle(). + * + * Any users of this function should be scrutinized carefully. + */ +int omap_hwmod_set_ocp_autoidle(struct omap_hwmod *oh, u8 autoidle) +{ + u32 v; + int retval = 0; + unsigned long flags; + + if (!oh || oh->_state != _HWMOD_STATE_ENABLED) + return -EINVAL; + + spin_lock_irqsave(&oh->_lock, flags); + + v = oh->_sysc_cache; + + retval = _set_module_autoidle(oh, autoidle, &v); + + if (!retval) + _write_sysconfig(v, oh); + + spin_unlock_irqrestore(&oh->_lock, flags); + + return retval; +} + +/** * _shutdown - shutdown an omap_hwmod * @oh: struct omap_hwmod * * @@ -1354,14 +1406,16 @@ static int _shutdown(struct omap_hwmod *oh) * @oh: struct omap_hwmod * * * Writes the CLOCKACTIVITY bits @clockact to the hwmod @oh - * OCP_SYSCONFIG register. Returns -EINVAL if the hwmod is in the - * wrong state or returns 0. + * OCP_SYSCONFIG register. Returns 0. */ static int _setup(struct omap_hwmod *oh, void *data) { int i, r; u8 postsetup_state; + if (oh->_state != _HWMOD_STATE_CLKS_INITED) + return 0; + /* Set iclk autoidle mode */ if (oh->slaves_cnt > 0) { for (i = 0; i < oh->slaves_cnt; i++) { @@ -1455,7 +1509,7 @@ static int _setup(struct omap_hwmod *oh, void *data) */ static int __init _register(struct omap_hwmod *oh) { - int ret, ms_id; + int ms_id; if (!oh || !oh->name || !oh->class || !oh->class->name || (oh->_state != _HWMOD_STATE_UNKNOWN)) @@ -1467,12 +1521,10 @@ static int __init _register(struct omap_hwmod *oh) return -EEXIST; ms_id = _find_mpu_port_index(oh); - if (!IS_ERR_VALUE(ms_id)) { + if (!IS_ERR_VALUE(ms_id)) oh->_mpu_port_index = ms_id; - oh->_mpu_rt_va = _find_mpu_rt_base(oh, oh->_mpu_port_index); - } else { + else oh->_int_flags |= _HWMOD_NO_MPU_PORT; - } list_add_tail(&oh->node, &omap_hwmod_list); @@ -1480,9 +1532,14 @@ static int __init _register(struct omap_hwmod *oh) oh->_state = _HWMOD_STATE_REGISTERED; - ret = 0; + /* + * XXX Rather than doing a strcmp(), this should test a flag + * set in the hwmod data, inserted by the autogenerator code. + */ + if (!strcmp(oh->name, MPU_INITIATOR_NAME)) + mpu_oh = oh; - return ret; + return 0; } @@ -1585,65 +1642,132 @@ int omap_hwmod_for_each(int (*fn)(struct omap_hwmod *oh, void *data), return ret; } - /** - * omap_hwmod_init - init omap_hwmod code and register hwmods + * omap_hwmod_register - register an array of hwmods * @ohs: pointer to an array of omap_hwmods to register * * Intended to be called early in boot before the clock framework is * initialized. If @ohs is not null, will register all omap_hwmods - * listed in @ohs that are valid for this chip. Returns -EINVAL if - * omap_hwmod_init() has already been called or 0 otherwise. + * listed in @ohs that are valid for this chip. Returns 0. */ -int __init omap_hwmod_init(struct omap_hwmod **ohs) +int __init omap_hwmod_register(struct omap_hwmod **ohs) +{ + int r, i; + + if (!ohs) + return 0; + + i = 0; + do { + if (!omap_chip_is(ohs[i]->omap_chip)) + continue; + + r = _register(ohs[i]); + WARN(r, "omap_hwmod: %s: _register returned %d\n", ohs[i]->name, + r); + } while (ohs[++i]); + + return 0; +} + +/* + * _populate_mpu_rt_base - populate the virtual address for a hwmod + * + * Must be called only from omap_hwmod_setup_*() so ioremap works properly. + * Assumes the caller takes care of locking if needed. + */ +static int __init _populate_mpu_rt_base(struct omap_hwmod *oh, void *data) +{ + if (oh->_state != _HWMOD_STATE_REGISTERED) + return 0; + + if (oh->_int_flags & _HWMOD_NO_MPU_PORT) + return 0; + + oh->_mpu_rt_va = _find_mpu_rt_base(oh, oh->_mpu_port_index); + if (!oh->_mpu_rt_va) + pr_warning("omap_hwmod: %s found no _mpu_rt_va for %s\n", + __func__, oh->name); + + return 0; +} + +/** + * omap_hwmod_setup_one - set up a single hwmod + * @oh_name: const char * name of the already-registered hwmod to set up + * + * Must be called after omap2_clk_init(). Resolves the struct clk + * names to struct clk pointers for each registered omap_hwmod. Also + * calls _setup() on each hwmod. Returns -EINVAL upon error or 0 upon + * success. + */ +int __init omap_hwmod_setup_one(const char *oh_name) { struct omap_hwmod *oh; int r; - if (inited) + pr_debug("omap_hwmod: %s: %s\n", oh_name, __func__); + + if (!mpu_oh) { + pr_err("omap_hwmod: %s: cannot setup_one: MPU initiator hwmod %s not yet registered\n", + oh_name, MPU_INITIATOR_NAME); return -EINVAL; + } - inited = 1; + oh = _lookup(oh_name); + if (!oh) { + WARN(1, "omap_hwmod: %s: hwmod not yet registered\n", oh_name); + return -EINVAL; + } - if (!ohs) - return 0; + if (mpu_oh->_state == _HWMOD_STATE_REGISTERED && oh != mpu_oh) + omap_hwmod_setup_one(MPU_INITIATOR_NAME); - oh = *ohs; - while (oh) { - if (omap_chip_is(oh->omap_chip)) { - r = _register(oh); - WARN(r, "omap_hwmod: %s: _register returned " - "%d\n", oh->name, r); - } - oh = *++ohs; + r = _populate_mpu_rt_base(oh, NULL); + if (IS_ERR_VALUE(r)) { + WARN(1, "omap_hwmod: %s: couldn't set mpu_rt_base\n", oh_name); + return -EINVAL; } + r = _init_clocks(oh, NULL); + if (IS_ERR_VALUE(r)) { + WARN(1, "omap_hwmod: %s: couldn't init clocks\n", oh_name); + return -EINVAL; + } + + _setup(oh, NULL); + return 0; } /** - * omap_hwmod_late_init - do some post-clock framework initialization + * omap_hwmod_setup - do some post-clock framework initialization * * Must be called after omap2_clk_init(). Resolves the struct clk names * to struct clk pointers for each registered omap_hwmod. Also calls - * _setup() on each hwmod. Returns 0. + * _setup() on each hwmod. Returns 0 upon success. */ -int omap_hwmod_late_init(void) +static int __init omap_hwmod_setup_all(void) { int r; - /* XXX check return value */ - r = omap_hwmod_for_each(_init_clocks, NULL); - WARN(r, "omap_hwmod: omap_hwmod_late_init(): _init_clocks failed\n"); + if (!mpu_oh) { + pr_err("omap_hwmod: %s: MPU initiator hwmod %s not yet registered\n", + __func__, MPU_INITIATOR_NAME); + return -EINVAL; + } - mpu_oh = omap_hwmod_lookup(MPU_INITIATOR_NAME); - WARN(!mpu_oh, "omap_hwmod: could not find MPU initiator hwmod %s\n", - MPU_INITIATOR_NAME); + r = omap_hwmod_for_each(_populate_mpu_rt_base, NULL); + + r = omap_hwmod_for_each(_init_clocks, NULL); + WARN(IS_ERR_VALUE(r), + "omap_hwmod: %s: _init_clocks failed\n", __func__); omap_hwmod_for_each(_setup, NULL); return 0; } +core_initcall(omap_hwmod_setup_all); /** * omap_hwmod_enable - enable an omap_hwmod @@ -1862,6 +1986,7 @@ int omap_hwmod_fill_resources(struct omap_hwmod *oh, struct resource *res) os = oh->slaves[i]; for (j = 0; j < os->addr_cnt; j++) { + (res + r)->name = (os->addr + j)->name; (res + r)->start = (os->addr + j)->pa_start; (res + r)->end = (os->addr + j)->pa_end; (res + r)->flags = IORESOURCE_MEM; @@ -2162,11 +2287,11 @@ int omap_hwmod_for_each_by_class(const char *classname, * @oh: struct omap_hwmod * * @state: state that _setup() should leave the hwmod in * - * Sets the hwmod state that @oh will enter at the end of _setup() (called by - * omap_hwmod_late_init()). Only valid to call between calls to - * omap_hwmod_init() and omap_hwmod_late_init(). Returns 0 upon success or - * -EINVAL if there is a problem with the arguments or if the hwmod is - * in the wrong state. + * Sets the hwmod state that @oh will enter at the end of _setup() + * (called by omap_hwmod_setup_*()). Only valid to call between + * calling omap_hwmod_register() and omap_hwmod_setup_*(). Returns + * 0 upon success or -EINVAL if there is a problem with the arguments + * or if the hwmod is in the wrong state. */ int omap_hwmod_set_postsetup_state(struct omap_hwmod *oh, u8 state) { @@ -2218,3 +2343,29 @@ u32 omap_hwmod_get_context_loss_count(struct omap_hwmod *oh) return ret; } + +/** + * omap_hwmod_no_setup_reset - prevent a hwmod from being reset upon setup + * @oh: struct omap_hwmod * + * + * Prevent the hwmod @oh from being reset during the setup process. + * Intended for use by board-*.c files on boards with devices that + * cannot tolerate being reset. Must be called before the hwmod has + * been set up. Returns 0 upon success or negative error code upon + * failure. + */ +int omap_hwmod_no_setup_reset(struct omap_hwmod *oh) +{ + if (!oh) + return -EINVAL; + + if (oh->_state != _HWMOD_STATE_REGISTERED) { + pr_err("omap_hwmod: %s: cannot prevent setup reset; in wrong state\n", + oh->name); + return -EINVAL; + } + + oh->flags |= HWMOD_INIT_NO_RESET; + + return 0; +} diff --git a/arch/arm/mach-omap2/omap_hwmod_2420_data.c b/arch/arm/mach-omap2/omap_hwmod_2420_data.c index b85c630b64d..62823467163 100644 --- a/arch/arm/mach-omap2/omap_hwmod_2420_data.c +++ b/arch/arm/mach-omap2/omap_hwmod_2420_data.c @@ -18,6 +18,10 @@ #include <plat/serial.h> #include <plat/i2c.h> #include <plat/gpio.h> +#include <plat/mcspi.h> +#include <plat/dmtimer.h> +#include <plat/l3_2xxx.h> +#include <plat/l4_2xxx.h> #include "omap_hwmod_common_data.h" @@ -38,12 +42,18 @@ static struct omap_hwmod omap2420_mpu_hwmod; static struct omap_hwmod omap2420_iva_hwmod; static struct omap_hwmod omap2420_l3_main_hwmod; static struct omap_hwmod omap2420_l4_core_hwmod; +static struct omap_hwmod omap2420_dss_core_hwmod; +static struct omap_hwmod omap2420_dss_dispc_hwmod; +static struct omap_hwmod omap2420_dss_rfbi_hwmod; +static struct omap_hwmod omap2420_dss_venc_hwmod; static struct omap_hwmod omap2420_wd_timer2_hwmod; static struct omap_hwmod omap2420_gpio1_hwmod; static struct omap_hwmod omap2420_gpio2_hwmod; static struct omap_hwmod omap2420_gpio3_hwmod; static struct omap_hwmod omap2420_gpio4_hwmod; static struct omap_hwmod omap2420_dma_system_hwmod; +static struct omap_hwmod omap2420_mcspi1_hwmod; +static struct omap_hwmod omap2420_mcspi2_hwmod; /* L3 -> L4_CORE interface */ static struct omap_hwmod_ocp_if omap2420_l3_main__l4_core = { @@ -64,6 +74,19 @@ static struct omap_hwmod_ocp_if *omap2420_l3_main_slaves[] = { &omap2420_mpu__l3_main, }; +/* DSS -> l3 */ +static struct omap_hwmod_ocp_if omap2420_dss__l3 = { + .master = &omap2420_dss_core_hwmod, + .slave = &omap2420_l3_main_hwmod, + .fw = { + .omap2 = { + .l3_perm_bit = OMAP2_L3_CORE_FW_CONNID_DSS, + .flags = OMAP_FIREWALL_L3, + } + }, + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + /* Master interfaces on the L3 interconnect */ static struct omap_hwmod_ocp_if *omap2420_l3_main_masters[] = { &omap2420_l3_main__l4_core, @@ -87,6 +110,44 @@ static struct omap_hwmod omap2420_uart2_hwmod; static struct omap_hwmod omap2420_uart3_hwmod; static struct omap_hwmod omap2420_i2c1_hwmod; static struct omap_hwmod omap2420_i2c2_hwmod; +static struct omap_hwmod omap2420_mcbsp1_hwmod; +static struct omap_hwmod omap2420_mcbsp2_hwmod; + +/* l4 core -> mcspi1 interface */ +static struct omap_hwmod_addr_space omap2420_mcspi1_addr_space[] = { + { + .pa_start = 0x48098000, + .pa_end = 0x480980ff, + .flags = ADDR_TYPE_RT, + }, +}; + +static struct omap_hwmod_ocp_if omap2420_l4_core__mcspi1 = { + .master = &omap2420_l4_core_hwmod, + .slave = &omap2420_mcspi1_hwmod, + .clk = "mcspi1_ick", + .addr = omap2420_mcspi1_addr_space, + .addr_cnt = ARRAY_SIZE(omap2420_mcspi1_addr_space), + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* l4 core -> mcspi2 interface */ +static struct omap_hwmod_addr_space omap2420_mcspi2_addr_space[] = { + { + .pa_start = 0x4809a000, + .pa_end = 0x4809a0ff, + .flags = ADDR_TYPE_RT, + }, +}; + +static struct omap_hwmod_ocp_if omap2420_l4_core__mcspi2 = { + .master = &omap2420_l4_core_hwmod, + .slave = &omap2420_mcspi2_hwmod, + .clk = "mcspi2_ick", + .addr = omap2420_mcspi2_addr_space, + .addr_cnt = ARRAY_SIZE(omap2420_mcspi2_addr_space), + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; /* L4_CORE -> L4_WKUP interface */ static struct omap_hwmod_ocp_if omap2420_l4_core__l4_wkup = { @@ -279,6 +340,625 @@ static struct omap_hwmod omap2420_iva_hwmod = { .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP2420) }; +/* Timer Common */ +static struct omap_hwmod_class_sysconfig omap2420_timer_sysc = { + .rev_offs = 0x0000, + .sysc_offs = 0x0010, + .syss_offs = 0x0014, + .sysc_flags = (SYSC_HAS_SIDLEMODE | SYSC_HAS_CLOCKACTIVITY | + SYSC_HAS_ENAWAKEUP | SYSC_HAS_SOFTRESET | + SYSC_HAS_AUTOIDLE), + .idlemodes = (SIDLE_FORCE | SIDLE_NO | SIDLE_SMART), + .sysc_fields = &omap_hwmod_sysc_type1, +}; + +static struct omap_hwmod_class omap2420_timer_hwmod_class = { + .name = "timer", + .sysc = &omap2420_timer_sysc, + .rev = OMAP_TIMER_IP_VERSION_1, +}; + +/* timer1 */ +static struct omap_hwmod omap2420_timer1_hwmod; +static struct omap_hwmod_irq_info omap2420_timer1_mpu_irqs[] = { + { .irq = 37, }, +}; + +static struct omap_hwmod_addr_space omap2420_timer1_addrs[] = { + { + .pa_start = 0x48028000, + .pa_end = 0x48028000 + SZ_1K - 1, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_wkup -> timer1 */ +static struct omap_hwmod_ocp_if omap2420_l4_wkup__timer1 = { + .master = &omap2420_l4_wkup_hwmod, + .slave = &omap2420_timer1_hwmod, + .clk = "gpt1_ick", + .addr = omap2420_timer1_addrs, + .addr_cnt = ARRAY_SIZE(omap2420_timer1_addrs), + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* timer1 slave port */ +static struct omap_hwmod_ocp_if *omap2420_timer1_slaves[] = { + &omap2420_l4_wkup__timer1, +}; + +/* timer1 hwmod */ +static struct omap_hwmod omap2420_timer1_hwmod = { + .name = "timer1", + .mpu_irqs = omap2420_timer1_mpu_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap2420_timer1_mpu_irqs), + .main_clk = "gpt1_fck", + .prcm = { + .omap2 = { + .prcm_reg_id = 1, + .module_bit = OMAP24XX_EN_GPT1_SHIFT, + .module_offs = WKUP_MOD, + .idlest_reg_id = 1, + .idlest_idle_bit = OMAP24XX_ST_GPT1_SHIFT, + }, + }, + .slaves = omap2420_timer1_slaves, + .slaves_cnt = ARRAY_SIZE(omap2420_timer1_slaves), + .class = &omap2420_timer_hwmod_class, + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP2420) +}; + +/* timer2 */ +static struct omap_hwmod omap2420_timer2_hwmod; +static struct omap_hwmod_irq_info omap2420_timer2_mpu_irqs[] = { + { .irq = 38, }, +}; + +static struct omap_hwmod_addr_space omap2420_timer2_addrs[] = { + { + .pa_start = 0x4802a000, + .pa_end = 0x4802a000 + SZ_1K - 1, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_core -> timer2 */ +static struct omap_hwmod_ocp_if omap2420_l4_core__timer2 = { + .master = &omap2420_l4_core_hwmod, + .slave = &omap2420_timer2_hwmod, + .clk = "gpt2_ick", + .addr = omap2420_timer2_addrs, + .addr_cnt = ARRAY_SIZE(omap2420_timer2_addrs), + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* timer2 slave port */ +static struct omap_hwmod_ocp_if *omap2420_timer2_slaves[] = { + &omap2420_l4_core__timer2, +}; + +/* timer2 hwmod */ +static struct omap_hwmod omap2420_timer2_hwmod = { + .name = "timer2", + .mpu_irqs = omap2420_timer2_mpu_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap2420_timer2_mpu_irqs), + .main_clk = "gpt2_fck", + .prcm = { + .omap2 = { + .prcm_reg_id = 1, + .module_bit = OMAP24XX_EN_GPT2_SHIFT, + .module_offs = CORE_MOD, + .idlest_reg_id = 1, + .idlest_idle_bit = OMAP24XX_ST_GPT2_SHIFT, + }, + }, + .slaves = omap2420_timer2_slaves, + .slaves_cnt = ARRAY_SIZE(omap2420_timer2_slaves), + .class = &omap2420_timer_hwmod_class, + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP2420) +}; + +/* timer3 */ +static struct omap_hwmod omap2420_timer3_hwmod; +static struct omap_hwmod_irq_info omap2420_timer3_mpu_irqs[] = { + { .irq = 39, }, +}; + +static struct omap_hwmod_addr_space omap2420_timer3_addrs[] = { + { + .pa_start = 0x48078000, + .pa_end = 0x48078000 + SZ_1K - 1, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_core -> timer3 */ +static struct omap_hwmod_ocp_if omap2420_l4_core__timer3 = { + .master = &omap2420_l4_core_hwmod, + .slave = &omap2420_timer3_hwmod, + .clk = "gpt3_ick", + .addr = omap2420_timer3_addrs, + .addr_cnt = ARRAY_SIZE(omap2420_timer3_addrs), + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* timer3 slave port */ +static struct omap_hwmod_ocp_if *omap2420_timer3_slaves[] = { + &omap2420_l4_core__timer3, +}; + +/* timer3 hwmod */ +static struct omap_hwmod omap2420_timer3_hwmod = { + .name = "timer3", + .mpu_irqs = omap2420_timer3_mpu_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap2420_timer3_mpu_irqs), + .main_clk = "gpt3_fck", + .prcm = { + .omap2 = { + .prcm_reg_id = 1, + .module_bit = OMAP24XX_EN_GPT3_SHIFT, + .module_offs = CORE_MOD, + .idlest_reg_id = 1, + .idlest_idle_bit = OMAP24XX_ST_GPT3_SHIFT, + }, + }, + .slaves = omap2420_timer3_slaves, + .slaves_cnt = ARRAY_SIZE(omap2420_timer3_slaves), + .class = &omap2420_timer_hwmod_class, + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP2420) +}; + +/* timer4 */ +static struct omap_hwmod omap2420_timer4_hwmod; +static struct omap_hwmod_irq_info omap2420_timer4_mpu_irqs[] = { + { .irq = 40, }, +}; + +static struct omap_hwmod_addr_space omap2420_timer4_addrs[] = { + { + .pa_start = 0x4807a000, + .pa_end = 0x4807a000 + SZ_1K - 1, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_core -> timer4 */ +static struct omap_hwmod_ocp_if omap2420_l4_core__timer4 = { + .master = &omap2420_l4_core_hwmod, + .slave = &omap2420_timer4_hwmod, + .clk = "gpt4_ick", + .addr = omap2420_timer4_addrs, + .addr_cnt = ARRAY_SIZE(omap2420_timer4_addrs), + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* timer4 slave port */ +static struct omap_hwmod_ocp_if *omap2420_timer4_slaves[] = { + &omap2420_l4_core__timer4, +}; + +/* timer4 hwmod */ +static struct omap_hwmod omap2420_timer4_hwmod = { + .name = "timer4", + .mpu_irqs = omap2420_timer4_mpu_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap2420_timer4_mpu_irqs), + .main_clk = "gpt4_fck", + .prcm = { + .omap2 = { + .prcm_reg_id = 1, + .module_bit = OMAP24XX_EN_GPT4_SHIFT, + .module_offs = CORE_MOD, + .idlest_reg_id = 1, + .idlest_idle_bit = OMAP24XX_ST_GPT4_SHIFT, + }, + }, + .slaves = omap2420_timer4_slaves, + .slaves_cnt = ARRAY_SIZE(omap2420_timer4_slaves), + .class = &omap2420_timer_hwmod_class, + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP2420) +}; + +/* timer5 */ +static struct omap_hwmod omap2420_timer5_hwmod; +static struct omap_hwmod_irq_info omap2420_timer5_mpu_irqs[] = { + { .irq = 41, }, +}; + +static struct omap_hwmod_addr_space omap2420_timer5_addrs[] = { + { + .pa_start = 0x4807c000, + .pa_end = 0x4807c000 + SZ_1K - 1, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_core -> timer5 */ +static struct omap_hwmod_ocp_if omap2420_l4_core__timer5 = { + .master = &omap2420_l4_core_hwmod, + .slave = &omap2420_timer5_hwmod, + .clk = "gpt5_ick", + .addr = omap2420_timer5_addrs, + .addr_cnt = ARRAY_SIZE(omap2420_timer5_addrs), + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* timer5 slave port */ +static struct omap_hwmod_ocp_if *omap2420_timer5_slaves[] = { + &omap2420_l4_core__timer5, +}; + +/* timer5 hwmod */ +static struct omap_hwmod omap2420_timer5_hwmod = { + .name = "timer5", + .mpu_irqs = omap2420_timer5_mpu_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap2420_timer5_mpu_irqs), + .main_clk = "gpt5_fck", + .prcm = { + .omap2 = { + .prcm_reg_id = 1, + .module_bit = OMAP24XX_EN_GPT5_SHIFT, + .module_offs = CORE_MOD, + .idlest_reg_id = 1, + .idlest_idle_bit = OMAP24XX_ST_GPT5_SHIFT, + }, + }, + .slaves = omap2420_timer5_slaves, + .slaves_cnt = ARRAY_SIZE(omap2420_timer5_slaves), + .class = &omap2420_timer_hwmod_class, + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP2420) +}; + + +/* timer6 */ +static struct omap_hwmod omap2420_timer6_hwmod; +static struct omap_hwmod_irq_info omap2420_timer6_mpu_irqs[] = { + { .irq = 42, }, +}; + +static struct omap_hwmod_addr_space omap2420_timer6_addrs[] = { + { + .pa_start = 0x4807e000, + .pa_end = 0x4807e000 + SZ_1K - 1, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_core -> timer6 */ +static struct omap_hwmod_ocp_if omap2420_l4_core__timer6 = { + .master = &omap2420_l4_core_hwmod, + .slave = &omap2420_timer6_hwmod, + .clk = "gpt6_ick", + .addr = omap2420_timer6_addrs, + .addr_cnt = ARRAY_SIZE(omap2420_timer6_addrs), + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* timer6 slave port */ +static struct omap_hwmod_ocp_if *omap2420_timer6_slaves[] = { + &omap2420_l4_core__timer6, +}; + +/* timer6 hwmod */ +static struct omap_hwmod omap2420_timer6_hwmod = { + .name = "timer6", + .mpu_irqs = omap2420_timer6_mpu_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap2420_timer6_mpu_irqs), + .main_clk = "gpt6_fck", + .prcm = { + .omap2 = { + .prcm_reg_id = 1, + .module_bit = OMAP24XX_EN_GPT6_SHIFT, + .module_offs = CORE_MOD, + .idlest_reg_id = 1, + .idlest_idle_bit = OMAP24XX_ST_GPT6_SHIFT, + }, + }, + .slaves = omap2420_timer6_slaves, + .slaves_cnt = ARRAY_SIZE(omap2420_timer6_slaves), + .class = &omap2420_timer_hwmod_class, + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP2420) +}; + +/* timer7 */ +static struct omap_hwmod omap2420_timer7_hwmod; +static struct omap_hwmod_irq_info omap2420_timer7_mpu_irqs[] = { + { .irq = 43, }, +}; + +static struct omap_hwmod_addr_space omap2420_timer7_addrs[] = { + { + .pa_start = 0x48080000, + .pa_end = 0x48080000 + SZ_1K - 1, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_core -> timer7 */ +static struct omap_hwmod_ocp_if omap2420_l4_core__timer7 = { + .master = &omap2420_l4_core_hwmod, + .slave = &omap2420_timer7_hwmod, + .clk = "gpt7_ick", + .addr = omap2420_timer7_addrs, + .addr_cnt = ARRAY_SIZE(omap2420_timer7_addrs), + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* timer7 slave port */ +static struct omap_hwmod_ocp_if *omap2420_timer7_slaves[] = { + &omap2420_l4_core__timer7, +}; + +/* timer7 hwmod */ +static struct omap_hwmod omap2420_timer7_hwmod = { + .name = "timer7", + .mpu_irqs = omap2420_timer7_mpu_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap2420_timer7_mpu_irqs), + .main_clk = "gpt7_fck", + .prcm = { + .omap2 = { + .prcm_reg_id = 1, + .module_bit = OMAP24XX_EN_GPT7_SHIFT, + .module_offs = CORE_MOD, + .idlest_reg_id = 1, + .idlest_idle_bit = OMAP24XX_ST_GPT7_SHIFT, + }, + }, + .slaves = omap2420_timer7_slaves, + .slaves_cnt = ARRAY_SIZE(omap2420_timer7_slaves), + .class = &omap2420_timer_hwmod_class, + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP2420) +}; + +/* timer8 */ +static struct omap_hwmod omap2420_timer8_hwmod; +static struct omap_hwmod_irq_info omap2420_timer8_mpu_irqs[] = { + { .irq = 44, }, +}; + +static struct omap_hwmod_addr_space omap2420_timer8_addrs[] = { + { + .pa_start = 0x48082000, + .pa_end = 0x48082000 + SZ_1K - 1, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_core -> timer8 */ +static struct omap_hwmod_ocp_if omap2420_l4_core__timer8 = { + .master = &omap2420_l4_core_hwmod, + .slave = &omap2420_timer8_hwmod, + .clk = "gpt8_ick", + .addr = omap2420_timer8_addrs, + .addr_cnt = ARRAY_SIZE(omap2420_timer8_addrs), + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* timer8 slave port */ +static struct omap_hwmod_ocp_if *omap2420_timer8_slaves[] = { + &omap2420_l4_core__timer8, +}; + +/* timer8 hwmod */ +static struct omap_hwmod omap2420_timer8_hwmod = { + .name = "timer8", + .mpu_irqs = omap2420_timer8_mpu_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap2420_timer8_mpu_irqs), + .main_clk = "gpt8_fck", + .prcm = { + .omap2 = { + .prcm_reg_id = 1, + .module_bit = OMAP24XX_EN_GPT8_SHIFT, + .module_offs = CORE_MOD, + .idlest_reg_id = 1, + .idlest_idle_bit = OMAP24XX_ST_GPT8_SHIFT, + }, + }, + .slaves = omap2420_timer8_slaves, + .slaves_cnt = ARRAY_SIZE(omap2420_timer8_slaves), + .class = &omap2420_timer_hwmod_class, + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP2420) +}; + +/* timer9 */ +static struct omap_hwmod omap2420_timer9_hwmod; +static struct omap_hwmod_irq_info omap2420_timer9_mpu_irqs[] = { + { .irq = 45, }, +}; + +static struct omap_hwmod_addr_space omap2420_timer9_addrs[] = { + { + .pa_start = 0x48084000, + .pa_end = 0x48084000 + SZ_1K - 1, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_core -> timer9 */ +static struct omap_hwmod_ocp_if omap2420_l4_core__timer9 = { + .master = &omap2420_l4_core_hwmod, + .slave = &omap2420_timer9_hwmod, + .clk = "gpt9_ick", + .addr = omap2420_timer9_addrs, + .addr_cnt = ARRAY_SIZE(omap2420_timer9_addrs), + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* timer9 slave port */ +static struct omap_hwmod_ocp_if *omap2420_timer9_slaves[] = { + &omap2420_l4_core__timer9, +}; + +/* timer9 hwmod */ +static struct omap_hwmod omap2420_timer9_hwmod = { + .name = "timer9", + .mpu_irqs = omap2420_timer9_mpu_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap2420_timer9_mpu_irqs), + .main_clk = "gpt9_fck", + .prcm = { + .omap2 = { + .prcm_reg_id = 1, + .module_bit = OMAP24XX_EN_GPT9_SHIFT, + .module_offs = CORE_MOD, + .idlest_reg_id = 1, + .idlest_idle_bit = OMAP24XX_ST_GPT9_SHIFT, + }, + }, + .slaves = omap2420_timer9_slaves, + .slaves_cnt = ARRAY_SIZE(omap2420_timer9_slaves), + .class = &omap2420_timer_hwmod_class, + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP2420) +}; + +/* timer10 */ +static struct omap_hwmod omap2420_timer10_hwmod; +static struct omap_hwmod_irq_info omap2420_timer10_mpu_irqs[] = { + { .irq = 46, }, +}; + +static struct omap_hwmod_addr_space omap2420_timer10_addrs[] = { + { + .pa_start = 0x48086000, + .pa_end = 0x48086000 + SZ_1K - 1, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_core -> timer10 */ +static struct omap_hwmod_ocp_if omap2420_l4_core__timer10 = { + .master = &omap2420_l4_core_hwmod, + .slave = &omap2420_timer10_hwmod, + .clk = "gpt10_ick", + .addr = omap2420_timer10_addrs, + .addr_cnt = ARRAY_SIZE(omap2420_timer10_addrs), + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* timer10 slave port */ +static struct omap_hwmod_ocp_if *omap2420_timer10_slaves[] = { + &omap2420_l4_core__timer10, +}; + +/* timer10 hwmod */ +static struct omap_hwmod omap2420_timer10_hwmod = { + .name = "timer10", + .mpu_irqs = omap2420_timer10_mpu_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap2420_timer10_mpu_irqs), + .main_clk = "gpt10_fck", + .prcm = { + .omap2 = { + .prcm_reg_id = 1, + .module_bit = OMAP24XX_EN_GPT10_SHIFT, + .module_offs = CORE_MOD, + .idlest_reg_id = 1, + .idlest_idle_bit = OMAP24XX_ST_GPT10_SHIFT, + }, + }, + .slaves = omap2420_timer10_slaves, + .slaves_cnt = ARRAY_SIZE(omap2420_timer10_slaves), + .class = &omap2420_timer_hwmod_class, + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP2420) +}; + +/* timer11 */ +static struct omap_hwmod omap2420_timer11_hwmod; +static struct omap_hwmod_irq_info omap2420_timer11_mpu_irqs[] = { + { .irq = 47, }, +}; + +static struct omap_hwmod_addr_space omap2420_timer11_addrs[] = { + { + .pa_start = 0x48088000, + .pa_end = 0x48088000 + SZ_1K - 1, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_core -> timer11 */ +static struct omap_hwmod_ocp_if omap2420_l4_core__timer11 = { + .master = &omap2420_l4_core_hwmod, + .slave = &omap2420_timer11_hwmod, + .clk = "gpt11_ick", + .addr = omap2420_timer11_addrs, + .addr_cnt = ARRAY_SIZE(omap2420_timer11_addrs), + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* timer11 slave port */ +static struct omap_hwmod_ocp_if *omap2420_timer11_slaves[] = { + &omap2420_l4_core__timer11, +}; + +/* timer11 hwmod */ +static struct omap_hwmod omap2420_timer11_hwmod = { + .name = "timer11", + .mpu_irqs = omap2420_timer11_mpu_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap2420_timer11_mpu_irqs), + .main_clk = "gpt11_fck", + .prcm = { + .omap2 = { + .prcm_reg_id = 1, + .module_bit = OMAP24XX_EN_GPT11_SHIFT, + .module_offs = CORE_MOD, + .idlest_reg_id = 1, + .idlest_idle_bit = OMAP24XX_ST_GPT11_SHIFT, + }, + }, + .slaves = omap2420_timer11_slaves, + .slaves_cnt = ARRAY_SIZE(omap2420_timer11_slaves), + .class = &omap2420_timer_hwmod_class, + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP2420) +}; + +/* timer12 */ +static struct omap_hwmod omap2420_timer12_hwmod; +static struct omap_hwmod_irq_info omap2420_timer12_mpu_irqs[] = { + { .irq = 48, }, +}; + +static struct omap_hwmod_addr_space omap2420_timer12_addrs[] = { + { + .pa_start = 0x4808a000, + .pa_end = 0x4808a000 + SZ_1K - 1, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_core -> timer12 */ +static struct omap_hwmod_ocp_if omap2420_l4_core__timer12 = { + .master = &omap2420_l4_core_hwmod, + .slave = &omap2420_timer12_hwmod, + .clk = "gpt12_ick", + .addr = omap2420_timer12_addrs, + .addr_cnt = ARRAY_SIZE(omap2420_timer12_addrs), + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* timer12 slave port */ +static struct omap_hwmod_ocp_if *omap2420_timer12_slaves[] = { + &omap2420_l4_core__timer12, +}; + +/* timer12 hwmod */ +static struct omap_hwmod omap2420_timer12_hwmod = { + .name = "timer12", + .mpu_irqs = omap2420_timer12_mpu_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap2420_timer12_mpu_irqs), + .main_clk = "gpt12_fck", + .prcm = { + .omap2 = { + .prcm_reg_id = 1, + .module_bit = OMAP24XX_EN_GPT12_SHIFT, + .module_offs = CORE_MOD, + .idlest_reg_id = 1, + .idlest_idle_bit = OMAP24XX_ST_GPT12_SHIFT, + }, + }, + .slaves = omap2420_timer12_slaves, + .slaves_cnt = ARRAY_SIZE(omap2420_timer12_slaves), + .class = &omap2420_timer_hwmod_class, + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP2420) +}; + /* l4_wkup -> wd_timer2 */ static struct omap_hwmod_addr_space omap2420_wd_timer2_addrs[] = { { @@ -308,7 +988,7 @@ static struct omap_hwmod_class_sysconfig omap2420_wd_timer_sysc = { .sysc_offs = 0x0010, .syss_offs = 0x0014, .sysc_flags = (SYSC_HAS_EMUFREE | SYSC_HAS_SOFTRESET | - SYSC_HAS_AUTOIDLE), + SYSC_HAS_AUTOIDLE | SYSS_HAS_RESET_STATUS), .sysc_fields = &omap_hwmod_sysc_type1, }; @@ -349,7 +1029,7 @@ static struct omap_hwmod_class_sysconfig uart_sysc = { .syss_offs = 0x58, .sysc_flags = (SYSC_HAS_SIDLEMODE | SYSC_HAS_ENAWAKEUP | SYSC_HAS_SOFTRESET | - SYSC_HAS_AUTOIDLE), + SYSC_HAS_AUTOIDLE | SYSS_HAS_RESET_STATUS), .idlemodes = (SIDLE_FORCE | SIDLE_NO | SIDLE_SMART), .sysc_fields = &omap_hwmod_sysc_type1, }; @@ -470,12 +1150,298 @@ static struct omap_hwmod omap2420_uart3_hwmod = { .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP2420), }; +/* + * 'dss' class + * display sub-system + */ + +static struct omap_hwmod_class_sysconfig omap2420_dss_sysc = { + .rev_offs = 0x0000, + .sysc_offs = 0x0010, + .syss_offs = 0x0014, + .sysc_flags = (SYSC_HAS_SOFTRESET | SYSC_HAS_AUTOIDLE), + .sysc_fields = &omap_hwmod_sysc_type1, +}; + +static struct omap_hwmod_class omap2420_dss_hwmod_class = { + .name = "dss", + .sysc = &omap2420_dss_sysc, +}; + +/* dss */ +static struct omap_hwmod_irq_info omap2420_dss_irqs[] = { + { .irq = 25 }, +}; + +static struct omap_hwmod_dma_info omap2420_dss_sdma_chs[] = { + { .name = "dispc", .dma_req = 5 }, +}; + +/* dss */ +/* dss master ports */ +static struct omap_hwmod_ocp_if *omap2420_dss_masters[] = { + &omap2420_dss__l3, +}; + +static struct omap_hwmod_addr_space omap2420_dss_addrs[] = { + { + .pa_start = 0x48050000, + .pa_end = 0x480503FF, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_core -> dss */ +static struct omap_hwmod_ocp_if omap2420_l4_core__dss = { + .master = &omap2420_l4_core_hwmod, + .slave = &omap2420_dss_core_hwmod, + .clk = "dss_ick", + .addr = omap2420_dss_addrs, + .addr_cnt = ARRAY_SIZE(omap2420_dss_addrs), + .fw = { + .omap2 = { + .l4_fw_region = OMAP2420_L4_CORE_FW_DSS_CORE_REGION, + .flags = OMAP_FIREWALL_L4, + } + }, + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* dss slave ports */ +static struct omap_hwmod_ocp_if *omap2420_dss_slaves[] = { + &omap2420_l4_core__dss, +}; + +static struct omap_hwmod_opt_clk dss_opt_clks[] = { + { .role = "tv_clk", .clk = "dss_54m_fck" }, + { .role = "sys_clk", .clk = "dss2_fck" }, +}; + +static struct omap_hwmod omap2420_dss_core_hwmod = { + .name = "dss_core", + .class = &omap2420_dss_hwmod_class, + .main_clk = "dss1_fck", /* instead of dss_fck */ + .mpu_irqs = omap2420_dss_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap2420_dss_irqs), + .sdma_reqs = omap2420_dss_sdma_chs, + .sdma_reqs_cnt = ARRAY_SIZE(omap2420_dss_sdma_chs), + .prcm = { + .omap2 = { + .prcm_reg_id = 1, + .module_bit = OMAP24XX_EN_DSS1_SHIFT, + .module_offs = CORE_MOD, + .idlest_reg_id = 1, + .idlest_stdby_bit = OMAP24XX_ST_DSS_SHIFT, + }, + }, + .opt_clks = dss_opt_clks, + .opt_clks_cnt = ARRAY_SIZE(dss_opt_clks), + .slaves = omap2420_dss_slaves, + .slaves_cnt = ARRAY_SIZE(omap2420_dss_slaves), + .masters = omap2420_dss_masters, + .masters_cnt = ARRAY_SIZE(omap2420_dss_masters), + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP2420), + .flags = HWMOD_NO_IDLEST, +}; + +/* + * 'dispc' class + * display controller + */ + +static struct omap_hwmod_class_sysconfig omap2420_dispc_sysc = { + .rev_offs = 0x0000, + .sysc_offs = 0x0010, + .syss_offs = 0x0014, + .sysc_flags = (SYSC_HAS_SIDLEMODE | SYSC_HAS_MIDLEMODE | + SYSC_HAS_SOFTRESET | SYSC_HAS_AUTOIDLE), + .idlemodes = (SIDLE_FORCE | SIDLE_NO | SIDLE_SMART | + MSTANDBY_FORCE | MSTANDBY_NO | MSTANDBY_SMART), + .sysc_fields = &omap_hwmod_sysc_type1, +}; + +static struct omap_hwmod_class omap2420_dispc_hwmod_class = { + .name = "dispc", + .sysc = &omap2420_dispc_sysc, +}; + +static struct omap_hwmod_addr_space omap2420_dss_dispc_addrs[] = { + { + .pa_start = 0x48050400, + .pa_end = 0x480507FF, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_core -> dss_dispc */ +static struct omap_hwmod_ocp_if omap2420_l4_core__dss_dispc = { + .master = &omap2420_l4_core_hwmod, + .slave = &omap2420_dss_dispc_hwmod, + .clk = "dss_ick", + .addr = omap2420_dss_dispc_addrs, + .addr_cnt = ARRAY_SIZE(omap2420_dss_dispc_addrs), + .fw = { + .omap2 = { + .l4_fw_region = OMAP2420_L4_CORE_FW_DSS_DISPC_REGION, + .flags = OMAP_FIREWALL_L4, + } + }, + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* dss_dispc slave ports */ +static struct omap_hwmod_ocp_if *omap2420_dss_dispc_slaves[] = { + &omap2420_l4_core__dss_dispc, +}; + +static struct omap_hwmod omap2420_dss_dispc_hwmod = { + .name = "dss_dispc", + .class = &omap2420_dispc_hwmod_class, + .main_clk = "dss1_fck", + .prcm = { + .omap2 = { + .prcm_reg_id = 1, + .module_bit = OMAP24XX_EN_DSS1_SHIFT, + .module_offs = CORE_MOD, + .idlest_reg_id = 1, + .idlest_stdby_bit = OMAP24XX_ST_DSS_SHIFT, + }, + }, + .slaves = omap2420_dss_dispc_slaves, + .slaves_cnt = ARRAY_SIZE(omap2420_dss_dispc_slaves), + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP2420), + .flags = HWMOD_NO_IDLEST, +}; + +/* + * 'rfbi' class + * remote frame buffer interface + */ + +static struct omap_hwmod_class_sysconfig omap2420_rfbi_sysc = { + .rev_offs = 0x0000, + .sysc_offs = 0x0010, + .syss_offs = 0x0014, + .sysc_flags = (SYSC_HAS_SIDLEMODE | SYSC_HAS_SOFTRESET | + SYSC_HAS_AUTOIDLE), + .idlemodes = (SIDLE_FORCE | SIDLE_NO | SIDLE_SMART), + .sysc_fields = &omap_hwmod_sysc_type1, +}; + +static struct omap_hwmod_class omap2420_rfbi_hwmod_class = { + .name = "rfbi", + .sysc = &omap2420_rfbi_sysc, +}; + +static struct omap_hwmod_addr_space omap2420_dss_rfbi_addrs[] = { + { + .pa_start = 0x48050800, + .pa_end = 0x48050BFF, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_core -> dss_rfbi */ +static struct omap_hwmod_ocp_if omap2420_l4_core__dss_rfbi = { + .master = &omap2420_l4_core_hwmod, + .slave = &omap2420_dss_rfbi_hwmod, + .clk = "dss_ick", + .addr = omap2420_dss_rfbi_addrs, + .addr_cnt = ARRAY_SIZE(omap2420_dss_rfbi_addrs), + .fw = { + .omap2 = { + .l4_fw_region = OMAP2420_L4_CORE_FW_DSS_CORE_REGION, + .flags = OMAP_FIREWALL_L4, + } + }, + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* dss_rfbi slave ports */ +static struct omap_hwmod_ocp_if *omap2420_dss_rfbi_slaves[] = { + &omap2420_l4_core__dss_rfbi, +}; + +static struct omap_hwmod omap2420_dss_rfbi_hwmod = { + .name = "dss_rfbi", + .class = &omap2420_rfbi_hwmod_class, + .main_clk = "dss1_fck", + .prcm = { + .omap2 = { + .prcm_reg_id = 1, + .module_bit = OMAP24XX_EN_DSS1_SHIFT, + .module_offs = CORE_MOD, + }, + }, + .slaves = omap2420_dss_rfbi_slaves, + .slaves_cnt = ARRAY_SIZE(omap2420_dss_rfbi_slaves), + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP2420), + .flags = HWMOD_NO_IDLEST, +}; + +/* + * 'venc' class + * video encoder + */ + +static struct omap_hwmod_class omap2420_venc_hwmod_class = { + .name = "venc", +}; + +/* dss_venc */ +static struct omap_hwmod_addr_space omap2420_dss_venc_addrs[] = { + { + .pa_start = 0x48050C00, + .pa_end = 0x48050FFF, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_core -> dss_venc */ +static struct omap_hwmod_ocp_if omap2420_l4_core__dss_venc = { + .master = &omap2420_l4_core_hwmod, + .slave = &omap2420_dss_venc_hwmod, + .clk = "dss_54m_fck", + .addr = omap2420_dss_venc_addrs, + .addr_cnt = ARRAY_SIZE(omap2420_dss_venc_addrs), + .fw = { + .omap2 = { + .l4_fw_region = OMAP2420_L4_CORE_FW_DSS_VENC_REGION, + .flags = OMAP_FIREWALL_L4, + } + }, + .flags = OCPIF_SWSUP_IDLE, + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* dss_venc slave ports */ +static struct omap_hwmod_ocp_if *omap2420_dss_venc_slaves[] = { + &omap2420_l4_core__dss_venc, +}; + +static struct omap_hwmod omap2420_dss_venc_hwmod = { + .name = "dss_venc", + .class = &omap2420_venc_hwmod_class, + .main_clk = "dss1_fck", + .prcm = { + .omap2 = { + .prcm_reg_id = 1, + .module_bit = OMAP24XX_EN_DSS1_SHIFT, + .module_offs = CORE_MOD, + }, + }, + .slaves = omap2420_dss_venc_slaves, + .slaves_cnt = ARRAY_SIZE(omap2420_dss_venc_slaves), + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP2420), + .flags = HWMOD_NO_IDLEST, +}; + /* I2C common */ static struct omap_hwmod_class_sysconfig i2c_sysc = { .rev_offs = 0x00, .sysc_offs = 0x20, .syss_offs = 0x10, - .sysc_flags = SYSC_HAS_SOFTRESET, + .sysc_flags = (SYSC_HAS_SOFTRESET | SYSS_HAS_RESET_STATUS), .sysc_fields = &omap_hwmod_sysc_type1, }; @@ -647,7 +1613,8 @@ static struct omap_hwmod_class_sysconfig omap242x_gpio_sysc = { .sysc_offs = 0x0010, .syss_offs = 0x0014, .sysc_flags = (SYSC_HAS_ENAWAKEUP | SYSC_HAS_SIDLEMODE | - SYSC_HAS_SOFTRESET | SYSC_HAS_AUTOIDLE), + SYSC_HAS_SOFTRESET | SYSC_HAS_AUTOIDLE | + SYSS_HAS_RESET_STATUS), .idlemodes = (SIDLE_FORCE | SIDLE_NO | SIDLE_SMART), .sysc_fields = &omap_hwmod_sysc_type1, }; @@ -789,7 +1756,7 @@ static struct omap_hwmod_class_sysconfig omap2420_dma_sysc = { .syss_offs = 0x0028, .sysc_flags = (SYSC_HAS_SOFTRESET | SYSC_HAS_MIDLEMODE | SYSC_HAS_CLOCKACTIVITY | SYSC_HAS_EMUFREE | - SYSC_HAS_AUTOIDLE), + SYSC_HAS_AUTOIDLE | SYSS_HAS_RESET_STATUS), .idlemodes = (MSTANDBY_FORCE | MSTANDBY_NO | MSTANDBY_SMART), .sysc_fields = &omap_hwmod_sysc_type1, }; @@ -864,16 +1831,342 @@ static struct omap_hwmod omap2420_dma_system_hwmod = { .flags = HWMOD_NO_IDLEST, }; +/* + * 'mailbox' class + * mailbox module allowing communication between the on-chip processors + * using a queued mailbox-interrupt mechanism. + */ + +static struct omap_hwmod_class_sysconfig omap2420_mailbox_sysc = { + .rev_offs = 0x000, + .sysc_offs = 0x010, + .syss_offs = 0x014, + .sysc_flags = (SYSC_HAS_CLOCKACTIVITY | SYSC_HAS_SIDLEMODE | + SYSC_HAS_SOFTRESET | SYSC_HAS_AUTOIDLE), + .idlemodes = (SIDLE_FORCE | SIDLE_NO | SIDLE_SMART), + .sysc_fields = &omap_hwmod_sysc_type1, +}; + +static struct omap_hwmod_class omap2420_mailbox_hwmod_class = { + .name = "mailbox", + .sysc = &omap2420_mailbox_sysc, +}; + +/* mailbox */ +static struct omap_hwmod omap2420_mailbox_hwmod; +static struct omap_hwmod_irq_info omap2420_mailbox_irqs[] = { + { .name = "dsp", .irq = 26 }, + { .name = "iva", .irq = 34 }, +}; + +static struct omap_hwmod_addr_space omap2420_mailbox_addrs[] = { + { + .pa_start = 0x48094000, + .pa_end = 0x480941ff, + .flags = ADDR_TYPE_RT, + }, +}; + +/* l4_core -> mailbox */ +static struct omap_hwmod_ocp_if omap2420_l4_core__mailbox = { + .master = &omap2420_l4_core_hwmod, + .slave = &omap2420_mailbox_hwmod, + .addr = omap2420_mailbox_addrs, + .addr_cnt = ARRAY_SIZE(omap2420_mailbox_addrs), + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* mailbox slave ports */ +static struct omap_hwmod_ocp_if *omap2420_mailbox_slaves[] = { + &omap2420_l4_core__mailbox, +}; + +static struct omap_hwmod omap2420_mailbox_hwmod = { + .name = "mailbox", + .class = &omap2420_mailbox_hwmod_class, + .mpu_irqs = omap2420_mailbox_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap2420_mailbox_irqs), + .main_clk = "mailboxes_ick", + .prcm = { + .omap2 = { + .prcm_reg_id = 1, + .module_bit = OMAP24XX_EN_MAILBOXES_SHIFT, + .module_offs = CORE_MOD, + .idlest_reg_id = 1, + .idlest_idle_bit = OMAP24XX_ST_MAILBOXES_SHIFT, + }, + }, + .slaves = omap2420_mailbox_slaves, + .slaves_cnt = ARRAY_SIZE(omap2420_mailbox_slaves), + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP2420), +}; + +/* + * 'mcspi' class + * multichannel serial port interface (mcspi) / master/slave synchronous serial + * bus + */ + +static struct omap_hwmod_class_sysconfig omap2420_mcspi_sysc = { + .rev_offs = 0x0000, + .sysc_offs = 0x0010, + .syss_offs = 0x0014, + .sysc_flags = (SYSC_HAS_CLOCKACTIVITY | SYSC_HAS_SIDLEMODE | + SYSC_HAS_ENAWAKEUP | SYSC_HAS_SOFTRESET | + SYSC_HAS_AUTOIDLE | SYSS_HAS_RESET_STATUS), + .idlemodes = (SIDLE_FORCE | SIDLE_NO | SIDLE_SMART), + .sysc_fields = &omap_hwmod_sysc_type1, +}; + +static struct omap_hwmod_class omap2420_mcspi_class = { + .name = "mcspi", + .sysc = &omap2420_mcspi_sysc, + .rev = OMAP2_MCSPI_REV, +}; + +/* mcspi1 */ +static struct omap_hwmod_irq_info omap2420_mcspi1_mpu_irqs[] = { + { .irq = 65 }, +}; + +static struct omap_hwmod_dma_info omap2420_mcspi1_sdma_reqs[] = { + { .name = "tx0", .dma_req = 35 }, /* DMA_SPI1_TX0 */ + { .name = "rx0", .dma_req = 36 }, /* DMA_SPI1_RX0 */ + { .name = "tx1", .dma_req = 37 }, /* DMA_SPI1_TX1 */ + { .name = "rx1", .dma_req = 38 }, /* DMA_SPI1_RX1 */ + { .name = "tx2", .dma_req = 39 }, /* DMA_SPI1_TX2 */ + { .name = "rx2", .dma_req = 40 }, /* DMA_SPI1_RX2 */ + { .name = "tx3", .dma_req = 41 }, /* DMA_SPI1_TX3 */ + { .name = "rx3", .dma_req = 42 }, /* DMA_SPI1_RX3 */ +}; + +static struct omap_hwmod_ocp_if *omap2420_mcspi1_slaves[] = { + &omap2420_l4_core__mcspi1, +}; + +static struct omap2_mcspi_dev_attr omap_mcspi1_dev_attr = { + .num_chipselect = 4, +}; + +static struct omap_hwmod omap2420_mcspi1_hwmod = { + .name = "mcspi1_hwmod", + .mpu_irqs = omap2420_mcspi1_mpu_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap2420_mcspi1_mpu_irqs), + .sdma_reqs = omap2420_mcspi1_sdma_reqs, + .sdma_reqs_cnt = ARRAY_SIZE(omap2420_mcspi1_sdma_reqs), + .main_clk = "mcspi1_fck", + .prcm = { + .omap2 = { + .module_offs = CORE_MOD, + .prcm_reg_id = 1, + .module_bit = OMAP24XX_EN_MCSPI1_SHIFT, + .idlest_reg_id = 1, + .idlest_idle_bit = OMAP24XX_ST_MCSPI1_SHIFT, + }, + }, + .slaves = omap2420_mcspi1_slaves, + .slaves_cnt = ARRAY_SIZE(omap2420_mcspi1_slaves), + .class = &omap2420_mcspi_class, + .dev_attr = &omap_mcspi1_dev_attr, + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP2420), +}; + +/* mcspi2 */ +static struct omap_hwmod_irq_info omap2420_mcspi2_mpu_irqs[] = { + { .irq = 66 }, +}; + +static struct omap_hwmod_dma_info omap2420_mcspi2_sdma_reqs[] = { + { .name = "tx0", .dma_req = 43 }, /* DMA_SPI2_TX0 */ + { .name = "rx0", .dma_req = 44 }, /* DMA_SPI2_RX0 */ + { .name = "tx1", .dma_req = 45 }, /* DMA_SPI2_TX1 */ + { .name = "rx1", .dma_req = 46 }, /* DMA_SPI2_RX1 */ +}; + +static struct omap_hwmod_ocp_if *omap2420_mcspi2_slaves[] = { + &omap2420_l4_core__mcspi2, +}; + +static struct omap2_mcspi_dev_attr omap_mcspi2_dev_attr = { + .num_chipselect = 2, +}; + +static struct omap_hwmod omap2420_mcspi2_hwmod = { + .name = "mcspi2_hwmod", + .mpu_irqs = omap2420_mcspi2_mpu_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap2420_mcspi2_mpu_irqs), + .sdma_reqs = omap2420_mcspi2_sdma_reqs, + .sdma_reqs_cnt = ARRAY_SIZE(omap2420_mcspi2_sdma_reqs), + .main_clk = "mcspi2_fck", + .prcm = { + .omap2 = { + .module_offs = CORE_MOD, + .prcm_reg_id = 1, + .module_bit = OMAP24XX_EN_MCSPI2_SHIFT, + .idlest_reg_id = 1, + .idlest_idle_bit = OMAP24XX_ST_MCSPI2_SHIFT, + }, + }, + .slaves = omap2420_mcspi2_slaves, + .slaves_cnt = ARRAY_SIZE(omap2420_mcspi2_slaves), + .class = &omap2420_mcspi_class, + .dev_attr = &omap_mcspi2_dev_attr, + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP2420), +}; + +/* + * 'mcbsp' class + * multi channel buffered serial port controller + */ + +static struct omap_hwmod_class omap2420_mcbsp_hwmod_class = { + .name = "mcbsp", +}; + +/* mcbsp1 */ +static struct omap_hwmod_irq_info omap2420_mcbsp1_irqs[] = { + { .name = "tx", .irq = 59 }, + { .name = "rx", .irq = 60 }, +}; + +static struct omap_hwmod_dma_info omap2420_mcbsp1_sdma_chs[] = { + { .name = "rx", .dma_req = 32 }, + { .name = "tx", .dma_req = 31 }, +}; + +static struct omap_hwmod_addr_space omap2420_mcbsp1_addrs[] = { + { + .name = "mpu", + .pa_start = 0x48074000, + .pa_end = 0x480740ff, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_core -> mcbsp1 */ +static struct omap_hwmod_ocp_if omap2420_l4_core__mcbsp1 = { + .master = &omap2420_l4_core_hwmod, + .slave = &omap2420_mcbsp1_hwmod, + .clk = "mcbsp1_ick", + .addr = omap2420_mcbsp1_addrs, + .addr_cnt = ARRAY_SIZE(omap2420_mcbsp1_addrs), + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* mcbsp1 slave ports */ +static struct omap_hwmod_ocp_if *omap2420_mcbsp1_slaves[] = { + &omap2420_l4_core__mcbsp1, +}; + +static struct omap_hwmod omap2420_mcbsp1_hwmod = { + .name = "mcbsp1", + .class = &omap2420_mcbsp_hwmod_class, + .mpu_irqs = omap2420_mcbsp1_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap2420_mcbsp1_irqs), + .sdma_reqs = omap2420_mcbsp1_sdma_chs, + .sdma_reqs_cnt = ARRAY_SIZE(omap2420_mcbsp1_sdma_chs), + .main_clk = "mcbsp1_fck", + .prcm = { + .omap2 = { + .prcm_reg_id = 1, + .module_bit = OMAP24XX_EN_MCBSP1_SHIFT, + .module_offs = CORE_MOD, + .idlest_reg_id = 1, + .idlest_idle_bit = OMAP24XX_ST_MCBSP1_SHIFT, + }, + }, + .slaves = omap2420_mcbsp1_slaves, + .slaves_cnt = ARRAY_SIZE(omap2420_mcbsp1_slaves), + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP2420), +}; + +/* mcbsp2 */ +static struct omap_hwmod_irq_info omap2420_mcbsp2_irqs[] = { + { .name = "tx", .irq = 62 }, + { .name = "rx", .irq = 63 }, +}; + +static struct omap_hwmod_dma_info omap2420_mcbsp2_sdma_chs[] = { + { .name = "rx", .dma_req = 34 }, + { .name = "tx", .dma_req = 33 }, +}; + +static struct omap_hwmod_addr_space omap2420_mcbsp2_addrs[] = { + { + .name = "mpu", + .pa_start = 0x48076000, + .pa_end = 0x480760ff, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_core -> mcbsp2 */ +static struct omap_hwmod_ocp_if omap2420_l4_core__mcbsp2 = { + .master = &omap2420_l4_core_hwmod, + .slave = &omap2420_mcbsp2_hwmod, + .clk = "mcbsp2_ick", + .addr = omap2420_mcbsp2_addrs, + .addr_cnt = ARRAY_SIZE(omap2420_mcbsp2_addrs), + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* mcbsp2 slave ports */ +static struct omap_hwmod_ocp_if *omap2420_mcbsp2_slaves[] = { + &omap2420_l4_core__mcbsp2, +}; + +static struct omap_hwmod omap2420_mcbsp2_hwmod = { + .name = "mcbsp2", + .class = &omap2420_mcbsp_hwmod_class, + .mpu_irqs = omap2420_mcbsp2_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap2420_mcbsp2_irqs), + .sdma_reqs = omap2420_mcbsp2_sdma_chs, + .sdma_reqs_cnt = ARRAY_SIZE(omap2420_mcbsp2_sdma_chs), + .main_clk = "mcbsp2_fck", + .prcm = { + .omap2 = { + .prcm_reg_id = 1, + .module_bit = OMAP24XX_EN_MCBSP2_SHIFT, + .module_offs = CORE_MOD, + .idlest_reg_id = 1, + .idlest_idle_bit = OMAP24XX_ST_MCBSP2_SHIFT, + }, + }, + .slaves = omap2420_mcbsp2_slaves, + .slaves_cnt = ARRAY_SIZE(omap2420_mcbsp2_slaves), + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP2420), +}; + static __initdata struct omap_hwmod *omap2420_hwmods[] = { &omap2420_l3_main_hwmod, &omap2420_l4_core_hwmod, &omap2420_l4_wkup_hwmod, &omap2420_mpu_hwmod, &omap2420_iva_hwmod, + + &omap2420_timer1_hwmod, + &omap2420_timer2_hwmod, + &omap2420_timer3_hwmod, + &omap2420_timer4_hwmod, + &omap2420_timer5_hwmod, + &omap2420_timer6_hwmod, + &omap2420_timer7_hwmod, + &omap2420_timer8_hwmod, + &omap2420_timer9_hwmod, + &omap2420_timer10_hwmod, + &omap2420_timer11_hwmod, + &omap2420_timer12_hwmod, + &omap2420_wd_timer2_hwmod, &omap2420_uart1_hwmod, &omap2420_uart2_hwmod, &omap2420_uart3_hwmod, + /* dss class */ + &omap2420_dss_core_hwmod, + &omap2420_dss_dispc_hwmod, + &omap2420_dss_rfbi_hwmod, + &omap2420_dss_venc_hwmod, + /* i2c class */ &omap2420_i2c1_hwmod, &omap2420_i2c2_hwmod, @@ -885,10 +2178,21 @@ static __initdata struct omap_hwmod *omap2420_hwmods[] = { /* dma_system class*/ &omap2420_dma_system_hwmod, + + /* mailbox class */ + &omap2420_mailbox_hwmod, + + /* mcbsp class */ + &omap2420_mcbsp1_hwmod, + &omap2420_mcbsp2_hwmod, + + /* mcspi class */ + &omap2420_mcspi1_hwmod, + &omap2420_mcspi2_hwmod, NULL, }; int __init omap2420_hwmod_init(void) { - return omap_hwmod_init(omap2420_hwmods); + return omap_hwmod_register(omap2420_hwmods); } diff --git a/arch/arm/mach-omap2/omap_hwmod_2430_data.c b/arch/arm/mach-omap2/omap_hwmod_2430_data.c index 8ecfbcde13b..0fdf2cabfb1 100644 --- a/arch/arm/mach-omap2/omap_hwmod_2430_data.c +++ b/arch/arm/mach-omap2/omap_hwmod_2430_data.c @@ -18,6 +18,11 @@ #include <plat/serial.h> #include <plat/i2c.h> #include <plat/gpio.h> +#include <plat/mcbsp.h> +#include <plat/mcspi.h> +#include <plat/dmtimer.h> +#include <plat/mmc.h> +#include <plat/l3_2xxx.h> #include "omap_hwmod_common_data.h" @@ -38,6 +43,10 @@ static struct omap_hwmod omap2430_mpu_hwmod; static struct omap_hwmod omap2430_iva_hwmod; static struct omap_hwmod omap2430_l3_main_hwmod; static struct omap_hwmod omap2430_l4_core_hwmod; +static struct omap_hwmod omap2430_dss_core_hwmod; +static struct omap_hwmod omap2430_dss_dispc_hwmod; +static struct omap_hwmod omap2430_dss_rfbi_hwmod; +static struct omap_hwmod omap2430_dss_venc_hwmod; static struct omap_hwmod omap2430_wd_timer2_hwmod; static struct omap_hwmod omap2430_gpio1_hwmod; static struct omap_hwmod omap2430_gpio2_hwmod; @@ -45,6 +54,16 @@ static struct omap_hwmod omap2430_gpio3_hwmod; static struct omap_hwmod omap2430_gpio4_hwmod; static struct omap_hwmod omap2430_gpio5_hwmod; static struct omap_hwmod omap2430_dma_system_hwmod; +static struct omap_hwmod omap2430_mcbsp1_hwmod; +static struct omap_hwmod omap2430_mcbsp2_hwmod; +static struct omap_hwmod omap2430_mcbsp3_hwmod; +static struct omap_hwmod omap2430_mcbsp4_hwmod; +static struct omap_hwmod omap2430_mcbsp5_hwmod; +static struct omap_hwmod omap2430_mcspi1_hwmod; +static struct omap_hwmod omap2430_mcspi2_hwmod; +static struct omap_hwmod omap2430_mcspi3_hwmod; +static struct omap_hwmod omap2430_mmc1_hwmod; +static struct omap_hwmod omap2430_mmc2_hwmod; /* L3 -> L4_CORE interface */ static struct omap_hwmod_ocp_if omap2430_l3_main__l4_core = { @@ -65,6 +84,19 @@ static struct omap_hwmod_ocp_if *omap2430_l3_main_slaves[] = { &omap2430_mpu__l3_main, }; +/* DSS -> l3 */ +static struct omap_hwmod_ocp_if omap2430_dss__l3 = { + .master = &omap2430_dss_core_hwmod, + .slave = &omap2430_l3_main_hwmod, + .fw = { + .omap2 = { + .l3_perm_bit = OMAP2_L3_CORE_FW_CONNID_DSS, + .flags = OMAP_FIREWALL_L3, + } + }, + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + /* Master interfaces on the L3 interconnect */ static struct omap_hwmod_ocp_if *omap2430_l3_main_masters[] = { &omap2430_l3_main__l4_core, @@ -89,6 +121,16 @@ static struct omap_hwmod omap2430_uart3_hwmod; static struct omap_hwmod omap2430_i2c1_hwmod; static struct omap_hwmod omap2430_i2c2_hwmod; +static struct omap_hwmod omap2430_usbhsotg_hwmod; + +/* l3_core -> usbhsotg interface */ +static struct omap_hwmod_ocp_if omap2430_usbhsotg__l3 = { + .master = &omap2430_usbhsotg_hwmod, + .slave = &omap2430_l3_main_hwmod, + .clk = "core_l3_ck", + .user = OCP_USER_MPU, +}; + /* I2C IP block address space length (in bytes) */ #define OMAP2_I2C_AS_LEN 128 @@ -189,6 +231,71 @@ static struct omap_hwmod_ocp_if omap2_l4_core__uart3 = { .user = OCP_USER_MPU | OCP_USER_SDMA, }; +/* +* usbhsotg interface data +*/ +static struct omap_hwmod_addr_space omap2430_usbhsotg_addrs[] = { + { + .pa_start = OMAP243X_HS_BASE, + .pa_end = OMAP243X_HS_BASE + SZ_4K - 1, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_core ->usbhsotg interface */ +static struct omap_hwmod_ocp_if omap2430_l4_core__usbhsotg = { + .master = &omap2430_l4_core_hwmod, + .slave = &omap2430_usbhsotg_hwmod, + .clk = "usb_l4_ick", + .addr = omap2430_usbhsotg_addrs, + .addr_cnt = ARRAY_SIZE(omap2430_usbhsotg_addrs), + .user = OCP_USER_MPU, +}; + +static struct omap_hwmod_ocp_if *omap2430_usbhsotg_masters[] = { + &omap2430_usbhsotg__l3, +}; + +static struct omap_hwmod_ocp_if *omap2430_usbhsotg_slaves[] = { + &omap2430_l4_core__usbhsotg, +}; + +/* L4 CORE -> MMC1 interface */ +static struct omap_hwmod_addr_space omap2430_mmc1_addr_space[] = { + { + .pa_start = 0x4809c000, + .pa_end = 0x4809c1ff, + .flags = ADDR_TYPE_RT, + }, +}; + +static struct omap_hwmod_ocp_if omap2430_l4_core__mmc1 = { + .master = &omap2430_l4_core_hwmod, + .slave = &omap2430_mmc1_hwmod, + .clk = "mmchs1_ick", + .addr = omap2430_mmc1_addr_space, + .addr_cnt = ARRAY_SIZE(omap2430_mmc1_addr_space), + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* L4 CORE -> MMC2 interface */ +static struct omap_hwmod_addr_space omap2430_mmc2_addr_space[] = { + { + .pa_start = 0x480b4000, + .pa_end = 0x480b41ff, + .flags = ADDR_TYPE_RT, + }, +}; + +static struct omap_hwmod_ocp_if omap2430_l4_core__mmc2 = { + .master = &omap2430_l4_core_hwmod, + .slave = &omap2430_mmc2_hwmod, + .addr = omap2430_mmc2_addr_space, + .clk = "mmchs2_ick", + .addr_cnt = ARRAY_SIZE(omap2430_mmc2_addr_space), + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + /* Slave interfaces on the L4_CORE interconnect */ static struct omap_hwmod_ocp_if *omap2430_l4_core_slaves[] = { &omap2430_l3_main__l4_core, @@ -197,6 +304,8 @@ static struct omap_hwmod_ocp_if *omap2430_l4_core_slaves[] = { /* Master interfaces on the L4_CORE interconnect */ static struct omap_hwmod_ocp_if *omap2430_l4_core_masters[] = { &omap2430_l4_core__l4_wkup, + &omap2430_l4_core__mmc1, + &omap2430_l4_core__mmc2, }; /* L4 CORE */ @@ -223,6 +332,60 @@ static struct omap_hwmod_ocp_if *omap2430_l4_wkup_slaves[] = { static struct omap_hwmod_ocp_if *omap2430_l4_wkup_masters[] = { }; +/* l4 core -> mcspi1 interface */ +static struct omap_hwmod_addr_space omap2430_mcspi1_addr_space[] = { + { + .pa_start = 0x48098000, + .pa_end = 0x480980ff, + .flags = ADDR_TYPE_RT, + }, +}; + +static struct omap_hwmod_ocp_if omap2430_l4_core__mcspi1 = { + .master = &omap2430_l4_core_hwmod, + .slave = &omap2430_mcspi1_hwmod, + .clk = "mcspi1_ick", + .addr = omap2430_mcspi1_addr_space, + .addr_cnt = ARRAY_SIZE(omap2430_mcspi1_addr_space), + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* l4 core -> mcspi2 interface */ +static struct omap_hwmod_addr_space omap2430_mcspi2_addr_space[] = { + { + .pa_start = 0x4809a000, + .pa_end = 0x4809a0ff, + .flags = ADDR_TYPE_RT, + }, +}; + +static struct omap_hwmod_ocp_if omap2430_l4_core__mcspi2 = { + .master = &omap2430_l4_core_hwmod, + .slave = &omap2430_mcspi2_hwmod, + .clk = "mcspi2_ick", + .addr = omap2430_mcspi2_addr_space, + .addr_cnt = ARRAY_SIZE(omap2430_mcspi2_addr_space), + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* l4 core -> mcspi3 interface */ +static struct omap_hwmod_addr_space omap2430_mcspi3_addr_space[] = { + { + .pa_start = 0x480b8000, + .pa_end = 0x480b80ff, + .flags = ADDR_TYPE_RT, + }, +}; + +static struct omap_hwmod_ocp_if omap2430_l4_core__mcspi3 = { + .master = &omap2430_l4_core_hwmod, + .slave = &omap2430_mcspi3_hwmod, + .clk = "mcspi3_ick", + .addr = omap2430_mcspi3_addr_space, + .addr_cnt = ARRAY_SIZE(omap2430_mcspi3_addr_space), + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + /* L4 WKUP */ static struct omap_hwmod omap2430_l4_wkup_hwmod = { .name = "l4_wkup", @@ -278,6 +441,624 @@ static struct omap_hwmod omap2430_iva_hwmod = { .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP2430) }; +/* Timer Common */ +static struct omap_hwmod_class_sysconfig omap2430_timer_sysc = { + .rev_offs = 0x0000, + .sysc_offs = 0x0010, + .syss_offs = 0x0014, + .sysc_flags = (SYSC_HAS_SIDLEMODE | SYSC_HAS_CLOCKACTIVITY | + SYSC_HAS_ENAWAKEUP | SYSC_HAS_SOFTRESET | + SYSC_HAS_AUTOIDLE), + .idlemodes = (SIDLE_FORCE | SIDLE_NO | SIDLE_SMART), + .sysc_fields = &omap_hwmod_sysc_type1, +}; + +static struct omap_hwmod_class omap2430_timer_hwmod_class = { + .name = "timer", + .sysc = &omap2430_timer_sysc, + .rev = OMAP_TIMER_IP_VERSION_1, +}; + +/* timer1 */ +static struct omap_hwmod omap2430_timer1_hwmod; +static struct omap_hwmod_irq_info omap2430_timer1_mpu_irqs[] = { + { .irq = 37, }, +}; + +static struct omap_hwmod_addr_space omap2430_timer1_addrs[] = { + { + .pa_start = 0x49018000, + .pa_end = 0x49018000 + SZ_1K - 1, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_wkup -> timer1 */ +static struct omap_hwmod_ocp_if omap2430_l4_wkup__timer1 = { + .master = &omap2430_l4_wkup_hwmod, + .slave = &omap2430_timer1_hwmod, + .clk = "gpt1_ick", + .addr = omap2430_timer1_addrs, + .addr_cnt = ARRAY_SIZE(omap2430_timer1_addrs), + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* timer1 slave port */ +static struct omap_hwmod_ocp_if *omap2430_timer1_slaves[] = { + &omap2430_l4_wkup__timer1, +}; + +/* timer1 hwmod */ +static struct omap_hwmod omap2430_timer1_hwmod = { + .name = "timer1", + .mpu_irqs = omap2430_timer1_mpu_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap2430_timer1_mpu_irqs), + .main_clk = "gpt1_fck", + .prcm = { + .omap2 = { + .prcm_reg_id = 1, + .module_bit = OMAP24XX_EN_GPT1_SHIFT, + .module_offs = WKUP_MOD, + .idlest_reg_id = 1, + .idlest_idle_bit = OMAP24XX_ST_GPT1_SHIFT, + }, + }, + .slaves = omap2430_timer1_slaves, + .slaves_cnt = ARRAY_SIZE(omap2430_timer1_slaves), + .class = &omap2430_timer_hwmod_class, + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP2430) +}; + +/* timer2 */ +static struct omap_hwmod omap2430_timer2_hwmod; +static struct omap_hwmod_irq_info omap2430_timer2_mpu_irqs[] = { + { .irq = 38, }, +}; + +static struct omap_hwmod_addr_space omap2430_timer2_addrs[] = { + { + .pa_start = 0x4802a000, + .pa_end = 0x4802a000 + SZ_1K - 1, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_core -> timer2 */ +static struct omap_hwmod_ocp_if omap2430_l4_core__timer2 = { + .master = &omap2430_l4_core_hwmod, + .slave = &omap2430_timer2_hwmod, + .clk = "gpt2_ick", + .addr = omap2430_timer2_addrs, + .addr_cnt = ARRAY_SIZE(omap2430_timer2_addrs), + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* timer2 slave port */ +static struct omap_hwmod_ocp_if *omap2430_timer2_slaves[] = { + &omap2430_l4_core__timer2, +}; + +/* timer2 hwmod */ +static struct omap_hwmod omap2430_timer2_hwmod = { + .name = "timer2", + .mpu_irqs = omap2430_timer2_mpu_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap2430_timer2_mpu_irqs), + .main_clk = "gpt2_fck", + .prcm = { + .omap2 = { + .prcm_reg_id = 1, + .module_bit = OMAP24XX_EN_GPT2_SHIFT, + .module_offs = CORE_MOD, + .idlest_reg_id = 1, + .idlest_idle_bit = OMAP24XX_ST_GPT2_SHIFT, + }, + }, + .slaves = omap2430_timer2_slaves, + .slaves_cnt = ARRAY_SIZE(omap2430_timer2_slaves), + .class = &omap2430_timer_hwmod_class, + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP2430) +}; + +/* timer3 */ +static struct omap_hwmod omap2430_timer3_hwmod; +static struct omap_hwmod_irq_info omap2430_timer3_mpu_irqs[] = { + { .irq = 39, }, +}; + +static struct omap_hwmod_addr_space omap2430_timer3_addrs[] = { + { + .pa_start = 0x48078000, + .pa_end = 0x48078000 + SZ_1K - 1, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_core -> timer3 */ +static struct omap_hwmod_ocp_if omap2430_l4_core__timer3 = { + .master = &omap2430_l4_core_hwmod, + .slave = &omap2430_timer3_hwmod, + .clk = "gpt3_ick", + .addr = omap2430_timer3_addrs, + .addr_cnt = ARRAY_SIZE(omap2430_timer3_addrs), + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* timer3 slave port */ +static struct omap_hwmod_ocp_if *omap2430_timer3_slaves[] = { + &omap2430_l4_core__timer3, +}; + +/* timer3 hwmod */ +static struct omap_hwmod omap2430_timer3_hwmod = { + .name = "timer3", + .mpu_irqs = omap2430_timer3_mpu_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap2430_timer3_mpu_irqs), + .main_clk = "gpt3_fck", + .prcm = { + .omap2 = { + .prcm_reg_id = 1, + .module_bit = OMAP24XX_EN_GPT3_SHIFT, + .module_offs = CORE_MOD, + .idlest_reg_id = 1, + .idlest_idle_bit = OMAP24XX_ST_GPT3_SHIFT, + }, + }, + .slaves = omap2430_timer3_slaves, + .slaves_cnt = ARRAY_SIZE(omap2430_timer3_slaves), + .class = &omap2430_timer_hwmod_class, + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP2430) +}; + +/* timer4 */ +static struct omap_hwmod omap2430_timer4_hwmod; +static struct omap_hwmod_irq_info omap2430_timer4_mpu_irqs[] = { + { .irq = 40, }, +}; + +static struct omap_hwmod_addr_space omap2430_timer4_addrs[] = { + { + .pa_start = 0x4807a000, + .pa_end = 0x4807a000 + SZ_1K - 1, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_core -> timer4 */ +static struct omap_hwmod_ocp_if omap2430_l4_core__timer4 = { + .master = &omap2430_l4_core_hwmod, + .slave = &omap2430_timer4_hwmod, + .clk = "gpt4_ick", + .addr = omap2430_timer4_addrs, + .addr_cnt = ARRAY_SIZE(omap2430_timer4_addrs), + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* timer4 slave port */ +static struct omap_hwmod_ocp_if *omap2430_timer4_slaves[] = { + &omap2430_l4_core__timer4, +}; + +/* timer4 hwmod */ +static struct omap_hwmod omap2430_timer4_hwmod = { + .name = "timer4", + .mpu_irqs = omap2430_timer4_mpu_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap2430_timer4_mpu_irqs), + .main_clk = "gpt4_fck", + .prcm = { + .omap2 = { + .prcm_reg_id = 1, + .module_bit = OMAP24XX_EN_GPT4_SHIFT, + .module_offs = CORE_MOD, + .idlest_reg_id = 1, + .idlest_idle_bit = OMAP24XX_ST_GPT4_SHIFT, + }, + }, + .slaves = omap2430_timer4_slaves, + .slaves_cnt = ARRAY_SIZE(omap2430_timer4_slaves), + .class = &omap2430_timer_hwmod_class, + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP2430) +}; + +/* timer5 */ +static struct omap_hwmod omap2430_timer5_hwmod; +static struct omap_hwmod_irq_info omap2430_timer5_mpu_irqs[] = { + { .irq = 41, }, +}; + +static struct omap_hwmod_addr_space omap2430_timer5_addrs[] = { + { + .pa_start = 0x4807c000, + .pa_end = 0x4807c000 + SZ_1K - 1, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_core -> timer5 */ +static struct omap_hwmod_ocp_if omap2430_l4_core__timer5 = { + .master = &omap2430_l4_core_hwmod, + .slave = &omap2430_timer5_hwmod, + .clk = "gpt5_ick", + .addr = omap2430_timer5_addrs, + .addr_cnt = ARRAY_SIZE(omap2430_timer5_addrs), + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* timer5 slave port */ +static struct omap_hwmod_ocp_if *omap2430_timer5_slaves[] = { + &omap2430_l4_core__timer5, +}; + +/* timer5 hwmod */ +static struct omap_hwmod omap2430_timer5_hwmod = { + .name = "timer5", + .mpu_irqs = omap2430_timer5_mpu_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap2430_timer5_mpu_irqs), + .main_clk = "gpt5_fck", + .prcm = { + .omap2 = { + .prcm_reg_id = 1, + .module_bit = OMAP24XX_EN_GPT5_SHIFT, + .module_offs = CORE_MOD, + .idlest_reg_id = 1, + .idlest_idle_bit = OMAP24XX_ST_GPT5_SHIFT, + }, + }, + .slaves = omap2430_timer5_slaves, + .slaves_cnt = ARRAY_SIZE(omap2430_timer5_slaves), + .class = &omap2430_timer_hwmod_class, + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP2430) +}; + +/* timer6 */ +static struct omap_hwmod omap2430_timer6_hwmod; +static struct omap_hwmod_irq_info omap2430_timer6_mpu_irqs[] = { + { .irq = 42, }, +}; + +static struct omap_hwmod_addr_space omap2430_timer6_addrs[] = { + { + .pa_start = 0x4807e000, + .pa_end = 0x4807e000 + SZ_1K - 1, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_core -> timer6 */ +static struct omap_hwmod_ocp_if omap2430_l4_core__timer6 = { + .master = &omap2430_l4_core_hwmod, + .slave = &omap2430_timer6_hwmod, + .clk = "gpt6_ick", + .addr = omap2430_timer6_addrs, + .addr_cnt = ARRAY_SIZE(omap2430_timer6_addrs), + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* timer6 slave port */ +static struct omap_hwmod_ocp_if *omap2430_timer6_slaves[] = { + &omap2430_l4_core__timer6, +}; + +/* timer6 hwmod */ +static struct omap_hwmod omap2430_timer6_hwmod = { + .name = "timer6", + .mpu_irqs = omap2430_timer6_mpu_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap2430_timer6_mpu_irqs), + .main_clk = "gpt6_fck", + .prcm = { + .omap2 = { + .prcm_reg_id = 1, + .module_bit = OMAP24XX_EN_GPT6_SHIFT, + .module_offs = CORE_MOD, + .idlest_reg_id = 1, + .idlest_idle_bit = OMAP24XX_ST_GPT6_SHIFT, + }, + }, + .slaves = omap2430_timer6_slaves, + .slaves_cnt = ARRAY_SIZE(omap2430_timer6_slaves), + .class = &omap2430_timer_hwmod_class, + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP2430) +}; + +/* timer7 */ +static struct omap_hwmod omap2430_timer7_hwmod; +static struct omap_hwmod_irq_info omap2430_timer7_mpu_irqs[] = { + { .irq = 43, }, +}; + +static struct omap_hwmod_addr_space omap2430_timer7_addrs[] = { + { + .pa_start = 0x48080000, + .pa_end = 0x48080000 + SZ_1K - 1, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_core -> timer7 */ +static struct omap_hwmod_ocp_if omap2430_l4_core__timer7 = { + .master = &omap2430_l4_core_hwmod, + .slave = &omap2430_timer7_hwmod, + .clk = "gpt7_ick", + .addr = omap2430_timer7_addrs, + .addr_cnt = ARRAY_SIZE(omap2430_timer7_addrs), + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* timer7 slave port */ +static struct omap_hwmod_ocp_if *omap2430_timer7_slaves[] = { + &omap2430_l4_core__timer7, +}; + +/* timer7 hwmod */ +static struct omap_hwmod omap2430_timer7_hwmod = { + .name = "timer7", + .mpu_irqs = omap2430_timer7_mpu_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap2430_timer7_mpu_irqs), + .main_clk = "gpt7_fck", + .prcm = { + .omap2 = { + .prcm_reg_id = 1, + .module_bit = OMAP24XX_EN_GPT7_SHIFT, + .module_offs = CORE_MOD, + .idlest_reg_id = 1, + .idlest_idle_bit = OMAP24XX_ST_GPT7_SHIFT, + }, + }, + .slaves = omap2430_timer7_slaves, + .slaves_cnt = ARRAY_SIZE(omap2430_timer7_slaves), + .class = &omap2430_timer_hwmod_class, + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP2430) +}; + +/* timer8 */ +static struct omap_hwmod omap2430_timer8_hwmod; +static struct omap_hwmod_irq_info omap2430_timer8_mpu_irqs[] = { + { .irq = 44, }, +}; + +static struct omap_hwmod_addr_space omap2430_timer8_addrs[] = { + { + .pa_start = 0x48082000, + .pa_end = 0x48082000 + SZ_1K - 1, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_core -> timer8 */ +static struct omap_hwmod_ocp_if omap2430_l4_core__timer8 = { + .master = &omap2430_l4_core_hwmod, + .slave = &omap2430_timer8_hwmod, + .clk = "gpt8_ick", + .addr = omap2430_timer8_addrs, + .addr_cnt = ARRAY_SIZE(omap2430_timer8_addrs), + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* timer8 slave port */ +static struct omap_hwmod_ocp_if *omap2430_timer8_slaves[] = { + &omap2430_l4_core__timer8, +}; + +/* timer8 hwmod */ +static struct omap_hwmod omap2430_timer8_hwmod = { + .name = "timer8", + .mpu_irqs = omap2430_timer8_mpu_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap2430_timer8_mpu_irqs), + .main_clk = "gpt8_fck", + .prcm = { + .omap2 = { + .prcm_reg_id = 1, + .module_bit = OMAP24XX_EN_GPT8_SHIFT, + .module_offs = CORE_MOD, + .idlest_reg_id = 1, + .idlest_idle_bit = OMAP24XX_ST_GPT8_SHIFT, + }, + }, + .slaves = omap2430_timer8_slaves, + .slaves_cnt = ARRAY_SIZE(omap2430_timer8_slaves), + .class = &omap2430_timer_hwmod_class, + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP2430) +}; + +/* timer9 */ +static struct omap_hwmod omap2430_timer9_hwmod; +static struct omap_hwmod_irq_info omap2430_timer9_mpu_irqs[] = { + { .irq = 45, }, +}; + +static struct omap_hwmod_addr_space omap2430_timer9_addrs[] = { + { + .pa_start = 0x48084000, + .pa_end = 0x48084000 + SZ_1K - 1, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_core -> timer9 */ +static struct omap_hwmod_ocp_if omap2430_l4_core__timer9 = { + .master = &omap2430_l4_core_hwmod, + .slave = &omap2430_timer9_hwmod, + .clk = "gpt9_ick", + .addr = omap2430_timer9_addrs, + .addr_cnt = ARRAY_SIZE(omap2430_timer9_addrs), + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* timer9 slave port */ +static struct omap_hwmod_ocp_if *omap2430_timer9_slaves[] = { + &omap2430_l4_core__timer9, +}; + +/* timer9 hwmod */ +static struct omap_hwmod omap2430_timer9_hwmod = { + .name = "timer9", + .mpu_irqs = omap2430_timer9_mpu_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap2430_timer9_mpu_irqs), + .main_clk = "gpt9_fck", + .prcm = { + .omap2 = { + .prcm_reg_id = 1, + .module_bit = OMAP24XX_EN_GPT9_SHIFT, + .module_offs = CORE_MOD, + .idlest_reg_id = 1, + .idlest_idle_bit = OMAP24XX_ST_GPT9_SHIFT, + }, + }, + .slaves = omap2430_timer9_slaves, + .slaves_cnt = ARRAY_SIZE(omap2430_timer9_slaves), + .class = &omap2430_timer_hwmod_class, + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP2430) +}; + +/* timer10 */ +static struct omap_hwmod omap2430_timer10_hwmod; +static struct omap_hwmod_irq_info omap2430_timer10_mpu_irqs[] = { + { .irq = 46, }, +}; + +static struct omap_hwmod_addr_space omap2430_timer10_addrs[] = { + { + .pa_start = 0x48086000, + .pa_end = 0x48086000 + SZ_1K - 1, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_core -> timer10 */ +static struct omap_hwmod_ocp_if omap2430_l4_core__timer10 = { + .master = &omap2430_l4_core_hwmod, + .slave = &omap2430_timer10_hwmod, + .clk = "gpt10_ick", + .addr = omap2430_timer10_addrs, + .addr_cnt = ARRAY_SIZE(omap2430_timer10_addrs), + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* timer10 slave port */ +static struct omap_hwmod_ocp_if *omap2430_timer10_slaves[] = { + &omap2430_l4_core__timer10, +}; + +/* timer10 hwmod */ +static struct omap_hwmod omap2430_timer10_hwmod = { + .name = "timer10", + .mpu_irqs = omap2430_timer10_mpu_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap2430_timer10_mpu_irqs), + .main_clk = "gpt10_fck", + .prcm = { + .omap2 = { + .prcm_reg_id = 1, + .module_bit = OMAP24XX_EN_GPT10_SHIFT, + .module_offs = CORE_MOD, + .idlest_reg_id = 1, + .idlest_idle_bit = OMAP24XX_ST_GPT10_SHIFT, + }, + }, + .slaves = omap2430_timer10_slaves, + .slaves_cnt = ARRAY_SIZE(omap2430_timer10_slaves), + .class = &omap2430_timer_hwmod_class, + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP2430) +}; + +/* timer11 */ +static struct omap_hwmod omap2430_timer11_hwmod; +static struct omap_hwmod_irq_info omap2430_timer11_mpu_irqs[] = { + { .irq = 47, }, +}; + +static struct omap_hwmod_addr_space omap2430_timer11_addrs[] = { + { + .pa_start = 0x48088000, + .pa_end = 0x48088000 + SZ_1K - 1, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_core -> timer11 */ +static struct omap_hwmod_ocp_if omap2430_l4_core__timer11 = { + .master = &omap2430_l4_core_hwmod, + .slave = &omap2430_timer11_hwmod, + .clk = "gpt11_ick", + .addr = omap2430_timer11_addrs, + .addr_cnt = ARRAY_SIZE(omap2430_timer11_addrs), + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* timer11 slave port */ +static struct omap_hwmod_ocp_if *omap2430_timer11_slaves[] = { + &omap2430_l4_core__timer11, +}; + +/* timer11 hwmod */ +static struct omap_hwmod omap2430_timer11_hwmod = { + .name = "timer11", + .mpu_irqs = omap2430_timer11_mpu_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap2430_timer11_mpu_irqs), + .main_clk = "gpt11_fck", + .prcm = { + .omap2 = { + .prcm_reg_id = 1, + .module_bit = OMAP24XX_EN_GPT11_SHIFT, + .module_offs = CORE_MOD, + .idlest_reg_id = 1, + .idlest_idle_bit = OMAP24XX_ST_GPT11_SHIFT, + }, + }, + .slaves = omap2430_timer11_slaves, + .slaves_cnt = ARRAY_SIZE(omap2430_timer11_slaves), + .class = &omap2430_timer_hwmod_class, + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP2430) +}; + +/* timer12 */ +static struct omap_hwmod omap2430_timer12_hwmod; +static struct omap_hwmod_irq_info omap2430_timer12_mpu_irqs[] = { + { .irq = 48, }, +}; + +static struct omap_hwmod_addr_space omap2430_timer12_addrs[] = { + { + .pa_start = 0x4808a000, + .pa_end = 0x4808a000 + SZ_1K - 1, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_core -> timer12 */ +static struct omap_hwmod_ocp_if omap2430_l4_core__timer12 = { + .master = &omap2430_l4_core_hwmod, + .slave = &omap2430_timer12_hwmod, + .clk = "gpt12_ick", + .addr = omap2430_timer12_addrs, + .addr_cnt = ARRAY_SIZE(omap2430_timer12_addrs), + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* timer12 slave port */ +static struct omap_hwmod_ocp_if *omap2430_timer12_slaves[] = { + &omap2430_l4_core__timer12, +}; + +/* timer12 hwmod */ +static struct omap_hwmod omap2430_timer12_hwmod = { + .name = "timer12", + .mpu_irqs = omap2430_timer12_mpu_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap2430_timer12_mpu_irqs), + .main_clk = "gpt12_fck", + .prcm = { + .omap2 = { + .prcm_reg_id = 1, + .module_bit = OMAP24XX_EN_GPT12_SHIFT, + .module_offs = CORE_MOD, + .idlest_reg_id = 1, + .idlest_idle_bit = OMAP24XX_ST_GPT12_SHIFT, + }, + }, + .slaves = omap2430_timer12_slaves, + .slaves_cnt = ARRAY_SIZE(omap2430_timer12_slaves), + .class = &omap2430_timer_hwmod_class, + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP2430) +}; + /* l4_wkup -> wd_timer2 */ static struct omap_hwmod_addr_space omap2430_wd_timer2_addrs[] = { { @@ -307,7 +1088,7 @@ static struct omap_hwmod_class_sysconfig omap2430_wd_timer_sysc = { .sysc_offs = 0x0010, .syss_offs = 0x0014, .sysc_flags = (SYSC_HAS_EMUFREE | SYSC_HAS_SOFTRESET | - SYSC_HAS_AUTOIDLE), + SYSC_HAS_AUTOIDLE | SYSS_HAS_RESET_STATUS), .sysc_fields = &omap_hwmod_sysc_type1, }; @@ -348,7 +1129,7 @@ static struct omap_hwmod_class_sysconfig uart_sysc = { .syss_offs = 0x58, .sysc_flags = (SYSC_HAS_SIDLEMODE | SYSC_HAS_ENAWAKEUP | SYSC_HAS_SOFTRESET | - SYSC_HAS_AUTOIDLE), + SYSC_HAS_AUTOIDLE | SYSS_HAS_RESET_STATUS), .idlemodes = (SIDLE_FORCE | SIDLE_NO | SIDLE_SMART), .sysc_fields = &omap_hwmod_sysc_type1, }; @@ -469,12 +1250,274 @@ static struct omap_hwmod omap2430_uart3_hwmod = { .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP2430), }; +/* + * 'dss' class + * display sub-system + */ + +static struct omap_hwmod_class_sysconfig omap2430_dss_sysc = { + .rev_offs = 0x0000, + .sysc_offs = 0x0010, + .syss_offs = 0x0014, + .sysc_flags = (SYSC_HAS_SOFTRESET | SYSC_HAS_AUTOIDLE), + .sysc_fields = &omap_hwmod_sysc_type1, +}; + +static struct omap_hwmod_class omap2430_dss_hwmod_class = { + .name = "dss", + .sysc = &omap2430_dss_sysc, +}; + +/* dss */ +static struct omap_hwmod_irq_info omap2430_dss_irqs[] = { + { .irq = 25 }, +}; +static struct omap_hwmod_dma_info omap2430_dss_sdma_chs[] = { + { .name = "dispc", .dma_req = 5 }, +}; + +/* dss */ +/* dss master ports */ +static struct omap_hwmod_ocp_if *omap2430_dss_masters[] = { + &omap2430_dss__l3, +}; + +static struct omap_hwmod_addr_space omap2430_dss_addrs[] = { + { + .pa_start = 0x48050000, + .pa_end = 0x480503FF, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_core -> dss */ +static struct omap_hwmod_ocp_if omap2430_l4_core__dss = { + .master = &omap2430_l4_core_hwmod, + .slave = &omap2430_dss_core_hwmod, + .clk = "dss_ick", + .addr = omap2430_dss_addrs, + .addr_cnt = ARRAY_SIZE(omap2430_dss_addrs), + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* dss slave ports */ +static struct omap_hwmod_ocp_if *omap2430_dss_slaves[] = { + &omap2430_l4_core__dss, +}; + +static struct omap_hwmod_opt_clk dss_opt_clks[] = { + { .role = "tv_clk", .clk = "dss_54m_fck" }, + { .role = "sys_clk", .clk = "dss2_fck" }, +}; + +static struct omap_hwmod omap2430_dss_core_hwmod = { + .name = "dss_core", + .class = &omap2430_dss_hwmod_class, + .main_clk = "dss1_fck", /* instead of dss_fck */ + .mpu_irqs = omap2430_dss_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap2430_dss_irqs), + .sdma_reqs = omap2430_dss_sdma_chs, + .sdma_reqs_cnt = ARRAY_SIZE(omap2430_dss_sdma_chs), + .prcm = { + .omap2 = { + .prcm_reg_id = 1, + .module_bit = OMAP24XX_EN_DSS1_SHIFT, + .module_offs = CORE_MOD, + .idlest_reg_id = 1, + .idlest_stdby_bit = OMAP24XX_ST_DSS_SHIFT, + }, + }, + .opt_clks = dss_opt_clks, + .opt_clks_cnt = ARRAY_SIZE(dss_opt_clks), + .slaves = omap2430_dss_slaves, + .slaves_cnt = ARRAY_SIZE(omap2430_dss_slaves), + .masters = omap2430_dss_masters, + .masters_cnt = ARRAY_SIZE(omap2430_dss_masters), + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP2430), + .flags = HWMOD_NO_IDLEST, +}; + +/* + * 'dispc' class + * display controller + */ + +static struct omap_hwmod_class_sysconfig omap2430_dispc_sysc = { + .rev_offs = 0x0000, + .sysc_offs = 0x0010, + .syss_offs = 0x0014, + .sysc_flags = (SYSC_HAS_SIDLEMODE | SYSC_HAS_MIDLEMODE | + SYSC_HAS_SOFTRESET | SYSC_HAS_AUTOIDLE), + .idlemodes = (SIDLE_FORCE | SIDLE_NO | SIDLE_SMART | + MSTANDBY_FORCE | MSTANDBY_NO | MSTANDBY_SMART), + .sysc_fields = &omap_hwmod_sysc_type1, +}; + +static struct omap_hwmod_class omap2430_dispc_hwmod_class = { + .name = "dispc", + .sysc = &omap2430_dispc_sysc, +}; + +static struct omap_hwmod_addr_space omap2430_dss_dispc_addrs[] = { + { + .pa_start = 0x48050400, + .pa_end = 0x480507FF, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_core -> dss_dispc */ +static struct omap_hwmod_ocp_if omap2430_l4_core__dss_dispc = { + .master = &omap2430_l4_core_hwmod, + .slave = &omap2430_dss_dispc_hwmod, + .clk = "dss_ick", + .addr = omap2430_dss_dispc_addrs, + .addr_cnt = ARRAY_SIZE(omap2430_dss_dispc_addrs), + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* dss_dispc slave ports */ +static struct omap_hwmod_ocp_if *omap2430_dss_dispc_slaves[] = { + &omap2430_l4_core__dss_dispc, +}; + +static struct omap_hwmod omap2430_dss_dispc_hwmod = { + .name = "dss_dispc", + .class = &omap2430_dispc_hwmod_class, + .main_clk = "dss1_fck", + .prcm = { + .omap2 = { + .prcm_reg_id = 1, + .module_bit = OMAP24XX_EN_DSS1_SHIFT, + .module_offs = CORE_MOD, + .idlest_reg_id = 1, + .idlest_stdby_bit = OMAP24XX_ST_DSS_SHIFT, + }, + }, + .slaves = omap2430_dss_dispc_slaves, + .slaves_cnt = ARRAY_SIZE(omap2430_dss_dispc_slaves), + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP2430), + .flags = HWMOD_NO_IDLEST, +}; + +/* + * 'rfbi' class + * remote frame buffer interface + */ + +static struct omap_hwmod_class_sysconfig omap2430_rfbi_sysc = { + .rev_offs = 0x0000, + .sysc_offs = 0x0010, + .syss_offs = 0x0014, + .sysc_flags = (SYSC_HAS_SIDLEMODE | SYSC_HAS_SOFTRESET | + SYSC_HAS_AUTOIDLE), + .idlemodes = (SIDLE_FORCE | SIDLE_NO | SIDLE_SMART), + .sysc_fields = &omap_hwmod_sysc_type1, +}; + +static struct omap_hwmod_class omap2430_rfbi_hwmod_class = { + .name = "rfbi", + .sysc = &omap2430_rfbi_sysc, +}; + +static struct omap_hwmod_addr_space omap2430_dss_rfbi_addrs[] = { + { + .pa_start = 0x48050800, + .pa_end = 0x48050BFF, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_core -> dss_rfbi */ +static struct omap_hwmod_ocp_if omap2430_l4_core__dss_rfbi = { + .master = &omap2430_l4_core_hwmod, + .slave = &omap2430_dss_rfbi_hwmod, + .clk = "dss_ick", + .addr = omap2430_dss_rfbi_addrs, + .addr_cnt = ARRAY_SIZE(omap2430_dss_rfbi_addrs), + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* dss_rfbi slave ports */ +static struct omap_hwmod_ocp_if *omap2430_dss_rfbi_slaves[] = { + &omap2430_l4_core__dss_rfbi, +}; + +static struct omap_hwmod omap2430_dss_rfbi_hwmod = { + .name = "dss_rfbi", + .class = &omap2430_rfbi_hwmod_class, + .main_clk = "dss1_fck", + .prcm = { + .omap2 = { + .prcm_reg_id = 1, + .module_bit = OMAP24XX_EN_DSS1_SHIFT, + .module_offs = CORE_MOD, + }, + }, + .slaves = omap2430_dss_rfbi_slaves, + .slaves_cnt = ARRAY_SIZE(omap2430_dss_rfbi_slaves), + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP2430), + .flags = HWMOD_NO_IDLEST, +}; + +/* + * 'venc' class + * video encoder + */ + +static struct omap_hwmod_class omap2430_venc_hwmod_class = { + .name = "venc", +}; + +/* dss_venc */ +static struct omap_hwmod_addr_space omap2430_dss_venc_addrs[] = { + { + .pa_start = 0x48050C00, + .pa_end = 0x48050FFF, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_core -> dss_venc */ +static struct omap_hwmod_ocp_if omap2430_l4_core__dss_venc = { + .master = &omap2430_l4_core_hwmod, + .slave = &omap2430_dss_venc_hwmod, + .clk = "dss_54m_fck", + .addr = omap2430_dss_venc_addrs, + .addr_cnt = ARRAY_SIZE(omap2430_dss_venc_addrs), + .flags = OCPIF_SWSUP_IDLE, + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* dss_venc slave ports */ +static struct omap_hwmod_ocp_if *omap2430_dss_venc_slaves[] = { + &omap2430_l4_core__dss_venc, +}; + +static struct omap_hwmod omap2430_dss_venc_hwmod = { + .name = "dss_venc", + .class = &omap2430_venc_hwmod_class, + .main_clk = "dss1_fck", + .prcm = { + .omap2 = { + .prcm_reg_id = 1, + .module_bit = OMAP24XX_EN_DSS1_SHIFT, + .module_offs = CORE_MOD, + }, + }, + .slaves = omap2430_dss_venc_slaves, + .slaves_cnt = ARRAY_SIZE(omap2430_dss_venc_slaves), + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP2430), + .flags = HWMOD_NO_IDLEST, +}; + /* I2C common */ static struct omap_hwmod_class_sysconfig i2c_sysc = { .rev_offs = 0x00, .sysc_offs = 0x20, .syss_offs = 0x10, - .sysc_flags = (SYSC_HAS_SOFTRESET | SYSC_HAS_AUTOIDLE), + .sysc_flags = (SYSC_HAS_SOFTRESET | SYSC_HAS_AUTOIDLE | + SYSS_HAS_RESET_STATUS), .sysc_fields = &omap_hwmod_sysc_type1, }; @@ -672,7 +1715,8 @@ static struct omap_hwmod_class_sysconfig omap243x_gpio_sysc = { .sysc_offs = 0x0010, .syss_offs = 0x0014, .sysc_flags = (SYSC_HAS_ENAWAKEUP | SYSC_HAS_SIDLEMODE | - SYSC_HAS_SOFTRESET | SYSC_HAS_AUTOIDLE), + SYSC_HAS_SOFTRESET | SYSC_HAS_AUTOIDLE | + SYSS_HAS_RESET_STATUS), .idlemodes = (SIDLE_FORCE | SIDLE_NO | SIDLE_SMART), .sysc_fields = &omap_hwmod_sysc_type1, }; @@ -844,7 +1888,7 @@ static struct omap_hwmod_class_sysconfig omap2430_dma_sysc = { .syss_offs = 0x0028, .sysc_flags = (SYSC_HAS_SOFTRESET | SYSC_HAS_MIDLEMODE | SYSC_HAS_CLOCKACTIVITY | SYSC_HAS_EMUFREE | - SYSC_HAS_AUTOIDLE), + SYSC_HAS_AUTOIDLE | SYSS_HAS_RESET_STATUS), .idlemodes = (MSTANDBY_FORCE | MSTANDBY_NO | MSTANDBY_SMART), .sysc_fields = &omap_hwmod_sysc_type1, }; @@ -919,18 +1963,741 @@ static struct omap_hwmod omap2430_dma_system_hwmod = { .flags = HWMOD_NO_IDLEST, }; +/* + * 'mailbox' class + * mailbox module allowing communication between the on-chip processors + * using a queued mailbox-interrupt mechanism. + */ + +static struct omap_hwmod_class_sysconfig omap2430_mailbox_sysc = { + .rev_offs = 0x000, + .sysc_offs = 0x010, + .syss_offs = 0x014, + .sysc_flags = (SYSC_HAS_CLOCKACTIVITY | SYSC_HAS_SIDLEMODE | + SYSC_HAS_SOFTRESET | SYSC_HAS_AUTOIDLE), + .idlemodes = (SIDLE_FORCE | SIDLE_NO | SIDLE_SMART), + .sysc_fields = &omap_hwmod_sysc_type1, +}; + +static struct omap_hwmod_class omap2430_mailbox_hwmod_class = { + .name = "mailbox", + .sysc = &omap2430_mailbox_sysc, +}; + +/* mailbox */ +static struct omap_hwmod omap2430_mailbox_hwmod; +static struct omap_hwmod_irq_info omap2430_mailbox_irqs[] = { + { .irq = 26 }, +}; + +static struct omap_hwmod_addr_space omap2430_mailbox_addrs[] = { + { + .pa_start = 0x48094000, + .pa_end = 0x480941ff, + .flags = ADDR_TYPE_RT, + }, +}; + +/* l4_core -> mailbox */ +static struct omap_hwmod_ocp_if omap2430_l4_core__mailbox = { + .master = &omap2430_l4_core_hwmod, + .slave = &omap2430_mailbox_hwmod, + .addr = omap2430_mailbox_addrs, + .addr_cnt = ARRAY_SIZE(omap2430_mailbox_addrs), + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* mailbox slave ports */ +static struct omap_hwmod_ocp_if *omap2430_mailbox_slaves[] = { + &omap2430_l4_core__mailbox, +}; + +static struct omap_hwmod omap2430_mailbox_hwmod = { + .name = "mailbox", + .class = &omap2430_mailbox_hwmod_class, + .mpu_irqs = omap2430_mailbox_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap2430_mailbox_irqs), + .main_clk = "mailboxes_ick", + .prcm = { + .omap2 = { + .prcm_reg_id = 1, + .module_bit = OMAP24XX_EN_MAILBOXES_SHIFT, + .module_offs = CORE_MOD, + .idlest_reg_id = 1, + .idlest_idle_bit = OMAP24XX_ST_MAILBOXES_SHIFT, + }, + }, + .slaves = omap2430_mailbox_slaves, + .slaves_cnt = ARRAY_SIZE(omap2430_mailbox_slaves), + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP2430), +}; + +/* + * 'mcspi' class + * multichannel serial port interface (mcspi) / master/slave synchronous serial + * bus + */ + +static struct omap_hwmod_class_sysconfig omap2430_mcspi_sysc = { + .rev_offs = 0x0000, + .sysc_offs = 0x0010, + .syss_offs = 0x0014, + .sysc_flags = (SYSC_HAS_CLOCKACTIVITY | SYSC_HAS_SIDLEMODE | + SYSC_HAS_ENAWAKEUP | SYSC_HAS_SOFTRESET | + SYSC_HAS_AUTOIDLE | SYSS_HAS_RESET_STATUS), + .idlemodes = (SIDLE_FORCE | SIDLE_NO | SIDLE_SMART), + .sysc_fields = &omap_hwmod_sysc_type1, +}; + +static struct omap_hwmod_class omap2430_mcspi_class = { + .name = "mcspi", + .sysc = &omap2430_mcspi_sysc, + .rev = OMAP2_MCSPI_REV, +}; + +/* mcspi1 */ +static struct omap_hwmod_irq_info omap2430_mcspi1_mpu_irqs[] = { + { .irq = 65 }, +}; + +static struct omap_hwmod_dma_info omap2430_mcspi1_sdma_reqs[] = { + { .name = "tx0", .dma_req = 35 }, /* DMA_SPI1_TX0 */ + { .name = "rx0", .dma_req = 36 }, /* DMA_SPI1_RX0 */ + { .name = "tx1", .dma_req = 37 }, /* DMA_SPI1_TX1 */ + { .name = "rx1", .dma_req = 38 }, /* DMA_SPI1_RX1 */ + { .name = "tx2", .dma_req = 39 }, /* DMA_SPI1_TX2 */ + { .name = "rx2", .dma_req = 40 }, /* DMA_SPI1_RX2 */ + { .name = "tx3", .dma_req = 41 }, /* DMA_SPI1_TX3 */ + { .name = "rx3", .dma_req = 42 }, /* DMA_SPI1_RX3 */ +}; + +static struct omap_hwmod_ocp_if *omap2430_mcspi1_slaves[] = { + &omap2430_l4_core__mcspi1, +}; + +static struct omap2_mcspi_dev_attr omap_mcspi1_dev_attr = { + .num_chipselect = 4, +}; + +static struct omap_hwmod omap2430_mcspi1_hwmod = { + .name = "mcspi1_hwmod", + .mpu_irqs = omap2430_mcspi1_mpu_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap2430_mcspi1_mpu_irqs), + .sdma_reqs = omap2430_mcspi1_sdma_reqs, + .sdma_reqs_cnt = ARRAY_SIZE(omap2430_mcspi1_sdma_reqs), + .main_clk = "mcspi1_fck", + .prcm = { + .omap2 = { + .module_offs = CORE_MOD, + .prcm_reg_id = 1, + .module_bit = OMAP24XX_EN_MCSPI1_SHIFT, + .idlest_reg_id = 1, + .idlest_idle_bit = OMAP24XX_ST_MCSPI1_SHIFT, + }, + }, + .slaves = omap2430_mcspi1_slaves, + .slaves_cnt = ARRAY_SIZE(omap2430_mcspi1_slaves), + .class = &omap2430_mcspi_class, + .dev_attr = &omap_mcspi1_dev_attr, + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP2430), +}; + +/* mcspi2 */ +static struct omap_hwmod_irq_info omap2430_mcspi2_mpu_irqs[] = { + { .irq = 66 }, +}; + +static struct omap_hwmod_dma_info omap2430_mcspi2_sdma_reqs[] = { + { .name = "tx0", .dma_req = 43 }, /* DMA_SPI2_TX0 */ + { .name = "rx0", .dma_req = 44 }, /* DMA_SPI2_RX0 */ + { .name = "tx1", .dma_req = 45 }, /* DMA_SPI2_TX1 */ + { .name = "rx1", .dma_req = 46 }, /* DMA_SPI2_RX1 */ +}; + +static struct omap_hwmod_ocp_if *omap2430_mcspi2_slaves[] = { + &omap2430_l4_core__mcspi2, +}; + +static struct omap2_mcspi_dev_attr omap_mcspi2_dev_attr = { + .num_chipselect = 2, +}; + +static struct omap_hwmod omap2430_mcspi2_hwmod = { + .name = "mcspi2_hwmod", + .mpu_irqs = omap2430_mcspi2_mpu_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap2430_mcspi2_mpu_irqs), + .sdma_reqs = omap2430_mcspi2_sdma_reqs, + .sdma_reqs_cnt = ARRAY_SIZE(omap2430_mcspi2_sdma_reqs), + .main_clk = "mcspi2_fck", + .prcm = { + .omap2 = { + .module_offs = CORE_MOD, + .prcm_reg_id = 1, + .module_bit = OMAP24XX_EN_MCSPI2_SHIFT, + .idlest_reg_id = 1, + .idlest_idle_bit = OMAP24XX_ST_MCSPI2_SHIFT, + }, + }, + .slaves = omap2430_mcspi2_slaves, + .slaves_cnt = ARRAY_SIZE(omap2430_mcspi2_slaves), + .class = &omap2430_mcspi_class, + .dev_attr = &omap_mcspi2_dev_attr, + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP2430), +}; + +/* mcspi3 */ +static struct omap_hwmod_irq_info omap2430_mcspi3_mpu_irqs[] = { + { .irq = 91 }, +}; + +static struct omap_hwmod_dma_info omap2430_mcspi3_sdma_reqs[] = { + { .name = "tx0", .dma_req = 15 }, /* DMA_SPI3_TX0 */ + { .name = "rx0", .dma_req = 16 }, /* DMA_SPI3_RX0 */ + { .name = "tx1", .dma_req = 23 }, /* DMA_SPI3_TX1 */ + { .name = "rx1", .dma_req = 24 }, /* DMA_SPI3_RX1 */ +}; + +static struct omap_hwmod_ocp_if *omap2430_mcspi3_slaves[] = { + &omap2430_l4_core__mcspi3, +}; + +static struct omap2_mcspi_dev_attr omap_mcspi3_dev_attr = { + .num_chipselect = 2, +}; + +static struct omap_hwmod omap2430_mcspi3_hwmod = { + .name = "mcspi3_hwmod", + .mpu_irqs = omap2430_mcspi3_mpu_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap2430_mcspi3_mpu_irqs), + .sdma_reqs = omap2430_mcspi3_sdma_reqs, + .sdma_reqs_cnt = ARRAY_SIZE(omap2430_mcspi3_sdma_reqs), + .main_clk = "mcspi3_fck", + .prcm = { + .omap2 = { + .module_offs = CORE_MOD, + .prcm_reg_id = 2, + .module_bit = OMAP2430_EN_MCSPI3_SHIFT, + .idlest_reg_id = 2, + .idlest_idle_bit = OMAP2430_ST_MCSPI3_SHIFT, + }, + }, + .slaves = omap2430_mcspi3_slaves, + .slaves_cnt = ARRAY_SIZE(omap2430_mcspi3_slaves), + .class = &omap2430_mcspi_class, + .dev_attr = &omap_mcspi3_dev_attr, + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP2430), +}; + +/* + * usbhsotg + */ +static struct omap_hwmod_class_sysconfig omap2430_usbhsotg_sysc = { + .rev_offs = 0x0400, + .sysc_offs = 0x0404, + .syss_offs = 0x0408, + .sysc_flags = (SYSC_HAS_SIDLEMODE | SYSC_HAS_MIDLEMODE| + SYSC_HAS_ENAWAKEUP | SYSC_HAS_SOFTRESET | + SYSC_HAS_AUTOIDLE), + .idlemodes = (SIDLE_FORCE | SIDLE_NO | SIDLE_SMART | + MSTANDBY_FORCE | MSTANDBY_NO | MSTANDBY_SMART), + .sysc_fields = &omap_hwmod_sysc_type1, +}; + +static struct omap_hwmod_class usbotg_class = { + .name = "usbotg", + .sysc = &omap2430_usbhsotg_sysc, +}; + +/* usb_otg_hs */ +static struct omap_hwmod_irq_info omap2430_usbhsotg_mpu_irqs[] = { + + { .name = "mc", .irq = 92 }, + { .name = "dma", .irq = 93 }, +}; + +static struct omap_hwmod omap2430_usbhsotg_hwmod = { + .name = "usb_otg_hs", + .mpu_irqs = omap2430_usbhsotg_mpu_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap2430_usbhsotg_mpu_irqs), + .main_clk = "usbhs_ick", + .prcm = { + .omap2 = { + .prcm_reg_id = 1, + .module_bit = OMAP2430_EN_USBHS_MASK, + .module_offs = CORE_MOD, + .idlest_reg_id = 1, + .idlest_idle_bit = OMAP2430_ST_USBHS_SHIFT, + }, + }, + .masters = omap2430_usbhsotg_masters, + .masters_cnt = ARRAY_SIZE(omap2430_usbhsotg_masters), + .slaves = omap2430_usbhsotg_slaves, + .slaves_cnt = ARRAY_SIZE(omap2430_usbhsotg_slaves), + .class = &usbotg_class, + /* + * Erratum ID: i479 idle_req / idle_ack mechanism potentially + * broken when autoidle is enabled + * workaround is to disable the autoidle bit at module level. + */ + .flags = HWMOD_NO_OCP_AUTOIDLE | HWMOD_SWSUP_SIDLE + | HWMOD_SWSUP_MSTANDBY, + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP2430) +}; + +/* + * 'mcbsp' class + * multi channel buffered serial port controller + */ + +static struct omap_hwmod_class_sysconfig omap2430_mcbsp_sysc = { + .rev_offs = 0x007C, + .sysc_offs = 0x008C, + .sysc_flags = (SYSC_HAS_SOFTRESET), + .sysc_fields = &omap_hwmod_sysc_type1, +}; + +static struct omap_hwmod_class omap2430_mcbsp_hwmod_class = { + .name = "mcbsp", + .sysc = &omap2430_mcbsp_sysc, + .rev = MCBSP_CONFIG_TYPE2, +}; + +/* mcbsp1 */ +static struct omap_hwmod_irq_info omap2430_mcbsp1_irqs[] = { + { .name = "tx", .irq = 59 }, + { .name = "rx", .irq = 60 }, + { .name = "ovr", .irq = 61 }, + { .name = "common", .irq = 64 }, +}; + +static struct omap_hwmod_dma_info omap2430_mcbsp1_sdma_chs[] = { + { .name = "rx", .dma_req = 32 }, + { .name = "tx", .dma_req = 31 }, +}; + +static struct omap_hwmod_addr_space omap2430_mcbsp1_addrs[] = { + { + .name = "mpu", + .pa_start = 0x48074000, + .pa_end = 0x480740ff, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_core -> mcbsp1 */ +static struct omap_hwmod_ocp_if omap2430_l4_core__mcbsp1 = { + .master = &omap2430_l4_core_hwmod, + .slave = &omap2430_mcbsp1_hwmod, + .clk = "mcbsp1_ick", + .addr = omap2430_mcbsp1_addrs, + .addr_cnt = ARRAY_SIZE(omap2430_mcbsp1_addrs), + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* mcbsp1 slave ports */ +static struct omap_hwmod_ocp_if *omap2430_mcbsp1_slaves[] = { + &omap2430_l4_core__mcbsp1, +}; + +static struct omap_hwmod omap2430_mcbsp1_hwmod = { + .name = "mcbsp1", + .class = &omap2430_mcbsp_hwmod_class, + .mpu_irqs = omap2430_mcbsp1_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap2430_mcbsp1_irqs), + .sdma_reqs = omap2430_mcbsp1_sdma_chs, + .sdma_reqs_cnt = ARRAY_SIZE(omap2430_mcbsp1_sdma_chs), + .main_clk = "mcbsp1_fck", + .prcm = { + .omap2 = { + .prcm_reg_id = 1, + .module_bit = OMAP24XX_EN_MCBSP1_SHIFT, + .module_offs = CORE_MOD, + .idlest_reg_id = 1, + .idlest_idle_bit = OMAP24XX_ST_MCBSP1_SHIFT, + }, + }, + .slaves = omap2430_mcbsp1_slaves, + .slaves_cnt = ARRAY_SIZE(omap2430_mcbsp1_slaves), + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP2430), +}; + +/* mcbsp2 */ +static struct omap_hwmod_irq_info omap2430_mcbsp2_irqs[] = { + { .name = "tx", .irq = 62 }, + { .name = "rx", .irq = 63 }, + { .name = "common", .irq = 16 }, +}; + +static struct omap_hwmod_dma_info omap2430_mcbsp2_sdma_chs[] = { + { .name = "rx", .dma_req = 34 }, + { .name = "tx", .dma_req = 33 }, +}; + +static struct omap_hwmod_addr_space omap2430_mcbsp2_addrs[] = { + { + .name = "mpu", + .pa_start = 0x48076000, + .pa_end = 0x480760ff, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_core -> mcbsp2 */ +static struct omap_hwmod_ocp_if omap2430_l4_core__mcbsp2 = { + .master = &omap2430_l4_core_hwmod, + .slave = &omap2430_mcbsp2_hwmod, + .clk = "mcbsp2_ick", + .addr = omap2430_mcbsp2_addrs, + .addr_cnt = ARRAY_SIZE(omap2430_mcbsp2_addrs), + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* mcbsp2 slave ports */ +static struct omap_hwmod_ocp_if *omap2430_mcbsp2_slaves[] = { + &omap2430_l4_core__mcbsp2, +}; + +static struct omap_hwmod omap2430_mcbsp2_hwmod = { + .name = "mcbsp2", + .class = &omap2430_mcbsp_hwmod_class, + .mpu_irqs = omap2430_mcbsp2_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap2430_mcbsp2_irqs), + .sdma_reqs = omap2430_mcbsp2_sdma_chs, + .sdma_reqs_cnt = ARRAY_SIZE(omap2430_mcbsp2_sdma_chs), + .main_clk = "mcbsp2_fck", + .prcm = { + .omap2 = { + .prcm_reg_id = 1, + .module_bit = OMAP24XX_EN_MCBSP2_SHIFT, + .module_offs = CORE_MOD, + .idlest_reg_id = 1, + .idlest_idle_bit = OMAP24XX_ST_MCBSP2_SHIFT, + }, + }, + .slaves = omap2430_mcbsp2_slaves, + .slaves_cnt = ARRAY_SIZE(omap2430_mcbsp2_slaves), + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP2430), +}; + +/* mcbsp3 */ +static struct omap_hwmod_irq_info omap2430_mcbsp3_irqs[] = { + { .name = "tx", .irq = 89 }, + { .name = "rx", .irq = 90 }, + { .name = "common", .irq = 17 }, +}; + +static struct omap_hwmod_dma_info omap2430_mcbsp3_sdma_chs[] = { + { .name = "rx", .dma_req = 18 }, + { .name = "tx", .dma_req = 17 }, +}; + +static struct omap_hwmod_addr_space omap2430_mcbsp3_addrs[] = { + { + .name = "mpu", + .pa_start = 0x4808C000, + .pa_end = 0x4808C0ff, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_core -> mcbsp3 */ +static struct omap_hwmod_ocp_if omap2430_l4_core__mcbsp3 = { + .master = &omap2430_l4_core_hwmod, + .slave = &omap2430_mcbsp3_hwmod, + .clk = "mcbsp3_ick", + .addr = omap2430_mcbsp3_addrs, + .addr_cnt = ARRAY_SIZE(omap2430_mcbsp3_addrs), + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* mcbsp3 slave ports */ +static struct omap_hwmod_ocp_if *omap2430_mcbsp3_slaves[] = { + &omap2430_l4_core__mcbsp3, +}; + +static struct omap_hwmod omap2430_mcbsp3_hwmod = { + .name = "mcbsp3", + .class = &omap2430_mcbsp_hwmod_class, + .mpu_irqs = omap2430_mcbsp3_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap2430_mcbsp3_irqs), + .sdma_reqs = omap2430_mcbsp3_sdma_chs, + .sdma_reqs_cnt = ARRAY_SIZE(omap2430_mcbsp3_sdma_chs), + .main_clk = "mcbsp3_fck", + .prcm = { + .omap2 = { + .prcm_reg_id = 1, + .module_bit = OMAP2430_EN_MCBSP3_SHIFT, + .module_offs = CORE_MOD, + .idlest_reg_id = 2, + .idlest_idle_bit = OMAP2430_ST_MCBSP3_SHIFT, + }, + }, + .slaves = omap2430_mcbsp3_slaves, + .slaves_cnt = ARRAY_SIZE(omap2430_mcbsp3_slaves), + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP2430), +}; + +/* mcbsp4 */ +static struct omap_hwmod_irq_info omap2430_mcbsp4_irqs[] = { + { .name = "tx", .irq = 54 }, + { .name = "rx", .irq = 55 }, + { .name = "common", .irq = 18 }, +}; + +static struct omap_hwmod_dma_info omap2430_mcbsp4_sdma_chs[] = { + { .name = "rx", .dma_req = 20 }, + { .name = "tx", .dma_req = 19 }, +}; + +static struct omap_hwmod_addr_space omap2430_mcbsp4_addrs[] = { + { + .name = "mpu", + .pa_start = 0x4808E000, + .pa_end = 0x4808E0ff, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_core -> mcbsp4 */ +static struct omap_hwmod_ocp_if omap2430_l4_core__mcbsp4 = { + .master = &omap2430_l4_core_hwmod, + .slave = &omap2430_mcbsp4_hwmod, + .clk = "mcbsp4_ick", + .addr = omap2430_mcbsp4_addrs, + .addr_cnt = ARRAY_SIZE(omap2430_mcbsp4_addrs), + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* mcbsp4 slave ports */ +static struct omap_hwmod_ocp_if *omap2430_mcbsp4_slaves[] = { + &omap2430_l4_core__mcbsp4, +}; + +static struct omap_hwmod omap2430_mcbsp4_hwmod = { + .name = "mcbsp4", + .class = &omap2430_mcbsp_hwmod_class, + .mpu_irqs = omap2430_mcbsp4_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap2430_mcbsp4_irqs), + .sdma_reqs = omap2430_mcbsp4_sdma_chs, + .sdma_reqs_cnt = ARRAY_SIZE(omap2430_mcbsp4_sdma_chs), + .main_clk = "mcbsp4_fck", + .prcm = { + .omap2 = { + .prcm_reg_id = 1, + .module_bit = OMAP2430_EN_MCBSP4_SHIFT, + .module_offs = CORE_MOD, + .idlest_reg_id = 2, + .idlest_idle_bit = OMAP2430_ST_MCBSP4_SHIFT, + }, + }, + .slaves = omap2430_mcbsp4_slaves, + .slaves_cnt = ARRAY_SIZE(omap2430_mcbsp4_slaves), + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP2430), +}; + +/* mcbsp5 */ +static struct omap_hwmod_irq_info omap2430_mcbsp5_irqs[] = { + { .name = "tx", .irq = 81 }, + { .name = "rx", .irq = 82 }, + { .name = "common", .irq = 19 }, +}; + +static struct omap_hwmod_dma_info omap2430_mcbsp5_sdma_chs[] = { + { .name = "rx", .dma_req = 22 }, + { .name = "tx", .dma_req = 21 }, +}; + +static struct omap_hwmod_addr_space omap2430_mcbsp5_addrs[] = { + { + .name = "mpu", + .pa_start = 0x48096000, + .pa_end = 0x480960ff, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_core -> mcbsp5 */ +static struct omap_hwmod_ocp_if omap2430_l4_core__mcbsp5 = { + .master = &omap2430_l4_core_hwmod, + .slave = &omap2430_mcbsp5_hwmod, + .clk = "mcbsp5_ick", + .addr = omap2430_mcbsp5_addrs, + .addr_cnt = ARRAY_SIZE(omap2430_mcbsp5_addrs), + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* mcbsp5 slave ports */ +static struct omap_hwmod_ocp_if *omap2430_mcbsp5_slaves[] = { + &omap2430_l4_core__mcbsp5, +}; + +static struct omap_hwmod omap2430_mcbsp5_hwmod = { + .name = "mcbsp5", + .class = &omap2430_mcbsp_hwmod_class, + .mpu_irqs = omap2430_mcbsp5_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap2430_mcbsp5_irqs), + .sdma_reqs = omap2430_mcbsp5_sdma_chs, + .sdma_reqs_cnt = ARRAY_SIZE(omap2430_mcbsp5_sdma_chs), + .main_clk = "mcbsp5_fck", + .prcm = { + .omap2 = { + .prcm_reg_id = 1, + .module_bit = OMAP2430_EN_MCBSP5_SHIFT, + .module_offs = CORE_MOD, + .idlest_reg_id = 2, + .idlest_idle_bit = OMAP2430_ST_MCBSP5_SHIFT, + }, + }, + .slaves = omap2430_mcbsp5_slaves, + .slaves_cnt = ARRAY_SIZE(omap2430_mcbsp5_slaves), + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP2430), +}; + +/* MMC/SD/SDIO common */ + +static struct omap_hwmod_class_sysconfig omap2430_mmc_sysc = { + .rev_offs = 0x1fc, + .sysc_offs = 0x10, + .syss_offs = 0x14, + .sysc_flags = (SYSC_HAS_CLOCKACTIVITY | SYSC_HAS_SIDLEMODE | + SYSC_HAS_ENAWAKEUP | SYSC_HAS_SOFTRESET | + SYSC_HAS_AUTOIDLE | SYSS_HAS_RESET_STATUS), + .idlemodes = (SIDLE_FORCE | SIDLE_NO | SIDLE_SMART), + .sysc_fields = &omap_hwmod_sysc_type1, +}; + +static struct omap_hwmod_class omap2430_mmc_class = { + .name = "mmc", + .sysc = &omap2430_mmc_sysc, +}; + +/* MMC/SD/SDIO1 */ + +static struct omap_hwmod_irq_info omap2430_mmc1_mpu_irqs[] = { + { .irq = 83 }, +}; + +static struct omap_hwmod_dma_info omap2430_mmc1_sdma_reqs[] = { + { .name = "tx", .dma_req = 61 }, /* DMA_MMC1_TX */ + { .name = "rx", .dma_req = 62 }, /* DMA_MMC1_RX */ +}; + +static struct omap_hwmod_opt_clk omap2430_mmc1_opt_clks[] = { + { .role = "dbck", .clk = "mmchsdb1_fck" }, +}; + +static struct omap_hwmod_ocp_if *omap2430_mmc1_slaves[] = { + &omap2430_l4_core__mmc1, +}; + +static struct omap_mmc_dev_attr mmc1_dev_attr = { + .flags = OMAP_HSMMC_SUPPORTS_DUAL_VOLT, +}; + +static struct omap_hwmod omap2430_mmc1_hwmod = { + .name = "mmc1", + .flags = HWMOD_CONTROL_OPT_CLKS_IN_RESET, + .mpu_irqs = omap2430_mmc1_mpu_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap2430_mmc1_mpu_irqs), + .sdma_reqs = omap2430_mmc1_sdma_reqs, + .sdma_reqs_cnt = ARRAY_SIZE(omap2430_mmc1_sdma_reqs), + .opt_clks = omap2430_mmc1_opt_clks, + .opt_clks_cnt = ARRAY_SIZE(omap2430_mmc1_opt_clks), + .main_clk = "mmchs1_fck", + .prcm = { + .omap2 = { + .module_offs = CORE_MOD, + .prcm_reg_id = 2, + .module_bit = OMAP2430_EN_MMCHS1_SHIFT, + .idlest_reg_id = 2, + .idlest_idle_bit = OMAP2430_ST_MMCHS1_SHIFT, + }, + }, + .dev_attr = &mmc1_dev_attr, + .slaves = omap2430_mmc1_slaves, + .slaves_cnt = ARRAY_SIZE(omap2430_mmc1_slaves), + .class = &omap2430_mmc_class, + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP2430), +}; + +/* MMC/SD/SDIO2 */ + +static struct omap_hwmod_irq_info omap2430_mmc2_mpu_irqs[] = { + { .irq = 86 }, +}; + +static struct omap_hwmod_dma_info omap2430_mmc2_sdma_reqs[] = { + { .name = "tx", .dma_req = 47 }, /* DMA_MMC2_TX */ + { .name = "rx", .dma_req = 48 }, /* DMA_MMC2_RX */ +}; + +static struct omap_hwmod_opt_clk omap2430_mmc2_opt_clks[] = { + { .role = "dbck", .clk = "mmchsdb2_fck" }, +}; + +static struct omap_hwmod_ocp_if *omap2430_mmc2_slaves[] = { + &omap2430_l4_core__mmc2, +}; + +static struct omap_hwmod omap2430_mmc2_hwmod = { + .name = "mmc2", + .flags = HWMOD_CONTROL_OPT_CLKS_IN_RESET, + .mpu_irqs = omap2430_mmc2_mpu_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap2430_mmc2_mpu_irqs), + .sdma_reqs = omap2430_mmc2_sdma_reqs, + .sdma_reqs_cnt = ARRAY_SIZE(omap2430_mmc2_sdma_reqs), + .opt_clks = omap2430_mmc2_opt_clks, + .opt_clks_cnt = ARRAY_SIZE(omap2430_mmc2_opt_clks), + .main_clk = "mmchs2_fck", + .prcm = { + .omap2 = { + .module_offs = CORE_MOD, + .prcm_reg_id = 2, + .module_bit = OMAP2430_EN_MMCHS2_SHIFT, + .idlest_reg_id = 2, + .idlest_idle_bit = OMAP2430_ST_MMCHS2_SHIFT, + }, + }, + .slaves = omap2430_mmc2_slaves, + .slaves_cnt = ARRAY_SIZE(omap2430_mmc2_slaves), + .class = &omap2430_mmc_class, + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP2430), +}; + static __initdata struct omap_hwmod *omap2430_hwmods[] = { &omap2430_l3_main_hwmod, &omap2430_l4_core_hwmod, &omap2430_l4_wkup_hwmod, &omap2430_mpu_hwmod, &omap2430_iva_hwmod, + + &omap2430_timer1_hwmod, + &omap2430_timer2_hwmod, + &omap2430_timer3_hwmod, + &omap2430_timer4_hwmod, + &omap2430_timer5_hwmod, + &omap2430_timer6_hwmod, + &omap2430_timer7_hwmod, + &omap2430_timer8_hwmod, + &omap2430_timer9_hwmod, + &omap2430_timer10_hwmod, + &omap2430_timer11_hwmod, + &omap2430_timer12_hwmod, + &omap2430_wd_timer2_hwmod, &omap2430_uart1_hwmod, &omap2430_uart2_hwmod, &omap2430_uart3_hwmod, + /* dss class */ + &omap2430_dss_core_hwmod, + &omap2430_dss_dispc_hwmod, + &omap2430_dss_rfbi_hwmod, + &omap2430_dss_venc_hwmod, + /* i2c class */ &omap2430_i2c1_hwmod, &omap2430_i2c2_hwmod, + &omap2430_mmc1_hwmod, + &omap2430_mmc2_hwmod, /* gpio class */ &omap2430_gpio1_hwmod, @@ -941,10 +2708,29 @@ static __initdata struct omap_hwmod *omap2430_hwmods[] = { /* dma_system class*/ &omap2430_dma_system_hwmod, + + /* mcbsp class */ + &omap2430_mcbsp1_hwmod, + &omap2430_mcbsp2_hwmod, + &omap2430_mcbsp3_hwmod, + &omap2430_mcbsp4_hwmod, + &omap2430_mcbsp5_hwmod, + + /* mailbox class */ + &omap2430_mailbox_hwmod, + + /* mcspi class */ + &omap2430_mcspi1_hwmod, + &omap2430_mcspi2_hwmod, + &omap2430_mcspi3_hwmod, + + /* usbotg class*/ + &omap2430_usbhsotg_hwmod, + NULL, }; int __init omap2430_hwmod_init(void) { - return omap_hwmod_init(omap2430_hwmods); + return omap_hwmod_register(omap2430_hwmods); } diff --git a/arch/arm/mach-omap2/omap_hwmod_3xxx_data.c b/arch/arm/mach-omap2/omap_hwmod_3xxx_data.c index 8d8181334f8..c819c306693 100644 --- a/arch/arm/mach-omap2/omap_hwmod_3xxx_data.c +++ b/arch/arm/mach-omap2/omap_hwmod_3xxx_data.c @@ -18,16 +18,21 @@ #include <plat/cpu.h> #include <plat/dma.h> #include <plat/serial.h> +#include <plat/l3_3xxx.h> #include <plat/l4_3xxx.h> #include <plat/i2c.h> #include <plat/gpio.h> -#include <plat/smartreflex.h> +#include <plat/mmc.h> +#include <plat/mcbsp.h> +#include <plat/mcspi.h> +#include <plat/dmtimer.h> #include "omap_hwmod_common_data.h" #include "prm-regbits-34xx.h" #include "cm-regbits-34xx.h" #include "wd_timer.h" +#include <mach/am35xx.h> /* * OMAP3xxx hardware module integration data @@ -44,6 +49,12 @@ static struct omap_hwmod omap3xxx_l3_main_hwmod; static struct omap_hwmod omap3xxx_l4_core_hwmod; static struct omap_hwmod omap3xxx_l4_per_hwmod; static struct omap_hwmod omap3xxx_wd_timer2_hwmod; +static struct omap_hwmod omap3430es1_dss_core_hwmod; +static struct omap_hwmod omap3xxx_dss_core_hwmod; +static struct omap_hwmod omap3xxx_dss_dispc_hwmod; +static struct omap_hwmod omap3xxx_dss_dsi1_hwmod; +static struct omap_hwmod omap3xxx_dss_rfbi_hwmod; +static struct omap_hwmod omap3xxx_dss_venc_hwmod; static struct omap_hwmod omap3xxx_i2c1_hwmod; static struct omap_hwmod omap3xxx_i2c2_hwmod; static struct omap_hwmod omap3xxx_i2c3_hwmod; @@ -55,9 +66,25 @@ static struct omap_hwmod omap3xxx_gpio5_hwmod; static struct omap_hwmod omap3xxx_gpio6_hwmod; static struct omap_hwmod omap34xx_sr1_hwmod; static struct omap_hwmod omap34xx_sr2_hwmod; +static struct omap_hwmod omap34xx_mcspi1; +static struct omap_hwmod omap34xx_mcspi2; +static struct omap_hwmod omap34xx_mcspi3; +static struct omap_hwmod omap34xx_mcspi4; +static struct omap_hwmod omap3xxx_mmc1_hwmod; +static struct omap_hwmod omap3xxx_mmc2_hwmod; +static struct omap_hwmod omap3xxx_mmc3_hwmod; +static struct omap_hwmod am35xx_usbhsotg_hwmod; static struct omap_hwmod omap3xxx_dma_system_hwmod; +static struct omap_hwmod omap3xxx_mcbsp1_hwmod; +static struct omap_hwmod omap3xxx_mcbsp2_hwmod; +static struct omap_hwmod omap3xxx_mcbsp3_hwmod; +static struct omap_hwmod omap3xxx_mcbsp4_hwmod; +static struct omap_hwmod omap3xxx_mcbsp5_hwmod; +static struct omap_hwmod omap3xxx_mcbsp2_sidetone_hwmod; +static struct omap_hwmod omap3xxx_mcbsp3_sidetone_hwmod; + /* L3 -> L4_CORE interface */ static struct omap_hwmod_ocp_if omap3xxx_l3_main__l4_core = { .master = &omap3xxx_l3_main_hwmod, @@ -72,10 +99,26 @@ static struct omap_hwmod_ocp_if omap3xxx_l3_main__l4_per = { .user = OCP_USER_MPU | OCP_USER_SDMA, }; +/* L3 taret configuration and error log registers */ +static struct omap_hwmod_irq_info omap3xxx_l3_main_irqs[] = { + { .irq = INT_34XX_L3_DBG_IRQ }, + { .irq = INT_34XX_L3_APP_IRQ }, +}; + +static struct omap_hwmod_addr_space omap3xxx_l3_main_addrs[] = { + { + .pa_start = 0x68000000, + .pa_end = 0x6800ffff, + .flags = ADDR_TYPE_RT, + }, +}; + /* MPU -> L3 interface */ static struct omap_hwmod_ocp_if omap3xxx_mpu__l3_main = { - .master = &omap3xxx_mpu_hwmod, - .slave = &omap3xxx_l3_main_hwmod, + .master = &omap3xxx_mpu_hwmod, + .slave = &omap3xxx_l3_main_hwmod, + .addr = omap3xxx_l3_main_addrs, + .addr_cnt = ARRAY_SIZE(omap3xxx_l3_main_addrs), .user = OCP_USER_MPU, }; @@ -84,6 +127,19 @@ static struct omap_hwmod_ocp_if *omap3xxx_l3_main_slaves[] = { &omap3xxx_mpu__l3_main, }; +/* DSS -> l3 */ +static struct omap_hwmod_ocp_if omap3xxx_dss__l3 = { + .master = &omap3xxx_dss_core_hwmod, + .slave = &omap3xxx_l3_main_hwmod, + .fw = { + .omap2 = { + .l3_perm_bit = OMAP3_L3_CORE_FW_INIT_ID_DSS, + .flags = OMAP_FIREWALL_L3, + } + }, + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + /* Master interfaces on the L3 interconnect */ static struct omap_hwmod_ocp_if *omap3xxx_l3_main_masters[] = { &omap3xxx_l3_main__l4_core, @@ -94,6 +150,8 @@ static struct omap_hwmod_ocp_if *omap3xxx_l3_main_masters[] = { static struct omap_hwmod omap3xxx_l3_main_hwmod = { .name = "l3_main", .class = &l3_hwmod_class, + .mpu_irqs = omap3xxx_l3_main_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap3xxx_l3_main_irqs), .masters = omap3xxx_l3_main_masters, .masters_cnt = ARRAY_SIZE(omap3xxx_l3_main_masters), .slaves = omap3xxx_l3_main_slaves, @@ -107,7 +165,23 @@ static struct omap_hwmod omap3xxx_uart1_hwmod; static struct omap_hwmod omap3xxx_uart2_hwmod; static struct omap_hwmod omap3xxx_uart3_hwmod; static struct omap_hwmod omap3xxx_uart4_hwmod; +static struct omap_hwmod omap3xxx_usbhsotg_hwmod; +/* l3_core -> usbhsotg interface */ +static struct omap_hwmod_ocp_if omap3xxx_usbhsotg__l3 = { + .master = &omap3xxx_usbhsotg_hwmod, + .slave = &omap3xxx_l3_main_hwmod, + .clk = "core_l3_ick", + .user = OCP_USER_MPU, +}; + +/* l3_core -> am35xx_usbhsotg interface */ +static struct omap_hwmod_ocp_if am35xx_usbhsotg__l3 = { + .master = &am35xx_usbhsotg_hwmod, + .slave = &omap3xxx_l3_main_hwmod, + .clk = "core_l3_ick", + .user = OCP_USER_MPU, +}; /* L4_CORE -> L4_WKUP interface */ static struct omap_hwmod_ocp_if omap3xxx_l4_core__l4_wkup = { .master = &omap3xxx_l4_core_hwmod, @@ -115,6 +189,63 @@ static struct omap_hwmod_ocp_if omap3xxx_l4_core__l4_wkup = { .user = OCP_USER_MPU | OCP_USER_SDMA, }; +/* L4 CORE -> MMC1 interface */ +static struct omap_hwmod_addr_space omap3xxx_mmc1_addr_space[] = { + { + .pa_start = 0x4809c000, + .pa_end = 0x4809c1ff, + .flags = ADDR_TYPE_RT, + }, +}; + +static struct omap_hwmod_ocp_if omap3xxx_l4_core__mmc1 = { + .master = &omap3xxx_l4_core_hwmod, + .slave = &omap3xxx_mmc1_hwmod, + .clk = "mmchs1_ick", + .addr = omap3xxx_mmc1_addr_space, + .addr_cnt = ARRAY_SIZE(omap3xxx_mmc1_addr_space), + .user = OCP_USER_MPU | OCP_USER_SDMA, + .flags = OMAP_FIREWALL_L4 +}; + +/* L4 CORE -> MMC2 interface */ +static struct omap_hwmod_addr_space omap3xxx_mmc2_addr_space[] = { + { + .pa_start = 0x480b4000, + .pa_end = 0x480b41ff, + .flags = ADDR_TYPE_RT, + }, +}; + +static struct omap_hwmod_ocp_if omap3xxx_l4_core__mmc2 = { + .master = &omap3xxx_l4_core_hwmod, + .slave = &omap3xxx_mmc2_hwmod, + .clk = "mmchs2_ick", + .addr = omap3xxx_mmc2_addr_space, + .addr_cnt = ARRAY_SIZE(omap3xxx_mmc2_addr_space), + .user = OCP_USER_MPU | OCP_USER_SDMA, + .flags = OMAP_FIREWALL_L4 +}; + +/* L4 CORE -> MMC3 interface */ +static struct omap_hwmod_addr_space omap3xxx_mmc3_addr_space[] = { + { + .pa_start = 0x480ad000, + .pa_end = 0x480ad1ff, + .flags = ADDR_TYPE_RT, + }, +}; + +static struct omap_hwmod_ocp_if omap3xxx_l4_core__mmc3 = { + .master = &omap3xxx_l4_core_hwmod, + .slave = &omap3xxx_mmc3_hwmod, + .clk = "mmchs3_ick", + .addr = omap3xxx_mmc3_addr_space, + .addr_cnt = ARRAY_SIZE(omap3xxx_mmc3_addr_space), + .user = OCP_USER_MPU | OCP_USER_SDMA, + .flags = OMAP_FIREWALL_L4 +}; + /* L4 CORE -> UART1 interface */ static struct omap_hwmod_addr_space omap3xxx_uart1_addr_space[] = { { @@ -301,29 +432,70 @@ static struct omap_hwmod_ocp_if omap3_l4_core__sr2 = { .user = OCP_USER_MPU, }; +/* +* usbhsotg interface data +*/ + +static struct omap_hwmod_addr_space omap3xxx_usbhsotg_addrs[] = { + { + .pa_start = OMAP34XX_HSUSB_OTG_BASE, + .pa_end = OMAP34XX_HSUSB_OTG_BASE + SZ_4K - 1, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_core -> usbhsotg */ +static struct omap_hwmod_ocp_if omap3xxx_l4_core__usbhsotg = { + .master = &omap3xxx_l4_core_hwmod, + .slave = &omap3xxx_usbhsotg_hwmod, + .clk = "l4_ick", + .addr = omap3xxx_usbhsotg_addrs, + .addr_cnt = ARRAY_SIZE(omap3xxx_usbhsotg_addrs), + .user = OCP_USER_MPU, +}; + +static struct omap_hwmod_ocp_if *omap3xxx_usbhsotg_masters[] = { + &omap3xxx_usbhsotg__l3, +}; + +static struct omap_hwmod_ocp_if *omap3xxx_usbhsotg_slaves[] = { + &omap3xxx_l4_core__usbhsotg, +}; + +static struct omap_hwmod_addr_space am35xx_usbhsotg_addrs[] = { + { + .pa_start = AM35XX_IPSS_USBOTGSS_BASE, + .pa_end = AM35XX_IPSS_USBOTGSS_BASE + SZ_4K - 1, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_core -> usbhsotg */ +static struct omap_hwmod_ocp_if am35xx_l4_core__usbhsotg = { + .master = &omap3xxx_l4_core_hwmod, + .slave = &am35xx_usbhsotg_hwmod, + .clk = "l4_ick", + .addr = am35xx_usbhsotg_addrs, + .addr_cnt = ARRAY_SIZE(am35xx_usbhsotg_addrs), + .user = OCP_USER_MPU, +}; + +static struct omap_hwmod_ocp_if *am35xx_usbhsotg_masters[] = { + &am35xx_usbhsotg__l3, +}; + +static struct omap_hwmod_ocp_if *am35xx_usbhsotg_slaves[] = { + &am35xx_l4_core__usbhsotg, +}; /* Slave interfaces on the L4_CORE interconnect */ static struct omap_hwmod_ocp_if *omap3xxx_l4_core_slaves[] = { &omap3xxx_l3_main__l4_core, - &omap3_l4_core__sr1, - &omap3_l4_core__sr2, -}; - -/* Master interfaces on the L4_CORE interconnect */ -static struct omap_hwmod_ocp_if *omap3xxx_l4_core_masters[] = { - &omap3xxx_l4_core__l4_wkup, - &omap3_l4_core__uart1, - &omap3_l4_core__uart2, - &omap3_l4_core__i2c1, - &omap3_l4_core__i2c2, - &omap3_l4_core__i2c3, }; /* L4 CORE */ static struct omap_hwmod omap3xxx_l4_core_hwmod = { .name = "l4_core", .class = &l4_hwmod_class, - .masters = omap3xxx_l4_core_masters, - .masters_cnt = ARRAY_SIZE(omap3xxx_l4_core_masters), .slaves = omap3xxx_l4_core_slaves, .slaves_cnt = ARRAY_SIZE(omap3xxx_l4_core_slaves), .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP3430), @@ -335,18 +507,10 @@ static struct omap_hwmod_ocp_if *omap3xxx_l4_per_slaves[] = { &omap3xxx_l3_main__l4_per, }; -/* Master interfaces on the L4_PER interconnect */ -static struct omap_hwmod_ocp_if *omap3xxx_l4_per_masters[] = { - &omap3_l4_per__uart3, - &omap3_l4_per__uart4, -}; - /* L4 PER */ static struct omap_hwmod omap3xxx_l4_per_hwmod = { .name = "l4_per", .class = &l4_hwmod_class, - .masters = omap3xxx_l4_per_masters, - .masters_cnt = ARRAY_SIZE(omap3xxx_l4_per_masters), .slaves = omap3xxx_l4_per_slaves, .slaves_cnt = ARRAY_SIZE(omap3xxx_l4_per_slaves), .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP3430), @@ -358,16 +522,10 @@ static struct omap_hwmod_ocp_if *omap3xxx_l4_wkup_slaves[] = { &omap3xxx_l4_core__l4_wkup, }; -/* Master interfaces on the L4_WKUP interconnect */ -static struct omap_hwmod_ocp_if *omap3xxx_l4_wkup_masters[] = { -}; - /* L4 WKUP */ static struct omap_hwmod omap3xxx_l4_wkup_hwmod = { .name = "l4_wkup", .class = &l4_hwmod_class, - .masters = omap3xxx_l4_wkup_masters, - .masters_cnt = ARRAY_SIZE(omap3xxx_l4_wkup_masters), .slaves = omap3xxx_l4_wkup_slaves, .slaves_cnt = ARRAY_SIZE(omap3xxx_l4_wkup_slaves), .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP3430), @@ -417,6 +575,640 @@ static struct omap_hwmod omap3xxx_iva_hwmod = { .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP3430) }; +/* timer class */ +static struct omap_hwmod_class_sysconfig omap3xxx_timer_1ms_sysc = { + .rev_offs = 0x0000, + .sysc_offs = 0x0010, + .syss_offs = 0x0014, + .sysc_flags = (SYSC_HAS_SIDLEMODE | SYSC_HAS_CLOCKACTIVITY | + SYSC_HAS_ENAWAKEUP | SYSC_HAS_SOFTRESET | + SYSC_HAS_EMUFREE | SYSC_HAS_AUTOIDLE), + .idlemodes = (SIDLE_FORCE | SIDLE_NO | SIDLE_SMART), + .sysc_fields = &omap_hwmod_sysc_type1, +}; + +static struct omap_hwmod_class omap3xxx_timer_1ms_hwmod_class = { + .name = "timer", + .sysc = &omap3xxx_timer_1ms_sysc, + .rev = OMAP_TIMER_IP_VERSION_1, +}; + +static struct omap_hwmod_class_sysconfig omap3xxx_timer_sysc = { + .rev_offs = 0x0000, + .sysc_offs = 0x0010, + .syss_offs = 0x0014, + .sysc_flags = (SYSC_HAS_SIDLEMODE | SYSC_HAS_ENAWAKEUP | + SYSC_HAS_SOFTRESET | SYSC_HAS_AUTOIDLE), + .idlemodes = (SIDLE_FORCE | SIDLE_NO | SIDLE_SMART), + .sysc_fields = &omap_hwmod_sysc_type1, +}; + +static struct omap_hwmod_class omap3xxx_timer_hwmod_class = { + .name = "timer", + .sysc = &omap3xxx_timer_sysc, + .rev = OMAP_TIMER_IP_VERSION_1, +}; + +/* timer1 */ +static struct omap_hwmod omap3xxx_timer1_hwmod; +static struct omap_hwmod_irq_info omap3xxx_timer1_mpu_irqs[] = { + { .irq = 37, }, +}; + +static struct omap_hwmod_addr_space omap3xxx_timer1_addrs[] = { + { + .pa_start = 0x48318000, + .pa_end = 0x48318000 + SZ_1K - 1, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_wkup -> timer1 */ +static struct omap_hwmod_ocp_if omap3xxx_l4_wkup__timer1 = { + .master = &omap3xxx_l4_wkup_hwmod, + .slave = &omap3xxx_timer1_hwmod, + .clk = "gpt1_ick", + .addr = omap3xxx_timer1_addrs, + .addr_cnt = ARRAY_SIZE(omap3xxx_timer1_addrs), + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* timer1 slave port */ +static struct omap_hwmod_ocp_if *omap3xxx_timer1_slaves[] = { + &omap3xxx_l4_wkup__timer1, +}; + +/* timer1 hwmod */ +static struct omap_hwmod omap3xxx_timer1_hwmod = { + .name = "timer1", + .mpu_irqs = omap3xxx_timer1_mpu_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap3xxx_timer1_mpu_irqs), + .main_clk = "gpt1_fck", + .prcm = { + .omap2 = { + .prcm_reg_id = 1, + .module_bit = OMAP3430_EN_GPT1_SHIFT, + .module_offs = WKUP_MOD, + .idlest_reg_id = 1, + .idlest_idle_bit = OMAP3430_ST_GPT1_SHIFT, + }, + }, + .slaves = omap3xxx_timer1_slaves, + .slaves_cnt = ARRAY_SIZE(omap3xxx_timer1_slaves), + .class = &omap3xxx_timer_1ms_hwmod_class, + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP3430) +}; + +/* timer2 */ +static struct omap_hwmod omap3xxx_timer2_hwmod; +static struct omap_hwmod_irq_info omap3xxx_timer2_mpu_irqs[] = { + { .irq = 38, }, +}; + +static struct omap_hwmod_addr_space omap3xxx_timer2_addrs[] = { + { + .pa_start = 0x49032000, + .pa_end = 0x49032000 + SZ_1K - 1, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_per -> timer2 */ +static struct omap_hwmod_ocp_if omap3xxx_l4_per__timer2 = { + .master = &omap3xxx_l4_per_hwmod, + .slave = &omap3xxx_timer2_hwmod, + .clk = "gpt2_ick", + .addr = omap3xxx_timer2_addrs, + .addr_cnt = ARRAY_SIZE(omap3xxx_timer2_addrs), + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* timer2 slave port */ +static struct omap_hwmod_ocp_if *omap3xxx_timer2_slaves[] = { + &omap3xxx_l4_per__timer2, +}; + +/* timer2 hwmod */ +static struct omap_hwmod omap3xxx_timer2_hwmod = { + .name = "timer2", + .mpu_irqs = omap3xxx_timer2_mpu_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap3xxx_timer2_mpu_irqs), + .main_clk = "gpt2_fck", + .prcm = { + .omap2 = { + .prcm_reg_id = 1, + .module_bit = OMAP3430_EN_GPT2_SHIFT, + .module_offs = OMAP3430_PER_MOD, + .idlest_reg_id = 1, + .idlest_idle_bit = OMAP3430_ST_GPT2_SHIFT, + }, + }, + .slaves = omap3xxx_timer2_slaves, + .slaves_cnt = ARRAY_SIZE(omap3xxx_timer2_slaves), + .class = &omap3xxx_timer_1ms_hwmod_class, + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP3430) +}; + +/* timer3 */ +static struct omap_hwmod omap3xxx_timer3_hwmod; +static struct omap_hwmod_irq_info omap3xxx_timer3_mpu_irqs[] = { + { .irq = 39, }, +}; + +static struct omap_hwmod_addr_space omap3xxx_timer3_addrs[] = { + { + .pa_start = 0x49034000, + .pa_end = 0x49034000 + SZ_1K - 1, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_per -> timer3 */ +static struct omap_hwmod_ocp_if omap3xxx_l4_per__timer3 = { + .master = &omap3xxx_l4_per_hwmod, + .slave = &omap3xxx_timer3_hwmod, + .clk = "gpt3_ick", + .addr = omap3xxx_timer3_addrs, + .addr_cnt = ARRAY_SIZE(omap3xxx_timer3_addrs), + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* timer3 slave port */ +static struct omap_hwmod_ocp_if *omap3xxx_timer3_slaves[] = { + &omap3xxx_l4_per__timer3, +}; + +/* timer3 hwmod */ +static struct omap_hwmod omap3xxx_timer3_hwmod = { + .name = "timer3", + .mpu_irqs = omap3xxx_timer3_mpu_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap3xxx_timer3_mpu_irqs), + .main_clk = "gpt3_fck", + .prcm = { + .omap2 = { + .prcm_reg_id = 1, + .module_bit = OMAP3430_EN_GPT3_SHIFT, + .module_offs = OMAP3430_PER_MOD, + .idlest_reg_id = 1, + .idlest_idle_bit = OMAP3430_ST_GPT3_SHIFT, + }, + }, + .slaves = omap3xxx_timer3_slaves, + .slaves_cnt = ARRAY_SIZE(omap3xxx_timer3_slaves), + .class = &omap3xxx_timer_hwmod_class, + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP3430) +}; + +/* timer4 */ +static struct omap_hwmod omap3xxx_timer4_hwmod; +static struct omap_hwmod_irq_info omap3xxx_timer4_mpu_irqs[] = { + { .irq = 40, }, +}; + +static struct omap_hwmod_addr_space omap3xxx_timer4_addrs[] = { + { + .pa_start = 0x49036000, + .pa_end = 0x49036000 + SZ_1K - 1, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_per -> timer4 */ +static struct omap_hwmod_ocp_if omap3xxx_l4_per__timer4 = { + .master = &omap3xxx_l4_per_hwmod, + .slave = &omap3xxx_timer4_hwmod, + .clk = "gpt4_ick", + .addr = omap3xxx_timer4_addrs, + .addr_cnt = ARRAY_SIZE(omap3xxx_timer4_addrs), + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* timer4 slave port */ +static struct omap_hwmod_ocp_if *omap3xxx_timer4_slaves[] = { + &omap3xxx_l4_per__timer4, +}; + +/* timer4 hwmod */ +static struct omap_hwmod omap3xxx_timer4_hwmod = { + .name = "timer4", + .mpu_irqs = omap3xxx_timer4_mpu_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap3xxx_timer4_mpu_irqs), + .main_clk = "gpt4_fck", + .prcm = { + .omap2 = { + .prcm_reg_id = 1, + .module_bit = OMAP3430_EN_GPT4_SHIFT, + .module_offs = OMAP3430_PER_MOD, + .idlest_reg_id = 1, + .idlest_idle_bit = OMAP3430_ST_GPT4_SHIFT, + }, + }, + .slaves = omap3xxx_timer4_slaves, + .slaves_cnt = ARRAY_SIZE(omap3xxx_timer4_slaves), + .class = &omap3xxx_timer_hwmod_class, + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP3430) +}; + +/* timer5 */ +static struct omap_hwmod omap3xxx_timer5_hwmod; +static struct omap_hwmod_irq_info omap3xxx_timer5_mpu_irqs[] = { + { .irq = 41, }, +}; + +static struct omap_hwmod_addr_space omap3xxx_timer5_addrs[] = { + { + .pa_start = 0x49038000, + .pa_end = 0x49038000 + SZ_1K - 1, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_per -> timer5 */ +static struct omap_hwmod_ocp_if omap3xxx_l4_per__timer5 = { + .master = &omap3xxx_l4_per_hwmod, + .slave = &omap3xxx_timer5_hwmod, + .clk = "gpt5_ick", + .addr = omap3xxx_timer5_addrs, + .addr_cnt = ARRAY_SIZE(omap3xxx_timer5_addrs), + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* timer5 slave port */ +static struct omap_hwmod_ocp_if *omap3xxx_timer5_slaves[] = { + &omap3xxx_l4_per__timer5, +}; + +/* timer5 hwmod */ +static struct omap_hwmod omap3xxx_timer5_hwmod = { + .name = "timer5", + .mpu_irqs = omap3xxx_timer5_mpu_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap3xxx_timer5_mpu_irqs), + .main_clk = "gpt5_fck", + .prcm = { + .omap2 = { + .prcm_reg_id = 1, + .module_bit = OMAP3430_EN_GPT5_SHIFT, + .module_offs = OMAP3430_PER_MOD, + .idlest_reg_id = 1, + .idlest_idle_bit = OMAP3430_ST_GPT5_SHIFT, + }, + }, + .slaves = omap3xxx_timer5_slaves, + .slaves_cnt = ARRAY_SIZE(omap3xxx_timer5_slaves), + .class = &omap3xxx_timer_hwmod_class, + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP3430) +}; + +/* timer6 */ +static struct omap_hwmod omap3xxx_timer6_hwmod; +static struct omap_hwmod_irq_info omap3xxx_timer6_mpu_irqs[] = { + { .irq = 42, }, +}; + +static struct omap_hwmod_addr_space omap3xxx_timer6_addrs[] = { + { + .pa_start = 0x4903A000, + .pa_end = 0x4903A000 + SZ_1K - 1, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_per -> timer6 */ +static struct omap_hwmod_ocp_if omap3xxx_l4_per__timer6 = { + .master = &omap3xxx_l4_per_hwmod, + .slave = &omap3xxx_timer6_hwmod, + .clk = "gpt6_ick", + .addr = omap3xxx_timer6_addrs, + .addr_cnt = ARRAY_SIZE(omap3xxx_timer6_addrs), + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* timer6 slave port */ +static struct omap_hwmod_ocp_if *omap3xxx_timer6_slaves[] = { + &omap3xxx_l4_per__timer6, +}; + +/* timer6 hwmod */ +static struct omap_hwmod omap3xxx_timer6_hwmod = { + .name = "timer6", + .mpu_irqs = omap3xxx_timer6_mpu_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap3xxx_timer6_mpu_irqs), + .main_clk = "gpt6_fck", + .prcm = { + .omap2 = { + .prcm_reg_id = 1, + .module_bit = OMAP3430_EN_GPT6_SHIFT, + .module_offs = OMAP3430_PER_MOD, + .idlest_reg_id = 1, + .idlest_idle_bit = OMAP3430_ST_GPT6_SHIFT, + }, + }, + .slaves = omap3xxx_timer6_slaves, + .slaves_cnt = ARRAY_SIZE(omap3xxx_timer6_slaves), + .class = &omap3xxx_timer_hwmod_class, + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP3430) +}; + +/* timer7 */ +static struct omap_hwmod omap3xxx_timer7_hwmod; +static struct omap_hwmod_irq_info omap3xxx_timer7_mpu_irqs[] = { + { .irq = 43, }, +}; + +static struct omap_hwmod_addr_space omap3xxx_timer7_addrs[] = { + { + .pa_start = 0x4903C000, + .pa_end = 0x4903C000 + SZ_1K - 1, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_per -> timer7 */ +static struct omap_hwmod_ocp_if omap3xxx_l4_per__timer7 = { + .master = &omap3xxx_l4_per_hwmod, + .slave = &omap3xxx_timer7_hwmod, + .clk = "gpt7_ick", + .addr = omap3xxx_timer7_addrs, + .addr_cnt = ARRAY_SIZE(omap3xxx_timer7_addrs), + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* timer7 slave port */ +static struct omap_hwmod_ocp_if *omap3xxx_timer7_slaves[] = { + &omap3xxx_l4_per__timer7, +}; + +/* timer7 hwmod */ +static struct omap_hwmod omap3xxx_timer7_hwmod = { + .name = "timer7", + .mpu_irqs = omap3xxx_timer7_mpu_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap3xxx_timer7_mpu_irqs), + .main_clk = "gpt7_fck", + .prcm = { + .omap2 = { + .prcm_reg_id = 1, + .module_bit = OMAP3430_EN_GPT7_SHIFT, + .module_offs = OMAP3430_PER_MOD, + .idlest_reg_id = 1, + .idlest_idle_bit = OMAP3430_ST_GPT7_SHIFT, + }, + }, + .slaves = omap3xxx_timer7_slaves, + .slaves_cnt = ARRAY_SIZE(omap3xxx_timer7_slaves), + .class = &omap3xxx_timer_hwmod_class, + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP3430) +}; + +/* timer8 */ +static struct omap_hwmod omap3xxx_timer8_hwmod; +static struct omap_hwmod_irq_info omap3xxx_timer8_mpu_irqs[] = { + { .irq = 44, }, +}; + +static struct omap_hwmod_addr_space omap3xxx_timer8_addrs[] = { + { + .pa_start = 0x4903E000, + .pa_end = 0x4903E000 + SZ_1K - 1, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_per -> timer8 */ +static struct omap_hwmod_ocp_if omap3xxx_l4_per__timer8 = { + .master = &omap3xxx_l4_per_hwmod, + .slave = &omap3xxx_timer8_hwmod, + .clk = "gpt8_ick", + .addr = omap3xxx_timer8_addrs, + .addr_cnt = ARRAY_SIZE(omap3xxx_timer8_addrs), + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* timer8 slave port */ +static struct omap_hwmod_ocp_if *omap3xxx_timer8_slaves[] = { + &omap3xxx_l4_per__timer8, +}; + +/* timer8 hwmod */ +static struct omap_hwmod omap3xxx_timer8_hwmod = { + .name = "timer8", + .mpu_irqs = omap3xxx_timer8_mpu_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap3xxx_timer8_mpu_irqs), + .main_clk = "gpt8_fck", + .prcm = { + .omap2 = { + .prcm_reg_id = 1, + .module_bit = OMAP3430_EN_GPT8_SHIFT, + .module_offs = OMAP3430_PER_MOD, + .idlest_reg_id = 1, + .idlest_idle_bit = OMAP3430_ST_GPT8_SHIFT, + }, + }, + .slaves = omap3xxx_timer8_slaves, + .slaves_cnt = ARRAY_SIZE(omap3xxx_timer8_slaves), + .class = &omap3xxx_timer_hwmod_class, + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP3430) +}; + +/* timer9 */ +static struct omap_hwmod omap3xxx_timer9_hwmod; +static struct omap_hwmod_irq_info omap3xxx_timer9_mpu_irqs[] = { + { .irq = 45, }, +}; + +static struct omap_hwmod_addr_space omap3xxx_timer9_addrs[] = { + { + .pa_start = 0x49040000, + .pa_end = 0x49040000 + SZ_1K - 1, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_per -> timer9 */ +static struct omap_hwmod_ocp_if omap3xxx_l4_per__timer9 = { + .master = &omap3xxx_l4_per_hwmod, + .slave = &omap3xxx_timer9_hwmod, + .clk = "gpt9_ick", + .addr = omap3xxx_timer9_addrs, + .addr_cnt = ARRAY_SIZE(omap3xxx_timer9_addrs), + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* timer9 slave port */ +static struct omap_hwmod_ocp_if *omap3xxx_timer9_slaves[] = { + &omap3xxx_l4_per__timer9, +}; + +/* timer9 hwmod */ +static struct omap_hwmod omap3xxx_timer9_hwmod = { + .name = "timer9", + .mpu_irqs = omap3xxx_timer9_mpu_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap3xxx_timer9_mpu_irqs), + .main_clk = "gpt9_fck", + .prcm = { + .omap2 = { + .prcm_reg_id = 1, + .module_bit = OMAP3430_EN_GPT9_SHIFT, + .module_offs = OMAP3430_PER_MOD, + .idlest_reg_id = 1, + .idlest_idle_bit = OMAP3430_ST_GPT9_SHIFT, + }, + }, + .slaves = omap3xxx_timer9_slaves, + .slaves_cnt = ARRAY_SIZE(omap3xxx_timer9_slaves), + .class = &omap3xxx_timer_hwmod_class, + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP3430) +}; + +/* timer10 */ +static struct omap_hwmod omap3xxx_timer10_hwmod; +static struct omap_hwmod_irq_info omap3xxx_timer10_mpu_irqs[] = { + { .irq = 46, }, +}; + +static struct omap_hwmod_addr_space omap3xxx_timer10_addrs[] = { + { + .pa_start = 0x48086000, + .pa_end = 0x48086000 + SZ_1K - 1, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_core -> timer10 */ +static struct omap_hwmod_ocp_if omap3xxx_l4_core__timer10 = { + .master = &omap3xxx_l4_core_hwmod, + .slave = &omap3xxx_timer10_hwmod, + .clk = "gpt10_ick", + .addr = omap3xxx_timer10_addrs, + .addr_cnt = ARRAY_SIZE(omap3xxx_timer10_addrs), + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* timer10 slave port */ +static struct omap_hwmod_ocp_if *omap3xxx_timer10_slaves[] = { + &omap3xxx_l4_core__timer10, +}; + +/* timer10 hwmod */ +static struct omap_hwmod omap3xxx_timer10_hwmod = { + .name = "timer10", + .mpu_irqs = omap3xxx_timer10_mpu_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap3xxx_timer10_mpu_irqs), + .main_clk = "gpt10_fck", + .prcm = { + .omap2 = { + .prcm_reg_id = 1, + .module_bit = OMAP3430_EN_GPT10_SHIFT, + .module_offs = CORE_MOD, + .idlest_reg_id = 1, + .idlest_idle_bit = OMAP3430_ST_GPT10_SHIFT, + }, + }, + .slaves = omap3xxx_timer10_slaves, + .slaves_cnt = ARRAY_SIZE(omap3xxx_timer10_slaves), + .class = &omap3xxx_timer_1ms_hwmod_class, + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP3430) +}; + +/* timer11 */ +static struct omap_hwmod omap3xxx_timer11_hwmod; +static struct omap_hwmod_irq_info omap3xxx_timer11_mpu_irqs[] = { + { .irq = 47, }, +}; + +static struct omap_hwmod_addr_space omap3xxx_timer11_addrs[] = { + { + .pa_start = 0x48088000, + .pa_end = 0x48088000 + SZ_1K - 1, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_core -> timer11 */ +static struct omap_hwmod_ocp_if omap3xxx_l4_core__timer11 = { + .master = &omap3xxx_l4_core_hwmod, + .slave = &omap3xxx_timer11_hwmod, + .clk = "gpt11_ick", + .addr = omap3xxx_timer11_addrs, + .addr_cnt = ARRAY_SIZE(omap3xxx_timer11_addrs), + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* timer11 slave port */ +static struct omap_hwmod_ocp_if *omap3xxx_timer11_slaves[] = { + &omap3xxx_l4_core__timer11, +}; + +/* timer11 hwmod */ +static struct omap_hwmod omap3xxx_timer11_hwmod = { + .name = "timer11", + .mpu_irqs = omap3xxx_timer11_mpu_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap3xxx_timer11_mpu_irqs), + .main_clk = "gpt11_fck", + .prcm = { + .omap2 = { + .prcm_reg_id = 1, + .module_bit = OMAP3430_EN_GPT11_SHIFT, + .module_offs = CORE_MOD, + .idlest_reg_id = 1, + .idlest_idle_bit = OMAP3430_ST_GPT11_SHIFT, + }, + }, + .slaves = omap3xxx_timer11_slaves, + .slaves_cnt = ARRAY_SIZE(omap3xxx_timer11_slaves), + .class = &omap3xxx_timer_hwmod_class, + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP3430) +}; + +/* timer12*/ +static struct omap_hwmod omap3xxx_timer12_hwmod; +static struct omap_hwmod_irq_info omap3xxx_timer12_mpu_irqs[] = { + { .irq = 95, }, +}; + +static struct omap_hwmod_addr_space omap3xxx_timer12_addrs[] = { + { + .pa_start = 0x48304000, + .pa_end = 0x48304000 + SZ_1K - 1, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_core -> timer12 */ +static struct omap_hwmod_ocp_if omap3xxx_l4_core__timer12 = { + .master = &omap3xxx_l4_core_hwmod, + .slave = &omap3xxx_timer12_hwmod, + .clk = "gpt12_ick", + .addr = omap3xxx_timer12_addrs, + .addr_cnt = ARRAY_SIZE(omap3xxx_timer12_addrs), + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* timer12 slave port */ +static struct omap_hwmod_ocp_if *omap3xxx_timer12_slaves[] = { + &omap3xxx_l4_core__timer12, +}; + +/* timer12 hwmod */ +static struct omap_hwmod omap3xxx_timer12_hwmod = { + .name = "timer12", + .mpu_irqs = omap3xxx_timer12_mpu_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap3xxx_timer12_mpu_irqs), + .main_clk = "gpt12_fck", + .prcm = { + .omap2 = { + .prcm_reg_id = 1, + .module_bit = OMAP3430_EN_GPT12_SHIFT, + .module_offs = WKUP_MOD, + .idlest_reg_id = 1, + .idlest_idle_bit = OMAP3430_ST_GPT12_SHIFT, + }, + }, + .slaves = omap3xxx_timer12_slaves, + .slaves_cnt = ARRAY_SIZE(omap3xxx_timer12_slaves), + .class = &omap3xxx_timer_hwmod_class, + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP3430) +}; + /* l4_wkup -> wd_timer2 */ static struct omap_hwmod_addr_space omap3xxx_wd_timer2_addrs[] = { { @@ -447,7 +1239,8 @@ static struct omap_hwmod_class_sysconfig omap3xxx_wd_timer_sysc = { .syss_offs = 0x0014, .sysc_flags = (SYSC_HAS_SIDLEMODE | SYSC_HAS_EMUFREE | SYSC_HAS_ENAWAKEUP | SYSC_HAS_SOFTRESET | - SYSC_HAS_AUTOIDLE | SYSC_HAS_CLOCKACTIVITY), + SYSC_HAS_AUTOIDLE | SYSC_HAS_CLOCKACTIVITY | + SYSS_HAS_RESET_STATUS), .idlemodes = (SIDLE_FORCE | SIDLE_NO | SIDLE_SMART), .sysc_fields = &omap_hwmod_sysc_type1, }; @@ -459,7 +1252,7 @@ static struct omap_hwmod_class_sysconfig i2c_sysc = { .syss_offs = 0x10, .sysc_flags = (SYSC_HAS_CLOCKACTIVITY | SYSC_HAS_SIDLEMODE | SYSC_HAS_ENAWAKEUP | SYSC_HAS_SOFTRESET | - SYSC_HAS_AUTOIDLE), + SYSC_HAS_AUTOIDLE | SYSS_HAS_RESET_STATUS), .idlemodes = (SIDLE_FORCE | SIDLE_NO | SIDLE_SMART), .sysc_fields = &omap_hwmod_sysc_type1, }; @@ -491,6 +1284,11 @@ static struct omap_hwmod omap3xxx_wd_timer2_hwmod = { .slaves = omap3xxx_wd_timer2_slaves, .slaves_cnt = ARRAY_SIZE(omap3xxx_wd_timer2_slaves), .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP3430), + /* + * XXX: Use software supervised mode, HW supervised smartidle seems to + * block CORE power domain idle transitions. Maybe a HW bug in wdt2? + */ + .flags = HWMOD_SWSUP_SIDLE, }; /* UART common */ @@ -501,7 +1299,7 @@ static struct omap_hwmod_class_sysconfig uart_sysc = { .syss_offs = 0x58, .sysc_flags = (SYSC_HAS_SIDLEMODE | SYSC_HAS_ENAWAKEUP | SYSC_HAS_SOFTRESET | - SYSC_HAS_AUTOIDLE), + SYSC_HAS_AUTOIDLE | SYSS_HAS_RESET_STATUS), .idlemodes = (SIDLE_FORCE | SIDLE_NO | SIDLE_SMART), .sysc_fields = &omap_hwmod_sysc_type1, }; @@ -664,6 +1462,411 @@ static struct omap_hwmod_class i2c_class = { .sysc = &i2c_sysc, }; +/* + * 'dss' class + * display sub-system + */ + +static struct omap_hwmod_class_sysconfig omap3xxx_dss_sysc = { + .rev_offs = 0x0000, + .sysc_offs = 0x0010, + .syss_offs = 0x0014, + .sysc_flags = (SYSC_HAS_SOFTRESET | SYSC_HAS_AUTOIDLE), + .sysc_fields = &omap_hwmod_sysc_type1, +}; + +static struct omap_hwmod_class omap3xxx_dss_hwmod_class = { + .name = "dss", + .sysc = &omap3xxx_dss_sysc, +}; + +/* dss */ +static struct omap_hwmod_irq_info omap3xxx_dss_irqs[] = { + { .irq = 25 }, +}; + +static struct omap_hwmod_dma_info omap3xxx_dss_sdma_chs[] = { + { .name = "dispc", .dma_req = 5 }, + { .name = "dsi1", .dma_req = 74 }, +}; + +/* dss */ +/* dss master ports */ +static struct omap_hwmod_ocp_if *omap3xxx_dss_masters[] = { + &omap3xxx_dss__l3, +}; + +static struct omap_hwmod_addr_space omap3xxx_dss_addrs[] = { + { + .pa_start = 0x48050000, + .pa_end = 0x480503FF, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_core -> dss */ +static struct omap_hwmod_ocp_if omap3430es1_l4_core__dss = { + .master = &omap3xxx_l4_core_hwmod, + .slave = &omap3430es1_dss_core_hwmod, + .clk = "dss_ick", + .addr = omap3xxx_dss_addrs, + .addr_cnt = ARRAY_SIZE(omap3xxx_dss_addrs), + .fw = { + .omap2 = { + .l4_fw_region = OMAP3ES1_L4_CORE_FW_DSS_CORE_REGION, + .l4_prot_group = OMAP3_L4_CORE_FW_DSS_PROT_GROUP, + .flags = OMAP_FIREWALL_L4, + } + }, + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +static struct omap_hwmod_ocp_if omap3xxx_l4_core__dss = { + .master = &omap3xxx_l4_core_hwmod, + .slave = &omap3xxx_dss_core_hwmod, + .clk = "dss_ick", + .addr = omap3xxx_dss_addrs, + .addr_cnt = ARRAY_SIZE(omap3xxx_dss_addrs), + .fw = { + .omap2 = { + .l4_fw_region = OMAP3_L4_CORE_FW_DSS_CORE_REGION, + .l4_prot_group = OMAP3_L4_CORE_FW_DSS_PROT_GROUP, + .flags = OMAP_FIREWALL_L4, + } + }, + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* dss slave ports */ +static struct omap_hwmod_ocp_if *omap3430es1_dss_slaves[] = { + &omap3430es1_l4_core__dss, +}; + +static struct omap_hwmod_ocp_if *omap3xxx_dss_slaves[] = { + &omap3xxx_l4_core__dss, +}; + +static struct omap_hwmod_opt_clk dss_opt_clks[] = { + { .role = "tv_clk", .clk = "dss_tv_fck" }, + { .role = "dssclk", .clk = "dss_96m_fck" }, + { .role = "sys_clk", .clk = "dss2_alwon_fck" }, +}; + +static struct omap_hwmod omap3430es1_dss_core_hwmod = { + .name = "dss_core", + .class = &omap3xxx_dss_hwmod_class, + .main_clk = "dss1_alwon_fck", /* instead of dss_fck */ + .mpu_irqs = omap3xxx_dss_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap3xxx_dss_irqs), + .sdma_reqs = omap3xxx_dss_sdma_chs, + .sdma_reqs_cnt = ARRAY_SIZE(omap3xxx_dss_sdma_chs), + + .prcm = { + .omap2 = { + .prcm_reg_id = 1, + .module_bit = OMAP3430_EN_DSS1_SHIFT, + .module_offs = OMAP3430_DSS_MOD, + .idlest_reg_id = 1, + .idlest_stdby_bit = OMAP3430ES1_ST_DSS_SHIFT, + }, + }, + .opt_clks = dss_opt_clks, + .opt_clks_cnt = ARRAY_SIZE(dss_opt_clks), + .slaves = omap3430es1_dss_slaves, + .slaves_cnt = ARRAY_SIZE(omap3430es1_dss_slaves), + .masters = omap3xxx_dss_masters, + .masters_cnt = ARRAY_SIZE(omap3xxx_dss_masters), + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP3430ES1), + .flags = HWMOD_NO_IDLEST, +}; + +static struct omap_hwmod omap3xxx_dss_core_hwmod = { + .name = "dss_core", + .class = &omap3xxx_dss_hwmod_class, + .main_clk = "dss1_alwon_fck", /* instead of dss_fck */ + .mpu_irqs = omap3xxx_dss_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap3xxx_dss_irqs), + .sdma_reqs = omap3xxx_dss_sdma_chs, + .sdma_reqs_cnt = ARRAY_SIZE(omap3xxx_dss_sdma_chs), + + .prcm = { + .omap2 = { + .prcm_reg_id = 1, + .module_bit = OMAP3430_EN_DSS1_SHIFT, + .module_offs = OMAP3430_DSS_MOD, + .idlest_reg_id = 1, + .idlest_idle_bit = OMAP3430ES2_ST_DSS_IDLE_SHIFT, + .idlest_stdby_bit = OMAP3430ES2_ST_DSS_STDBY_SHIFT, + }, + }, + .opt_clks = dss_opt_clks, + .opt_clks_cnt = ARRAY_SIZE(dss_opt_clks), + .slaves = omap3xxx_dss_slaves, + .slaves_cnt = ARRAY_SIZE(omap3xxx_dss_slaves), + .masters = omap3xxx_dss_masters, + .masters_cnt = ARRAY_SIZE(omap3xxx_dss_masters), + .omap_chip = OMAP_CHIP_INIT(CHIP_GE_OMAP3430ES2 | + CHIP_IS_OMAP3630ES1 | CHIP_GE_OMAP3630ES1_1), +}; + +/* + * 'dispc' class + * display controller + */ + +static struct omap_hwmod_class_sysconfig omap3xxx_dispc_sysc = { + .rev_offs = 0x0000, + .sysc_offs = 0x0010, + .syss_offs = 0x0014, + .sysc_flags = (SYSC_HAS_SIDLEMODE | SYSC_HAS_CLOCKACTIVITY | + SYSC_HAS_MIDLEMODE | SYSC_HAS_ENAWAKEUP | + SYSC_HAS_SOFTRESET | SYSC_HAS_AUTOIDLE), + .idlemodes = (SIDLE_FORCE | SIDLE_NO | SIDLE_SMART | + MSTANDBY_FORCE | MSTANDBY_NO | MSTANDBY_SMART), + .sysc_fields = &omap_hwmod_sysc_type1, +}; + +static struct omap_hwmod_class omap3xxx_dispc_hwmod_class = { + .name = "dispc", + .sysc = &omap3xxx_dispc_sysc, +}; + +static struct omap_hwmod_addr_space omap3xxx_dss_dispc_addrs[] = { + { + .pa_start = 0x48050400, + .pa_end = 0x480507FF, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_core -> dss_dispc */ +static struct omap_hwmod_ocp_if omap3xxx_l4_core__dss_dispc = { + .master = &omap3xxx_l4_core_hwmod, + .slave = &omap3xxx_dss_dispc_hwmod, + .clk = "dss_ick", + .addr = omap3xxx_dss_dispc_addrs, + .addr_cnt = ARRAY_SIZE(omap3xxx_dss_dispc_addrs), + .fw = { + .omap2 = { + .l4_fw_region = OMAP3_L4_CORE_FW_DSS_DISPC_REGION, + .l4_prot_group = OMAP3_L4_CORE_FW_DSS_PROT_GROUP, + .flags = OMAP_FIREWALL_L4, + } + }, + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* dss_dispc slave ports */ +static struct omap_hwmod_ocp_if *omap3xxx_dss_dispc_slaves[] = { + &omap3xxx_l4_core__dss_dispc, +}; + +static struct omap_hwmod omap3xxx_dss_dispc_hwmod = { + .name = "dss_dispc", + .class = &omap3xxx_dispc_hwmod_class, + .main_clk = "dss1_alwon_fck", + .prcm = { + .omap2 = { + .prcm_reg_id = 1, + .module_bit = OMAP3430_EN_DSS1_SHIFT, + .module_offs = OMAP3430_DSS_MOD, + }, + }, + .slaves = omap3xxx_dss_dispc_slaves, + .slaves_cnt = ARRAY_SIZE(omap3xxx_dss_dispc_slaves), + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP3430ES1 | + CHIP_GE_OMAP3430ES2 | CHIP_IS_OMAP3630ES1 | + CHIP_GE_OMAP3630ES1_1), + .flags = HWMOD_NO_IDLEST, +}; + +/* + * 'dsi' class + * display serial interface controller + */ + +static struct omap_hwmod_class omap3xxx_dsi_hwmod_class = { + .name = "dsi", +}; + +/* dss_dsi1 */ +static struct omap_hwmod_addr_space omap3xxx_dss_dsi1_addrs[] = { + { + .pa_start = 0x4804FC00, + .pa_end = 0x4804FFFF, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_core -> dss_dsi1 */ +static struct omap_hwmod_ocp_if omap3xxx_l4_core__dss_dsi1 = { + .master = &omap3xxx_l4_core_hwmod, + .slave = &omap3xxx_dss_dsi1_hwmod, + .addr = omap3xxx_dss_dsi1_addrs, + .addr_cnt = ARRAY_SIZE(omap3xxx_dss_dsi1_addrs), + .fw = { + .omap2 = { + .l4_fw_region = OMAP3_L4_CORE_FW_DSS_DSI_REGION, + .l4_prot_group = OMAP3_L4_CORE_FW_DSS_PROT_GROUP, + .flags = OMAP_FIREWALL_L4, + } + }, + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* dss_dsi1 slave ports */ +static struct omap_hwmod_ocp_if *omap3xxx_dss_dsi1_slaves[] = { + &omap3xxx_l4_core__dss_dsi1, +}; + +static struct omap_hwmod omap3xxx_dss_dsi1_hwmod = { + .name = "dss_dsi1", + .class = &omap3xxx_dsi_hwmod_class, + .main_clk = "dss1_alwon_fck", + .prcm = { + .omap2 = { + .prcm_reg_id = 1, + .module_bit = OMAP3430_EN_DSS1_SHIFT, + .module_offs = OMAP3430_DSS_MOD, + }, + }, + .slaves = omap3xxx_dss_dsi1_slaves, + .slaves_cnt = ARRAY_SIZE(omap3xxx_dss_dsi1_slaves), + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP3430ES1 | + CHIP_GE_OMAP3430ES2 | CHIP_IS_OMAP3630ES1 | + CHIP_GE_OMAP3630ES1_1), + .flags = HWMOD_NO_IDLEST, +}; + +/* + * 'rfbi' class + * remote frame buffer interface + */ + +static struct omap_hwmod_class_sysconfig omap3xxx_rfbi_sysc = { + .rev_offs = 0x0000, + .sysc_offs = 0x0010, + .syss_offs = 0x0014, + .sysc_flags = (SYSC_HAS_SIDLEMODE | SYSC_HAS_SOFTRESET | + SYSC_HAS_AUTOIDLE), + .idlemodes = (SIDLE_FORCE | SIDLE_NO | SIDLE_SMART), + .sysc_fields = &omap_hwmod_sysc_type1, +}; + +static struct omap_hwmod_class omap3xxx_rfbi_hwmod_class = { + .name = "rfbi", + .sysc = &omap3xxx_rfbi_sysc, +}; + +static struct omap_hwmod_addr_space omap3xxx_dss_rfbi_addrs[] = { + { + .pa_start = 0x48050800, + .pa_end = 0x48050BFF, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_core -> dss_rfbi */ +static struct omap_hwmod_ocp_if omap3xxx_l4_core__dss_rfbi = { + .master = &omap3xxx_l4_core_hwmod, + .slave = &omap3xxx_dss_rfbi_hwmod, + .clk = "dss_ick", + .addr = omap3xxx_dss_rfbi_addrs, + .addr_cnt = ARRAY_SIZE(omap3xxx_dss_rfbi_addrs), + .fw = { + .omap2 = { + .l4_fw_region = OMAP3_L4_CORE_FW_DSS_RFBI_REGION, + .l4_prot_group = OMAP3_L4_CORE_FW_DSS_PROT_GROUP , + .flags = OMAP_FIREWALL_L4, + } + }, + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* dss_rfbi slave ports */ +static struct omap_hwmod_ocp_if *omap3xxx_dss_rfbi_slaves[] = { + &omap3xxx_l4_core__dss_rfbi, +}; + +static struct omap_hwmod omap3xxx_dss_rfbi_hwmod = { + .name = "dss_rfbi", + .class = &omap3xxx_rfbi_hwmod_class, + .main_clk = "dss1_alwon_fck", + .prcm = { + .omap2 = { + .prcm_reg_id = 1, + .module_bit = OMAP3430_EN_DSS1_SHIFT, + .module_offs = OMAP3430_DSS_MOD, + }, + }, + .slaves = omap3xxx_dss_rfbi_slaves, + .slaves_cnt = ARRAY_SIZE(omap3xxx_dss_rfbi_slaves), + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP3430ES1 | + CHIP_GE_OMAP3430ES2 | CHIP_IS_OMAP3630ES1 | + CHIP_GE_OMAP3630ES1_1), + .flags = HWMOD_NO_IDLEST, +}; + +/* + * 'venc' class + * video encoder + */ + +static struct omap_hwmod_class omap3xxx_venc_hwmod_class = { + .name = "venc", +}; + +/* dss_venc */ +static struct omap_hwmod_addr_space omap3xxx_dss_venc_addrs[] = { + { + .pa_start = 0x48050C00, + .pa_end = 0x48050FFF, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_core -> dss_venc */ +static struct omap_hwmod_ocp_if omap3xxx_l4_core__dss_venc = { + .master = &omap3xxx_l4_core_hwmod, + .slave = &omap3xxx_dss_venc_hwmod, + .clk = "dss_tv_fck", + .addr = omap3xxx_dss_venc_addrs, + .addr_cnt = ARRAY_SIZE(omap3xxx_dss_venc_addrs), + .fw = { + .omap2 = { + .l4_fw_region = OMAP3_L4_CORE_FW_DSS_VENC_REGION, + .l4_prot_group = OMAP3_L4_CORE_FW_DSS_PROT_GROUP, + .flags = OMAP_FIREWALL_L4, + } + }, + .flags = OCPIF_SWSUP_IDLE, + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* dss_venc slave ports */ +static struct omap_hwmod_ocp_if *omap3xxx_dss_venc_slaves[] = { + &omap3xxx_l4_core__dss_venc, +}; + +static struct omap_hwmod omap3xxx_dss_venc_hwmod = { + .name = "dss_venc", + .class = &omap3xxx_venc_hwmod_class, + .main_clk = "dss1_alwon_fck", + .prcm = { + .omap2 = { + .prcm_reg_id = 1, + .module_bit = OMAP3430_EN_DSS1_SHIFT, + .module_offs = OMAP3430_DSS_MOD, + }, + }, + .slaves = omap3xxx_dss_venc_slaves, + .slaves_cnt = ARRAY_SIZE(omap3xxx_dss_venc_slaves), + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP3430ES1 | + CHIP_GE_OMAP3430ES2 | CHIP_IS_OMAP3630ES1 | + CHIP_GE_OMAP3630ES1_1), + .flags = HWMOD_NO_IDLEST, +}; + /* I2C1 */ static struct omap_i2c_dev_attr i2c1_dev_attr = { @@ -902,7 +2105,8 @@ static struct omap_hwmod_class_sysconfig omap3xxx_gpio_sysc = { .sysc_offs = 0x0010, .syss_offs = 0x0014, .sysc_flags = (SYSC_HAS_ENAWAKEUP | SYSC_HAS_SIDLEMODE | - SYSC_HAS_SOFTRESET | SYSC_HAS_AUTOIDLE), + SYSC_HAS_SOFTRESET | SYSC_HAS_AUTOIDLE | + SYSS_HAS_RESET_STATUS), .idlemodes = (SIDLE_FORCE | SIDLE_NO | SIDLE_SMART), .sysc_fields = &omap_hwmod_sysc_type1, }; @@ -1156,7 +2360,8 @@ static struct omap_hwmod_class_sysconfig omap3xxx_dma_sysc = { .syss_offs = 0x0028, .sysc_flags = (SYSC_HAS_SIDLEMODE | SYSC_HAS_SOFTRESET | SYSC_HAS_MIDLEMODE | SYSC_HAS_CLOCKACTIVITY | - SYSC_HAS_EMUFREE | SYSC_HAS_AUTOIDLE), + SYSC_HAS_EMUFREE | SYSC_HAS_AUTOIDLE | + SYSS_HAS_RESET_STATUS), .idlemodes = (SIDLE_FORCE | SIDLE_NO | SIDLE_SMART | MSTANDBY_FORCE | MSTANDBY_NO | MSTANDBY_SMART), .sysc_fields = &omap_hwmod_sysc_type1, @@ -1227,6 +2432,437 @@ static struct omap_hwmod omap3xxx_dma_system_hwmod = { .flags = HWMOD_NO_IDLEST, }; +/* + * 'mcbsp' class + * multi channel buffered serial port controller + */ + +static struct omap_hwmod_class_sysconfig omap3xxx_mcbsp_sysc = { + .sysc_offs = 0x008c, + .sysc_flags = (SYSC_HAS_CLOCKACTIVITY | SYSC_HAS_ENAWAKEUP | + SYSC_HAS_SIDLEMODE | SYSC_HAS_SOFTRESET), + .idlemodes = (SIDLE_FORCE | SIDLE_NO | SIDLE_SMART), + .sysc_fields = &omap_hwmod_sysc_type1, + .clockact = 0x2, +}; + +static struct omap_hwmod_class omap3xxx_mcbsp_hwmod_class = { + .name = "mcbsp", + .sysc = &omap3xxx_mcbsp_sysc, + .rev = MCBSP_CONFIG_TYPE3, +}; + +/* mcbsp1 */ +static struct omap_hwmod_irq_info omap3xxx_mcbsp1_irqs[] = { + { .name = "irq", .irq = 16 }, + { .name = "tx", .irq = 59 }, + { .name = "rx", .irq = 60 }, +}; + +static struct omap_hwmod_dma_info omap3xxx_mcbsp1_sdma_chs[] = { + { .name = "rx", .dma_req = 32 }, + { .name = "tx", .dma_req = 31 }, +}; + +static struct omap_hwmod_addr_space omap3xxx_mcbsp1_addrs[] = { + { + .name = "mpu", + .pa_start = 0x48074000, + .pa_end = 0x480740ff, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_core -> mcbsp1 */ +static struct omap_hwmod_ocp_if omap3xxx_l4_core__mcbsp1 = { + .master = &omap3xxx_l4_core_hwmod, + .slave = &omap3xxx_mcbsp1_hwmod, + .clk = "mcbsp1_ick", + .addr = omap3xxx_mcbsp1_addrs, + .addr_cnt = ARRAY_SIZE(omap3xxx_mcbsp1_addrs), + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* mcbsp1 slave ports */ +static struct omap_hwmod_ocp_if *omap3xxx_mcbsp1_slaves[] = { + &omap3xxx_l4_core__mcbsp1, +}; + +static struct omap_hwmod omap3xxx_mcbsp1_hwmod = { + .name = "mcbsp1", + .class = &omap3xxx_mcbsp_hwmod_class, + .mpu_irqs = omap3xxx_mcbsp1_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap3xxx_mcbsp1_irqs), + .sdma_reqs = omap3xxx_mcbsp1_sdma_chs, + .sdma_reqs_cnt = ARRAY_SIZE(omap3xxx_mcbsp1_sdma_chs), + .main_clk = "mcbsp1_fck", + .prcm = { + .omap2 = { + .prcm_reg_id = 1, + .module_bit = OMAP3430_EN_MCBSP1_SHIFT, + .module_offs = CORE_MOD, + .idlest_reg_id = 1, + .idlest_idle_bit = OMAP3430_ST_MCBSP1_SHIFT, + }, + }, + .slaves = omap3xxx_mcbsp1_slaves, + .slaves_cnt = ARRAY_SIZE(omap3xxx_mcbsp1_slaves), + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP3430), +}; + +/* mcbsp2 */ +static struct omap_hwmod_irq_info omap3xxx_mcbsp2_irqs[] = { + { .name = "irq", .irq = 17 }, + { .name = "tx", .irq = 62 }, + { .name = "rx", .irq = 63 }, +}; + +static struct omap_hwmod_dma_info omap3xxx_mcbsp2_sdma_chs[] = { + { .name = "rx", .dma_req = 34 }, + { .name = "tx", .dma_req = 33 }, +}; + +static struct omap_hwmod_addr_space omap3xxx_mcbsp2_addrs[] = { + { + .name = "mpu", + .pa_start = 0x49022000, + .pa_end = 0x490220ff, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_per -> mcbsp2 */ +static struct omap_hwmod_ocp_if omap3xxx_l4_per__mcbsp2 = { + .master = &omap3xxx_l4_per_hwmod, + .slave = &omap3xxx_mcbsp2_hwmod, + .clk = "mcbsp2_ick", + .addr = omap3xxx_mcbsp2_addrs, + .addr_cnt = ARRAY_SIZE(omap3xxx_mcbsp2_addrs), + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* mcbsp2 slave ports */ +static struct omap_hwmod_ocp_if *omap3xxx_mcbsp2_slaves[] = { + &omap3xxx_l4_per__mcbsp2, +}; + +static struct omap_mcbsp_dev_attr omap34xx_mcbsp2_dev_attr = { + .sidetone = "mcbsp2_sidetone", +}; + +static struct omap_hwmod omap3xxx_mcbsp2_hwmod = { + .name = "mcbsp2", + .class = &omap3xxx_mcbsp_hwmod_class, + .mpu_irqs = omap3xxx_mcbsp2_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap3xxx_mcbsp2_irqs), + .sdma_reqs = omap3xxx_mcbsp2_sdma_chs, + .sdma_reqs_cnt = ARRAY_SIZE(omap3xxx_mcbsp2_sdma_chs), + .main_clk = "mcbsp2_fck", + .prcm = { + .omap2 = { + .prcm_reg_id = 1, + .module_bit = OMAP3430_EN_MCBSP2_SHIFT, + .module_offs = OMAP3430_PER_MOD, + .idlest_reg_id = 1, + .idlest_idle_bit = OMAP3430_ST_MCBSP2_SHIFT, + }, + }, + .slaves = omap3xxx_mcbsp2_slaves, + .slaves_cnt = ARRAY_SIZE(omap3xxx_mcbsp2_slaves), + .dev_attr = &omap34xx_mcbsp2_dev_attr, + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP3430), +}; + +/* mcbsp3 */ +static struct omap_hwmod_irq_info omap3xxx_mcbsp3_irqs[] = { + { .name = "irq", .irq = 22 }, + { .name = "tx", .irq = 89 }, + { .name = "rx", .irq = 90 }, +}; + +static struct omap_hwmod_dma_info omap3xxx_mcbsp3_sdma_chs[] = { + { .name = "rx", .dma_req = 18 }, + { .name = "tx", .dma_req = 17 }, +}; + +static struct omap_hwmod_addr_space omap3xxx_mcbsp3_addrs[] = { + { + .name = "mpu", + .pa_start = 0x49024000, + .pa_end = 0x490240ff, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_per -> mcbsp3 */ +static struct omap_hwmod_ocp_if omap3xxx_l4_per__mcbsp3 = { + .master = &omap3xxx_l4_per_hwmod, + .slave = &omap3xxx_mcbsp3_hwmod, + .clk = "mcbsp3_ick", + .addr = omap3xxx_mcbsp3_addrs, + .addr_cnt = ARRAY_SIZE(omap3xxx_mcbsp3_addrs), + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* mcbsp3 slave ports */ +static struct omap_hwmod_ocp_if *omap3xxx_mcbsp3_slaves[] = { + &omap3xxx_l4_per__mcbsp3, +}; + +static struct omap_mcbsp_dev_attr omap34xx_mcbsp3_dev_attr = { + .sidetone = "mcbsp3_sidetone", +}; + +static struct omap_hwmod omap3xxx_mcbsp3_hwmod = { + .name = "mcbsp3", + .class = &omap3xxx_mcbsp_hwmod_class, + .mpu_irqs = omap3xxx_mcbsp3_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap3xxx_mcbsp3_irqs), + .sdma_reqs = omap3xxx_mcbsp3_sdma_chs, + .sdma_reqs_cnt = ARRAY_SIZE(omap3xxx_mcbsp3_sdma_chs), + .main_clk = "mcbsp3_fck", + .prcm = { + .omap2 = { + .prcm_reg_id = 1, + .module_bit = OMAP3430_EN_MCBSP3_SHIFT, + .module_offs = OMAP3430_PER_MOD, + .idlest_reg_id = 1, + .idlest_idle_bit = OMAP3430_ST_MCBSP3_SHIFT, + }, + }, + .slaves = omap3xxx_mcbsp3_slaves, + .slaves_cnt = ARRAY_SIZE(omap3xxx_mcbsp3_slaves), + .dev_attr = &omap34xx_mcbsp3_dev_attr, + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP3430), +}; + +/* mcbsp4 */ +static struct omap_hwmod_irq_info omap3xxx_mcbsp4_irqs[] = { + { .name = "irq", .irq = 23 }, + { .name = "tx", .irq = 54 }, + { .name = "rx", .irq = 55 }, +}; + +static struct omap_hwmod_dma_info omap3xxx_mcbsp4_sdma_chs[] = { + { .name = "rx", .dma_req = 20 }, + { .name = "tx", .dma_req = 19 }, +}; + +static struct omap_hwmod_addr_space omap3xxx_mcbsp4_addrs[] = { + { + .name = "mpu", + .pa_start = 0x49026000, + .pa_end = 0x490260ff, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_per -> mcbsp4 */ +static struct omap_hwmod_ocp_if omap3xxx_l4_per__mcbsp4 = { + .master = &omap3xxx_l4_per_hwmod, + .slave = &omap3xxx_mcbsp4_hwmod, + .clk = "mcbsp4_ick", + .addr = omap3xxx_mcbsp4_addrs, + .addr_cnt = ARRAY_SIZE(omap3xxx_mcbsp4_addrs), + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* mcbsp4 slave ports */ +static struct omap_hwmod_ocp_if *omap3xxx_mcbsp4_slaves[] = { + &omap3xxx_l4_per__mcbsp4, +}; + +static struct omap_hwmod omap3xxx_mcbsp4_hwmod = { + .name = "mcbsp4", + .class = &omap3xxx_mcbsp_hwmod_class, + .mpu_irqs = omap3xxx_mcbsp4_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap3xxx_mcbsp4_irqs), + .sdma_reqs = omap3xxx_mcbsp4_sdma_chs, + .sdma_reqs_cnt = ARRAY_SIZE(omap3xxx_mcbsp4_sdma_chs), + .main_clk = "mcbsp4_fck", + .prcm = { + .omap2 = { + .prcm_reg_id = 1, + .module_bit = OMAP3430_EN_MCBSP4_SHIFT, + .module_offs = OMAP3430_PER_MOD, + .idlest_reg_id = 1, + .idlest_idle_bit = OMAP3430_ST_MCBSP4_SHIFT, + }, + }, + .slaves = omap3xxx_mcbsp4_slaves, + .slaves_cnt = ARRAY_SIZE(omap3xxx_mcbsp4_slaves), + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP3430), +}; + +/* mcbsp5 */ +static struct omap_hwmod_irq_info omap3xxx_mcbsp5_irqs[] = { + { .name = "irq", .irq = 27 }, + { .name = "tx", .irq = 81 }, + { .name = "rx", .irq = 82 }, +}; + +static struct omap_hwmod_dma_info omap3xxx_mcbsp5_sdma_chs[] = { + { .name = "rx", .dma_req = 22 }, + { .name = "tx", .dma_req = 21 }, +}; + +static struct omap_hwmod_addr_space omap3xxx_mcbsp5_addrs[] = { + { + .name = "mpu", + .pa_start = 0x48096000, + .pa_end = 0x480960ff, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_core -> mcbsp5 */ +static struct omap_hwmod_ocp_if omap3xxx_l4_core__mcbsp5 = { + .master = &omap3xxx_l4_core_hwmod, + .slave = &omap3xxx_mcbsp5_hwmod, + .clk = "mcbsp5_ick", + .addr = omap3xxx_mcbsp5_addrs, + .addr_cnt = ARRAY_SIZE(omap3xxx_mcbsp5_addrs), + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* mcbsp5 slave ports */ +static struct omap_hwmod_ocp_if *omap3xxx_mcbsp5_slaves[] = { + &omap3xxx_l4_core__mcbsp5, +}; + +static struct omap_hwmod omap3xxx_mcbsp5_hwmod = { + .name = "mcbsp5", + .class = &omap3xxx_mcbsp_hwmod_class, + .mpu_irqs = omap3xxx_mcbsp5_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap3xxx_mcbsp5_irqs), + .sdma_reqs = omap3xxx_mcbsp5_sdma_chs, + .sdma_reqs_cnt = ARRAY_SIZE(omap3xxx_mcbsp5_sdma_chs), + .main_clk = "mcbsp5_fck", + .prcm = { + .omap2 = { + .prcm_reg_id = 1, + .module_bit = OMAP3430_EN_MCBSP5_SHIFT, + .module_offs = CORE_MOD, + .idlest_reg_id = 1, + .idlest_idle_bit = OMAP3430_ST_MCBSP5_SHIFT, + }, + }, + .slaves = omap3xxx_mcbsp5_slaves, + .slaves_cnt = ARRAY_SIZE(omap3xxx_mcbsp5_slaves), + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP3430), +}; +/* 'mcbsp sidetone' class */ + +static struct omap_hwmod_class_sysconfig omap3xxx_mcbsp_sidetone_sysc = { + .sysc_offs = 0x0010, + .sysc_flags = SYSC_HAS_AUTOIDLE, + .sysc_fields = &omap_hwmod_sysc_type1, +}; + +static struct omap_hwmod_class omap3xxx_mcbsp_sidetone_hwmod_class = { + .name = "mcbsp_sidetone", + .sysc = &omap3xxx_mcbsp_sidetone_sysc, +}; + +/* mcbsp2_sidetone */ +static struct omap_hwmod_irq_info omap3xxx_mcbsp2_sidetone_irqs[] = { + { .name = "irq", .irq = 4 }, +}; + +static struct omap_hwmod_addr_space omap3xxx_mcbsp2_sidetone_addrs[] = { + { + .name = "sidetone", + .pa_start = 0x49028000, + .pa_end = 0x490280ff, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_per -> mcbsp2_sidetone */ +static struct omap_hwmod_ocp_if omap3xxx_l4_per__mcbsp2_sidetone = { + .master = &omap3xxx_l4_per_hwmod, + .slave = &omap3xxx_mcbsp2_sidetone_hwmod, + .clk = "mcbsp2_ick", + .addr = omap3xxx_mcbsp2_sidetone_addrs, + .addr_cnt = ARRAY_SIZE(omap3xxx_mcbsp2_sidetone_addrs), + .user = OCP_USER_MPU, +}; + +/* mcbsp2_sidetone slave ports */ +static struct omap_hwmod_ocp_if *omap3xxx_mcbsp2_sidetone_slaves[] = { + &omap3xxx_l4_per__mcbsp2_sidetone, +}; + +static struct omap_hwmod omap3xxx_mcbsp2_sidetone_hwmod = { + .name = "mcbsp2_sidetone", + .class = &omap3xxx_mcbsp_sidetone_hwmod_class, + .mpu_irqs = omap3xxx_mcbsp2_sidetone_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap3xxx_mcbsp2_sidetone_irqs), + .main_clk = "mcbsp2_fck", + .prcm = { + .omap2 = { + .prcm_reg_id = 1, + .module_bit = OMAP3430_EN_MCBSP2_SHIFT, + .module_offs = OMAP3430_PER_MOD, + .idlest_reg_id = 1, + .idlest_idle_bit = OMAP3430_ST_MCBSP2_SHIFT, + }, + }, + .slaves = omap3xxx_mcbsp2_sidetone_slaves, + .slaves_cnt = ARRAY_SIZE(omap3xxx_mcbsp2_sidetone_slaves), + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP3430), +}; + +/* mcbsp3_sidetone */ +static struct omap_hwmod_irq_info omap3xxx_mcbsp3_sidetone_irqs[] = { + { .name = "irq", .irq = 5 }, +}; + +static struct omap_hwmod_addr_space omap3xxx_mcbsp3_sidetone_addrs[] = { + { + .name = "sidetone", + .pa_start = 0x4902A000, + .pa_end = 0x4902A0ff, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_per -> mcbsp3_sidetone */ +static struct omap_hwmod_ocp_if omap3xxx_l4_per__mcbsp3_sidetone = { + .master = &omap3xxx_l4_per_hwmod, + .slave = &omap3xxx_mcbsp3_sidetone_hwmod, + .clk = "mcbsp3_ick", + .addr = omap3xxx_mcbsp3_sidetone_addrs, + .addr_cnt = ARRAY_SIZE(omap3xxx_mcbsp3_sidetone_addrs), + .user = OCP_USER_MPU, +}; + +/* mcbsp3_sidetone slave ports */ +static struct omap_hwmod_ocp_if *omap3xxx_mcbsp3_sidetone_slaves[] = { + &omap3xxx_l4_per__mcbsp3_sidetone, +}; + +static struct omap_hwmod omap3xxx_mcbsp3_sidetone_hwmod = { + .name = "mcbsp3_sidetone", + .class = &omap3xxx_mcbsp_sidetone_hwmod_class, + .mpu_irqs = omap3xxx_mcbsp3_sidetone_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap3xxx_mcbsp3_sidetone_irqs), + .main_clk = "mcbsp3_fck", + .prcm = { + .omap2 = { + .prcm_reg_id = 1, + .module_bit = OMAP3430_EN_MCBSP3_SHIFT, + .module_offs = OMAP3430_PER_MOD, + .idlest_reg_id = 1, + .idlest_idle_bit = OMAP3430_ST_MCBSP3_SHIFT, + }, + }, + .slaves = omap3xxx_mcbsp3_sidetone_slaves, + .slaves_cnt = ARRAY_SIZE(omap3xxx_mcbsp3_sidetone_slaves), + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP3430), +}; + + /* SR common */ static struct omap_hwmod_sysc_fields omap34xx_sr_sysc_fields = { .clkact_shift = 20, @@ -1356,18 +2992,617 @@ static struct omap_hwmod omap36xx_sr2_hwmod = { .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP3630ES1), }; +/* + * 'mailbox' class + * mailbox module allowing communication between the on-chip processors + * using a queued mailbox-interrupt mechanism. + */ + +static struct omap_hwmod_class_sysconfig omap3xxx_mailbox_sysc = { + .rev_offs = 0x000, + .sysc_offs = 0x010, + .syss_offs = 0x014, + .sysc_flags = (SYSC_HAS_CLOCKACTIVITY | SYSC_HAS_SIDLEMODE | + SYSC_HAS_SOFTRESET | SYSC_HAS_AUTOIDLE), + .idlemodes = (SIDLE_FORCE | SIDLE_NO | SIDLE_SMART), + .sysc_fields = &omap_hwmod_sysc_type1, +}; + +static struct omap_hwmod_class omap3xxx_mailbox_hwmod_class = { + .name = "mailbox", + .sysc = &omap3xxx_mailbox_sysc, +}; + +static struct omap_hwmod omap3xxx_mailbox_hwmod; +static struct omap_hwmod_irq_info omap3xxx_mailbox_irqs[] = { + { .irq = 26 }, +}; + +static struct omap_hwmod_addr_space omap3xxx_mailbox_addrs[] = { + { + .pa_start = 0x48094000, + .pa_end = 0x480941ff, + .flags = ADDR_TYPE_RT, + }, +}; + +/* l4_core -> mailbox */ +static struct omap_hwmod_ocp_if omap3xxx_l4_core__mailbox = { + .master = &omap3xxx_l4_core_hwmod, + .slave = &omap3xxx_mailbox_hwmod, + .addr = omap3xxx_mailbox_addrs, + .addr_cnt = ARRAY_SIZE(omap3xxx_mailbox_addrs), + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* mailbox slave ports */ +static struct omap_hwmod_ocp_if *omap3xxx_mailbox_slaves[] = { + &omap3xxx_l4_core__mailbox, +}; + +static struct omap_hwmod omap3xxx_mailbox_hwmod = { + .name = "mailbox", + .class = &omap3xxx_mailbox_hwmod_class, + .mpu_irqs = omap3xxx_mailbox_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap3xxx_mailbox_irqs), + .main_clk = "mailboxes_ick", + .prcm = { + .omap2 = { + .prcm_reg_id = 1, + .module_bit = OMAP3430_EN_MAILBOXES_SHIFT, + .module_offs = CORE_MOD, + .idlest_reg_id = 1, + .idlest_idle_bit = OMAP3430_ST_MAILBOXES_SHIFT, + }, + }, + .slaves = omap3xxx_mailbox_slaves, + .slaves_cnt = ARRAY_SIZE(omap3xxx_mailbox_slaves), + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP3430), +}; + +/* l4 core -> mcspi1 interface */ +static struct omap_hwmod_addr_space omap34xx_mcspi1_addr_space[] = { + { + .pa_start = 0x48098000, + .pa_end = 0x480980ff, + .flags = ADDR_TYPE_RT, + }, +}; + +static struct omap_hwmod_ocp_if omap34xx_l4_core__mcspi1 = { + .master = &omap3xxx_l4_core_hwmod, + .slave = &omap34xx_mcspi1, + .clk = "mcspi1_ick", + .addr = omap34xx_mcspi1_addr_space, + .addr_cnt = ARRAY_SIZE(omap34xx_mcspi1_addr_space), + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* l4 core -> mcspi2 interface */ +static struct omap_hwmod_addr_space omap34xx_mcspi2_addr_space[] = { + { + .pa_start = 0x4809a000, + .pa_end = 0x4809a0ff, + .flags = ADDR_TYPE_RT, + }, +}; + +static struct omap_hwmod_ocp_if omap34xx_l4_core__mcspi2 = { + .master = &omap3xxx_l4_core_hwmod, + .slave = &omap34xx_mcspi2, + .clk = "mcspi2_ick", + .addr = omap34xx_mcspi2_addr_space, + .addr_cnt = ARRAY_SIZE(omap34xx_mcspi2_addr_space), + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* l4 core -> mcspi3 interface */ +static struct omap_hwmod_addr_space omap34xx_mcspi3_addr_space[] = { + { + .pa_start = 0x480b8000, + .pa_end = 0x480b80ff, + .flags = ADDR_TYPE_RT, + }, +}; + +static struct omap_hwmod_ocp_if omap34xx_l4_core__mcspi3 = { + .master = &omap3xxx_l4_core_hwmod, + .slave = &omap34xx_mcspi3, + .clk = "mcspi3_ick", + .addr = omap34xx_mcspi3_addr_space, + .addr_cnt = ARRAY_SIZE(omap34xx_mcspi3_addr_space), + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* l4 core -> mcspi4 interface */ +static struct omap_hwmod_addr_space omap34xx_mcspi4_addr_space[] = { + { + .pa_start = 0x480ba000, + .pa_end = 0x480ba0ff, + .flags = ADDR_TYPE_RT, + }, +}; + +static struct omap_hwmod_ocp_if omap34xx_l4_core__mcspi4 = { + .master = &omap3xxx_l4_core_hwmod, + .slave = &omap34xx_mcspi4, + .clk = "mcspi4_ick", + .addr = omap34xx_mcspi4_addr_space, + .addr_cnt = ARRAY_SIZE(omap34xx_mcspi4_addr_space), + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* + * 'mcspi' class + * multichannel serial port interface (mcspi) / master/slave synchronous serial + * bus + */ + +static struct omap_hwmod_class_sysconfig omap34xx_mcspi_sysc = { + .rev_offs = 0x0000, + .sysc_offs = 0x0010, + .syss_offs = 0x0014, + .sysc_flags = (SYSC_HAS_CLOCKACTIVITY | SYSC_HAS_SIDLEMODE | + SYSC_HAS_ENAWAKEUP | SYSC_HAS_SOFTRESET | + SYSC_HAS_AUTOIDLE | SYSS_HAS_RESET_STATUS), + .idlemodes = (SIDLE_FORCE | SIDLE_NO | SIDLE_SMART), + .sysc_fields = &omap_hwmod_sysc_type1, +}; + +static struct omap_hwmod_class omap34xx_mcspi_class = { + .name = "mcspi", + .sysc = &omap34xx_mcspi_sysc, + .rev = OMAP3_MCSPI_REV, +}; + +/* mcspi1 */ +static struct omap_hwmod_irq_info omap34xx_mcspi1_mpu_irqs[] = { + { .name = "irq", .irq = 65 }, +}; + +static struct omap_hwmod_dma_info omap34xx_mcspi1_sdma_reqs[] = { + { .name = "tx0", .dma_req = 35 }, + { .name = "rx0", .dma_req = 36 }, + { .name = "tx1", .dma_req = 37 }, + { .name = "rx1", .dma_req = 38 }, + { .name = "tx2", .dma_req = 39 }, + { .name = "rx2", .dma_req = 40 }, + { .name = "tx3", .dma_req = 41 }, + { .name = "rx3", .dma_req = 42 }, +}; + +static struct omap_hwmod_ocp_if *omap34xx_mcspi1_slaves[] = { + &omap34xx_l4_core__mcspi1, +}; + +static struct omap2_mcspi_dev_attr omap_mcspi1_dev_attr = { + .num_chipselect = 4, +}; + +static struct omap_hwmod omap34xx_mcspi1 = { + .name = "mcspi1", + .mpu_irqs = omap34xx_mcspi1_mpu_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap34xx_mcspi1_mpu_irqs), + .sdma_reqs = omap34xx_mcspi1_sdma_reqs, + .sdma_reqs_cnt = ARRAY_SIZE(omap34xx_mcspi1_sdma_reqs), + .main_clk = "mcspi1_fck", + .prcm = { + .omap2 = { + .module_offs = CORE_MOD, + .prcm_reg_id = 1, + .module_bit = OMAP3430_EN_MCSPI1_SHIFT, + .idlest_reg_id = 1, + .idlest_idle_bit = OMAP3430_ST_MCSPI1_SHIFT, + }, + }, + .slaves = omap34xx_mcspi1_slaves, + .slaves_cnt = ARRAY_SIZE(omap34xx_mcspi1_slaves), + .class = &omap34xx_mcspi_class, + .dev_attr = &omap_mcspi1_dev_attr, + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP3430), +}; + +/* mcspi2 */ +static struct omap_hwmod_irq_info omap34xx_mcspi2_mpu_irqs[] = { + { .name = "irq", .irq = 66 }, +}; + +static struct omap_hwmod_dma_info omap34xx_mcspi2_sdma_reqs[] = { + { .name = "tx0", .dma_req = 43 }, + { .name = "rx0", .dma_req = 44 }, + { .name = "tx1", .dma_req = 45 }, + { .name = "rx1", .dma_req = 46 }, +}; + +static struct omap_hwmod_ocp_if *omap34xx_mcspi2_slaves[] = { + &omap34xx_l4_core__mcspi2, +}; + +static struct omap2_mcspi_dev_attr omap_mcspi2_dev_attr = { + .num_chipselect = 2, +}; + +static struct omap_hwmod omap34xx_mcspi2 = { + .name = "mcspi2", + .mpu_irqs = omap34xx_mcspi2_mpu_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap34xx_mcspi2_mpu_irqs), + .sdma_reqs = omap34xx_mcspi2_sdma_reqs, + .sdma_reqs_cnt = ARRAY_SIZE(omap34xx_mcspi2_sdma_reqs), + .main_clk = "mcspi2_fck", + .prcm = { + .omap2 = { + .module_offs = CORE_MOD, + .prcm_reg_id = 1, + .module_bit = OMAP3430_EN_MCSPI2_SHIFT, + .idlest_reg_id = 1, + .idlest_idle_bit = OMAP3430_ST_MCSPI2_SHIFT, + }, + }, + .slaves = omap34xx_mcspi2_slaves, + .slaves_cnt = ARRAY_SIZE(omap34xx_mcspi2_slaves), + .class = &omap34xx_mcspi_class, + .dev_attr = &omap_mcspi2_dev_attr, + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP3430), +}; + +/* mcspi3 */ +static struct omap_hwmod_irq_info omap34xx_mcspi3_mpu_irqs[] = { + { .name = "irq", .irq = 91 }, /* 91 */ +}; + +static struct omap_hwmod_dma_info omap34xx_mcspi3_sdma_reqs[] = { + { .name = "tx0", .dma_req = 15 }, + { .name = "rx0", .dma_req = 16 }, + { .name = "tx1", .dma_req = 23 }, + { .name = "rx1", .dma_req = 24 }, +}; + +static struct omap_hwmod_ocp_if *omap34xx_mcspi3_slaves[] = { + &omap34xx_l4_core__mcspi3, +}; + +static struct omap2_mcspi_dev_attr omap_mcspi3_dev_attr = { + .num_chipselect = 2, +}; + +static struct omap_hwmod omap34xx_mcspi3 = { + .name = "mcspi3", + .mpu_irqs = omap34xx_mcspi3_mpu_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap34xx_mcspi3_mpu_irqs), + .sdma_reqs = omap34xx_mcspi3_sdma_reqs, + .sdma_reqs_cnt = ARRAY_SIZE(omap34xx_mcspi3_sdma_reqs), + .main_clk = "mcspi3_fck", + .prcm = { + .omap2 = { + .module_offs = CORE_MOD, + .prcm_reg_id = 1, + .module_bit = OMAP3430_EN_MCSPI3_SHIFT, + .idlest_reg_id = 1, + .idlest_idle_bit = OMAP3430_ST_MCSPI3_SHIFT, + }, + }, + .slaves = omap34xx_mcspi3_slaves, + .slaves_cnt = ARRAY_SIZE(omap34xx_mcspi3_slaves), + .class = &omap34xx_mcspi_class, + .dev_attr = &omap_mcspi3_dev_attr, + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP3430), +}; + +/* SPI4 */ +static struct omap_hwmod_irq_info omap34xx_mcspi4_mpu_irqs[] = { + { .name = "irq", .irq = INT_34XX_SPI4_IRQ }, /* 48 */ +}; + +static struct omap_hwmod_dma_info omap34xx_mcspi4_sdma_reqs[] = { + { .name = "tx0", .dma_req = 70 }, /* DMA_SPI4_TX0 */ + { .name = "rx0", .dma_req = 71 }, /* DMA_SPI4_RX0 */ +}; + +static struct omap_hwmod_ocp_if *omap34xx_mcspi4_slaves[] = { + &omap34xx_l4_core__mcspi4, +}; + +static struct omap2_mcspi_dev_attr omap_mcspi4_dev_attr = { + .num_chipselect = 1, +}; + +static struct omap_hwmod omap34xx_mcspi4 = { + .name = "mcspi4", + .mpu_irqs = omap34xx_mcspi4_mpu_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap34xx_mcspi4_mpu_irqs), + .sdma_reqs = omap34xx_mcspi4_sdma_reqs, + .sdma_reqs_cnt = ARRAY_SIZE(omap34xx_mcspi4_sdma_reqs), + .main_clk = "mcspi4_fck", + .prcm = { + .omap2 = { + .module_offs = CORE_MOD, + .prcm_reg_id = 1, + .module_bit = OMAP3430_EN_MCSPI4_SHIFT, + .idlest_reg_id = 1, + .idlest_idle_bit = OMAP3430_ST_MCSPI4_SHIFT, + }, + }, + .slaves = omap34xx_mcspi4_slaves, + .slaves_cnt = ARRAY_SIZE(omap34xx_mcspi4_slaves), + .class = &omap34xx_mcspi_class, + .dev_attr = &omap_mcspi4_dev_attr, + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP3430), +}; + +/* + * usbhsotg + */ +static struct omap_hwmod_class_sysconfig omap3xxx_usbhsotg_sysc = { + .rev_offs = 0x0400, + .sysc_offs = 0x0404, + .syss_offs = 0x0408, + .sysc_flags = (SYSC_HAS_SIDLEMODE | SYSC_HAS_MIDLEMODE| + SYSC_HAS_ENAWAKEUP | SYSC_HAS_SOFTRESET | + SYSC_HAS_AUTOIDLE), + .idlemodes = (SIDLE_FORCE | SIDLE_NO | SIDLE_SMART | + MSTANDBY_FORCE | MSTANDBY_NO | MSTANDBY_SMART), + .sysc_fields = &omap_hwmod_sysc_type1, +}; + +static struct omap_hwmod_class usbotg_class = { + .name = "usbotg", + .sysc = &omap3xxx_usbhsotg_sysc, +}; +/* usb_otg_hs */ +static struct omap_hwmod_irq_info omap3xxx_usbhsotg_mpu_irqs[] = { + + { .name = "mc", .irq = 92 }, + { .name = "dma", .irq = 93 }, +}; + +static struct omap_hwmod omap3xxx_usbhsotg_hwmod = { + .name = "usb_otg_hs", + .mpu_irqs = omap3xxx_usbhsotg_mpu_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap3xxx_usbhsotg_mpu_irqs), + .main_clk = "hsotgusb_ick", + .prcm = { + .omap2 = { + .prcm_reg_id = 1, + .module_bit = OMAP3430_EN_HSOTGUSB_SHIFT, + .module_offs = CORE_MOD, + .idlest_reg_id = 1, + .idlest_idle_bit = OMAP3430ES2_ST_HSOTGUSB_IDLE_SHIFT, + .idlest_stdby_bit = OMAP3430ES2_ST_HSOTGUSB_STDBY_SHIFT + }, + }, + .masters = omap3xxx_usbhsotg_masters, + .masters_cnt = ARRAY_SIZE(omap3xxx_usbhsotg_masters), + .slaves = omap3xxx_usbhsotg_slaves, + .slaves_cnt = ARRAY_SIZE(omap3xxx_usbhsotg_slaves), + .class = &usbotg_class, + + /* + * Erratum ID: i479 idle_req / idle_ack mechanism potentially + * broken when autoidle is enabled + * workaround is to disable the autoidle bit at module level. + */ + .flags = HWMOD_NO_OCP_AUTOIDLE | HWMOD_SWSUP_SIDLE + | HWMOD_SWSUP_MSTANDBY, + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP3430) +}; + +/* usb_otg_hs */ +static struct omap_hwmod_irq_info am35xx_usbhsotg_mpu_irqs[] = { + + { .name = "mc", .irq = 71 }, +}; + +static struct omap_hwmod_class am35xx_usbotg_class = { + .name = "am35xx_usbotg", + .sysc = NULL, +}; + +static struct omap_hwmod am35xx_usbhsotg_hwmod = { + .name = "am35x_otg_hs", + .mpu_irqs = am35xx_usbhsotg_mpu_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(am35xx_usbhsotg_mpu_irqs), + .main_clk = NULL, + .prcm = { + .omap2 = { + }, + }, + .masters = am35xx_usbhsotg_masters, + .masters_cnt = ARRAY_SIZE(am35xx_usbhsotg_masters), + .slaves = am35xx_usbhsotg_slaves, + .slaves_cnt = ARRAY_SIZE(am35xx_usbhsotg_slaves), + .class = &am35xx_usbotg_class, + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP3430ES3_1) +}; + +/* MMC/SD/SDIO common */ + +static struct omap_hwmod_class_sysconfig omap34xx_mmc_sysc = { + .rev_offs = 0x1fc, + .sysc_offs = 0x10, + .syss_offs = 0x14, + .sysc_flags = (SYSC_HAS_CLOCKACTIVITY | SYSC_HAS_SIDLEMODE | + SYSC_HAS_ENAWAKEUP | SYSC_HAS_SOFTRESET | + SYSC_HAS_AUTOIDLE | SYSS_HAS_RESET_STATUS), + .idlemodes = (SIDLE_FORCE | SIDLE_NO | SIDLE_SMART), + .sysc_fields = &omap_hwmod_sysc_type1, +}; + +static struct omap_hwmod_class omap34xx_mmc_class = { + .name = "mmc", + .sysc = &omap34xx_mmc_sysc, +}; + +/* MMC/SD/SDIO1 */ + +static struct omap_hwmod_irq_info omap34xx_mmc1_mpu_irqs[] = { + { .irq = 83, }, +}; + +static struct omap_hwmod_dma_info omap34xx_mmc1_sdma_reqs[] = { + { .name = "tx", .dma_req = 61, }, + { .name = "rx", .dma_req = 62, }, +}; + +static struct omap_hwmod_opt_clk omap34xx_mmc1_opt_clks[] = { + { .role = "dbck", .clk = "omap_32k_fck", }, +}; + +static struct omap_hwmod_ocp_if *omap3xxx_mmc1_slaves[] = { + &omap3xxx_l4_core__mmc1, +}; + +static struct omap_mmc_dev_attr mmc1_dev_attr = { + .flags = OMAP_HSMMC_SUPPORTS_DUAL_VOLT, +}; + +static struct omap_hwmod omap3xxx_mmc1_hwmod = { + .name = "mmc1", + .mpu_irqs = omap34xx_mmc1_mpu_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap34xx_mmc1_mpu_irqs), + .sdma_reqs = omap34xx_mmc1_sdma_reqs, + .sdma_reqs_cnt = ARRAY_SIZE(omap34xx_mmc1_sdma_reqs), + .opt_clks = omap34xx_mmc1_opt_clks, + .opt_clks_cnt = ARRAY_SIZE(omap34xx_mmc1_opt_clks), + .main_clk = "mmchs1_fck", + .prcm = { + .omap2 = { + .module_offs = CORE_MOD, + .prcm_reg_id = 1, + .module_bit = OMAP3430_EN_MMC1_SHIFT, + .idlest_reg_id = 1, + .idlest_idle_bit = OMAP3430_ST_MMC1_SHIFT, + }, + }, + .dev_attr = &mmc1_dev_attr, + .slaves = omap3xxx_mmc1_slaves, + .slaves_cnt = ARRAY_SIZE(omap3xxx_mmc1_slaves), + .class = &omap34xx_mmc_class, + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP3430), +}; + +/* MMC/SD/SDIO2 */ + +static struct omap_hwmod_irq_info omap34xx_mmc2_mpu_irqs[] = { + { .irq = INT_24XX_MMC2_IRQ, }, +}; + +static struct omap_hwmod_dma_info omap34xx_mmc2_sdma_reqs[] = { + { .name = "tx", .dma_req = 47, }, + { .name = "rx", .dma_req = 48, }, +}; + +static struct omap_hwmod_opt_clk omap34xx_mmc2_opt_clks[] = { + { .role = "dbck", .clk = "omap_32k_fck", }, +}; + +static struct omap_hwmod_ocp_if *omap3xxx_mmc2_slaves[] = { + &omap3xxx_l4_core__mmc2, +}; + +static struct omap_hwmod omap3xxx_mmc2_hwmod = { + .name = "mmc2", + .mpu_irqs = omap34xx_mmc2_mpu_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap34xx_mmc2_mpu_irqs), + .sdma_reqs = omap34xx_mmc2_sdma_reqs, + .sdma_reqs_cnt = ARRAY_SIZE(omap34xx_mmc2_sdma_reqs), + .opt_clks = omap34xx_mmc2_opt_clks, + .opt_clks_cnt = ARRAY_SIZE(omap34xx_mmc2_opt_clks), + .main_clk = "mmchs2_fck", + .prcm = { + .omap2 = { + .module_offs = CORE_MOD, + .prcm_reg_id = 1, + .module_bit = OMAP3430_EN_MMC2_SHIFT, + .idlest_reg_id = 1, + .idlest_idle_bit = OMAP3430_ST_MMC2_SHIFT, + }, + }, + .slaves = omap3xxx_mmc2_slaves, + .slaves_cnt = ARRAY_SIZE(omap3xxx_mmc2_slaves), + .class = &omap34xx_mmc_class, + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP3430), +}; + +/* MMC/SD/SDIO3 */ + +static struct omap_hwmod_irq_info omap34xx_mmc3_mpu_irqs[] = { + { .irq = 94, }, +}; + +static struct omap_hwmod_dma_info omap34xx_mmc3_sdma_reqs[] = { + { .name = "tx", .dma_req = 77, }, + { .name = "rx", .dma_req = 78, }, +}; + +static struct omap_hwmod_opt_clk omap34xx_mmc3_opt_clks[] = { + { .role = "dbck", .clk = "omap_32k_fck", }, +}; + +static struct omap_hwmod_ocp_if *omap3xxx_mmc3_slaves[] = { + &omap3xxx_l4_core__mmc3, +}; + +static struct omap_hwmod omap3xxx_mmc3_hwmod = { + .name = "mmc3", + .mpu_irqs = omap34xx_mmc3_mpu_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap34xx_mmc3_mpu_irqs), + .sdma_reqs = omap34xx_mmc3_sdma_reqs, + .sdma_reqs_cnt = ARRAY_SIZE(omap34xx_mmc3_sdma_reqs), + .opt_clks = omap34xx_mmc3_opt_clks, + .opt_clks_cnt = ARRAY_SIZE(omap34xx_mmc3_opt_clks), + .main_clk = "mmchs3_fck", + .prcm = { + .omap2 = { + .prcm_reg_id = 1, + .module_bit = OMAP3430_EN_MMC3_SHIFT, + .idlest_reg_id = 1, + .idlest_idle_bit = OMAP3430_ST_MMC3_SHIFT, + }, + }, + .slaves = omap3xxx_mmc3_slaves, + .slaves_cnt = ARRAY_SIZE(omap3xxx_mmc3_slaves), + .class = &omap34xx_mmc_class, + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP3430), +}; + static __initdata struct omap_hwmod *omap3xxx_hwmods[] = { &omap3xxx_l3_main_hwmod, &omap3xxx_l4_core_hwmod, &omap3xxx_l4_per_hwmod, &omap3xxx_l4_wkup_hwmod, + &omap3xxx_mmc1_hwmod, + &omap3xxx_mmc2_hwmod, + &omap3xxx_mmc3_hwmod, &omap3xxx_mpu_hwmod, &omap3xxx_iva_hwmod, + + &omap3xxx_timer1_hwmod, + &omap3xxx_timer2_hwmod, + &omap3xxx_timer3_hwmod, + &omap3xxx_timer4_hwmod, + &omap3xxx_timer5_hwmod, + &omap3xxx_timer6_hwmod, + &omap3xxx_timer7_hwmod, + &omap3xxx_timer8_hwmod, + &omap3xxx_timer9_hwmod, + &omap3xxx_timer10_hwmod, + &omap3xxx_timer11_hwmod, + &omap3xxx_timer12_hwmod, + &omap3xxx_wd_timer2_hwmod, &omap3xxx_uart1_hwmod, &omap3xxx_uart2_hwmod, &omap3xxx_uart3_hwmod, &omap3xxx_uart4_hwmod, + /* dss class */ + &omap3430es1_dss_core_hwmod, + &omap3xxx_dss_core_hwmod, + &omap3xxx_dss_dispc_hwmod, + &omap3xxx_dss_dsi1_hwmod, + &omap3xxx_dss_rfbi_hwmod, + &omap3xxx_dss_venc_hwmod, + + /* i2c class */ &omap3xxx_i2c1_hwmod, &omap3xxx_i2c2_hwmod, &omap3xxx_i2c3_hwmod, @@ -1387,10 +3622,35 @@ static __initdata struct omap_hwmod *omap3xxx_hwmods[] = { /* dma_system class*/ &omap3xxx_dma_system_hwmod, + + /* mcbsp class */ + &omap3xxx_mcbsp1_hwmod, + &omap3xxx_mcbsp2_hwmod, + &omap3xxx_mcbsp3_hwmod, + &omap3xxx_mcbsp4_hwmod, + &omap3xxx_mcbsp5_hwmod, + &omap3xxx_mcbsp2_sidetone_hwmod, + &omap3xxx_mcbsp3_sidetone_hwmod, + + /* mailbox class */ + &omap3xxx_mailbox_hwmod, + + /* mcspi class */ + &omap34xx_mcspi1, + &omap34xx_mcspi2, + &omap34xx_mcspi3, + &omap34xx_mcspi4, + + /* usbotg class */ + &omap3xxx_usbhsotg_hwmod, + + /* usbotg for am35x */ + &am35xx_usbhsotg_hwmod, + NULL, }; int __init omap3xxx_hwmod_init(void) { - return omap_hwmod_init(omap3xxx_hwmods); + return omap_hwmod_register(omap3xxx_hwmods); } diff --git a/arch/arm/mach-omap2/omap_hwmod_44xx_data.c b/arch/arm/mach-omap2/omap_hwmod_44xx_data.c index c2806bd11fb..3e88dd3f8ef 100644 --- a/arch/arm/mach-omap2/omap_hwmod_44xx_data.c +++ b/arch/arm/mach-omap2/omap_hwmod_44xx_data.c @@ -1,7 +1,7 @@ /* * Hardware modules present on the OMAP44xx chips * - * Copyright (C) 2009-2010 Texas Instruments, Inc. + * Copyright (C) 2009-2011 Texas Instruments, Inc. * Copyright (C) 2009-2010 Nokia Corporation * * Paul Walmsley @@ -24,6 +24,9 @@ #include <plat/cpu.h> #include <plat/gpio.h> #include <plat/dma.h> +#include <plat/mcspi.h> +#include <plat/mcbsp.h> +#include <plat/mmc.h> #include "omap_hwmod_common_data.h" @@ -40,10 +43,15 @@ #define OMAP44XX_DMA_REQ_START 1 /* Backward references (IPs with Bus Master capability) */ +static struct omap_hwmod omap44xx_aess_hwmod; static struct omap_hwmod omap44xx_dma_system_hwmod; static struct omap_hwmod omap44xx_dmm_hwmod; static struct omap_hwmod omap44xx_dsp_hwmod; +static struct omap_hwmod omap44xx_dss_hwmod; static struct omap_hwmod omap44xx_emif_fw_hwmod; +static struct omap_hwmod omap44xx_hsi_hwmod; +static struct omap_hwmod omap44xx_ipu_hwmod; +static struct omap_hwmod omap44xx_iss_hwmod; static struct omap_hwmod omap44xx_iva_hwmod; static struct omap_hwmod omap44xx_l3_instr_hwmod; static struct omap_hwmod omap44xx_l3_main_1_hwmod; @@ -53,8 +61,11 @@ static struct omap_hwmod omap44xx_l4_abe_hwmod; static struct omap_hwmod omap44xx_l4_cfg_hwmod; static struct omap_hwmod omap44xx_l4_per_hwmod; static struct omap_hwmod omap44xx_l4_wkup_hwmod; +static struct omap_hwmod omap44xx_mmc1_hwmod; +static struct omap_hwmod omap44xx_mmc2_hwmod; static struct omap_hwmod omap44xx_mpu_hwmod; static struct omap_hwmod omap44xx_mpu_private_hwmod; +static struct omap_hwmod omap44xx_usb_otg_hs_hwmod; /* * Interconnects omap_hwmod structures @@ -213,6 +224,14 @@ static struct omap_hwmod_ocp_if omap44xx_dsp__l3_main_1 = { .user = OCP_USER_MPU | OCP_USER_SDMA, }; +/* dss -> l3_main_1 */ +static struct omap_hwmod_ocp_if omap44xx_dss__l3_main_1 = { + .master = &omap44xx_dss_hwmod, + .slave = &omap44xx_l3_main_1_hwmod, + .clk = "l3_div_ck", + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + /* l3_main_2 -> l3_main_1 */ static struct omap_hwmod_ocp_if omap44xx_l3_main_2__l3_main_1 = { .master = &omap44xx_l3_main_2_hwmod, @@ -229,25 +248,62 @@ static struct omap_hwmod_ocp_if omap44xx_l4_cfg__l3_main_1 = { .user = OCP_USER_MPU | OCP_USER_SDMA, }; +/* mmc1 -> l3_main_1 */ +static struct omap_hwmod_ocp_if omap44xx_mmc1__l3_main_1 = { + .master = &omap44xx_mmc1_hwmod, + .slave = &omap44xx_l3_main_1_hwmod, + .clk = "l3_div_ck", + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* mmc2 -> l3_main_1 */ +static struct omap_hwmod_ocp_if omap44xx_mmc2__l3_main_1 = { + .master = &omap44xx_mmc2_hwmod, + .slave = &omap44xx_l3_main_1_hwmod, + .clk = "l3_div_ck", + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* L3 target configuration and error log registers */ +static struct omap_hwmod_irq_info omap44xx_l3_targ_irqs[] = { + { .irq = 9 + OMAP44XX_IRQ_GIC_START }, + { .irq = 10 + OMAP44XX_IRQ_GIC_START }, +}; + +static struct omap_hwmod_addr_space omap44xx_l3_main_1_addrs[] = { + { + .pa_start = 0x44000000, + .pa_end = 0x44000fff, + .flags = ADDR_TYPE_RT, + }, +}; + /* mpu -> l3_main_1 */ static struct omap_hwmod_ocp_if omap44xx_mpu__l3_main_1 = { .master = &omap44xx_mpu_hwmod, .slave = &omap44xx_l3_main_1_hwmod, .clk = "l3_div_ck", + .addr = omap44xx_l3_main_1_addrs, + .addr_cnt = ARRAY_SIZE(omap44xx_l3_main_1_addrs), .user = OCP_USER_MPU | OCP_USER_SDMA, }; /* l3_main_1 slave ports */ static struct omap_hwmod_ocp_if *omap44xx_l3_main_1_slaves[] = { &omap44xx_dsp__l3_main_1, + &omap44xx_dss__l3_main_1, &omap44xx_l3_main_2__l3_main_1, &omap44xx_l4_cfg__l3_main_1, + &omap44xx_mmc1__l3_main_1, + &omap44xx_mmc2__l3_main_1, &omap44xx_mpu__l3_main_1, }; static struct omap_hwmod omap44xx_l3_main_1_hwmod = { .name = "l3_main_1", .class = &omap44xx_l3_hwmod_class, + .mpu_irqs = omap44xx_l3_targ_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap44xx_l3_targ_irqs), .slaves = omap44xx_l3_main_1_slaves, .slaves_cnt = ARRAY_SIZE(omap44xx_l3_main_1_slaves), .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430), @@ -262,6 +318,30 @@ static struct omap_hwmod_ocp_if omap44xx_dma_system__l3_main_2 = { .user = OCP_USER_MPU | OCP_USER_SDMA, }; +/* hsi -> l3_main_2 */ +static struct omap_hwmod_ocp_if omap44xx_hsi__l3_main_2 = { + .master = &omap44xx_hsi_hwmod, + .slave = &omap44xx_l3_main_2_hwmod, + .clk = "l3_div_ck", + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* ipu -> l3_main_2 */ +static struct omap_hwmod_ocp_if omap44xx_ipu__l3_main_2 = { + .master = &omap44xx_ipu_hwmod, + .slave = &omap44xx_l3_main_2_hwmod, + .clk = "l3_div_ck", + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* iss -> l3_main_2 */ +static struct omap_hwmod_ocp_if omap44xx_iss__l3_main_2 = { + .master = &omap44xx_iss_hwmod, + .slave = &omap44xx_l3_main_2_hwmod, + .clk = "l3_div_ck", + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + /* iva -> l3_main_2 */ static struct omap_hwmod_ocp_if omap44xx_iva__l3_main_2 = { .master = &omap44xx_iva_hwmod, @@ -270,11 +350,21 @@ static struct omap_hwmod_ocp_if omap44xx_iva__l3_main_2 = { .user = OCP_USER_MPU | OCP_USER_SDMA, }; +static struct omap_hwmod_addr_space omap44xx_l3_main_2_addrs[] = { + { + .pa_start = 0x44800000, + .pa_end = 0x44801fff, + .flags = ADDR_TYPE_RT, + }, +}; + /* l3_main_1 -> l3_main_2 */ static struct omap_hwmod_ocp_if omap44xx_l3_main_1__l3_main_2 = { .master = &omap44xx_l3_main_1_hwmod, .slave = &omap44xx_l3_main_2_hwmod, .clk = "l3_div_ck", + .addr = omap44xx_l3_main_2_addrs, + .addr_cnt = ARRAY_SIZE(omap44xx_l3_main_2_addrs), .user = OCP_USER_MPU | OCP_USER_SDMA, }; @@ -286,12 +376,24 @@ static struct omap_hwmod_ocp_if omap44xx_l4_cfg__l3_main_2 = { .user = OCP_USER_MPU | OCP_USER_SDMA, }; +/* usb_otg_hs -> l3_main_2 */ +static struct omap_hwmod_ocp_if omap44xx_usb_otg_hs__l3_main_2 = { + .master = &omap44xx_usb_otg_hs_hwmod, + .slave = &omap44xx_l3_main_2_hwmod, + .clk = "l3_div_ck", + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + /* l3_main_2 slave ports */ static struct omap_hwmod_ocp_if *omap44xx_l3_main_2_slaves[] = { &omap44xx_dma_system__l3_main_2, + &omap44xx_hsi__l3_main_2, + &omap44xx_ipu__l3_main_2, + &omap44xx_iss__l3_main_2, &omap44xx_iva__l3_main_2, &omap44xx_l3_main_1__l3_main_2, &omap44xx_l4_cfg__l3_main_2, + &omap44xx_usb_otg_hs__l3_main_2, }; static struct omap_hwmod omap44xx_l3_main_2_hwmod = { @@ -303,11 +405,21 @@ static struct omap_hwmod omap44xx_l3_main_2_hwmod = { }; /* l3_main_3 interface data */ +static struct omap_hwmod_addr_space omap44xx_l3_main_3_addrs[] = { + { + .pa_start = 0x45000000, + .pa_end = 0x45000fff, + .flags = ADDR_TYPE_RT, + }, +}; + /* l3_main_1 -> l3_main_3 */ static struct omap_hwmod_ocp_if omap44xx_l3_main_1__l3_main_3 = { .master = &omap44xx_l3_main_1_hwmod, .slave = &omap44xx_l3_main_3_hwmod, .clk = "l3_div_ck", + .addr = omap44xx_l3_main_3_addrs, + .addr_cnt = ARRAY_SIZE(omap44xx_l3_main_3_addrs), .user = OCP_USER_MPU | OCP_USER_SDMA, }; @@ -351,6 +463,14 @@ static struct omap_hwmod_class omap44xx_l4_hwmod_class = { }; /* l4_abe interface data */ +/* aess -> l4_abe */ +static struct omap_hwmod_ocp_if omap44xx_aess__l4_abe = { + .master = &omap44xx_aess_hwmod, + .slave = &omap44xx_l4_abe_hwmod, + .clk = "ocp_abe_iclk", + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + /* dsp -> l4_abe */ static struct omap_hwmod_ocp_if omap44xx_dsp__l4_abe = { .master = &omap44xx_dsp_hwmod, @@ -377,6 +497,7 @@ static struct omap_hwmod_ocp_if omap44xx_mpu__l4_abe = { /* l4_abe slave ports */ static struct omap_hwmod_ocp_if *omap44xx_l4_abe_slaves[] = { + &omap44xx_aess__l4_abe, &omap44xx_dsp__l4_abe, &omap44xx_l3_main_1__l4_abe, &omap44xx_mpu__l4_abe, @@ -494,26 +615,15 @@ static struct omap_hwmod omap44xx_mpu_private_hwmod = { * - They still need to be validated with the driver * properly adapted to omap_hwmod / omap_device * - * aess - * bandgap * c2c * c2c_target_fw * cm_core * cm_core_aon - * counter_32k * ctrl_module_core * ctrl_module_pad_core * ctrl_module_pad_wkup * ctrl_module_wkup * debugss - * dmic - * dss - * dss_dispc - * dss_dsi1 - * dss_dsi2 - * dss_hdmi - * dss_rfbi - * dss_venc * efuse_ctrl_cust * efuse_ctrl_std * elm @@ -524,58 +634,211 @@ static struct omap_hwmod omap44xx_mpu_private_hwmod = { * gpu * hdq1w * hsi - * ipu - * iss - * kbd - * mailbox - * mcasp - * mcbsp1 - * mcbsp2 - * mcbsp3 - * mcbsp4 - * mcpdm - * mcspi1 - * mcspi2 - * mcspi3 - * mcspi4 - * mmc1 - * mmc2 - * mmc3 - * mmc4 - * mmc5 - * mpu_c0 - * mpu_c1 * ocmc_ram * ocp2scp_usb_phy * ocp_wp_noc - * prcm * prcm_mpu * prm * scrm * sl2if * slimbus1 * slimbus2 - * spinlock - * timer1 - * timer10 - * timer11 - * timer2 - * timer3 - * timer4 - * timer5 - * timer6 - * timer7 - * timer8 - * timer9 * usb_host_fs * usb_host_hs - * usb_otg_hs * usb_phy_cm * usb_tll_hs * usim */ /* + * 'aess' class + * audio engine sub system + */ + +static struct omap_hwmod_class_sysconfig omap44xx_aess_sysc = { + .rev_offs = 0x0000, + .sysc_offs = 0x0010, + .sysc_flags = (SYSC_HAS_MIDLEMODE | SYSC_HAS_SIDLEMODE), + .idlemodes = (SIDLE_FORCE | SIDLE_NO | SIDLE_SMART | + MSTANDBY_FORCE | MSTANDBY_NO | MSTANDBY_SMART), + .sysc_fields = &omap_hwmod_sysc_type2, +}; + +static struct omap_hwmod_class omap44xx_aess_hwmod_class = { + .name = "aess", + .sysc = &omap44xx_aess_sysc, +}; + +/* aess */ +static struct omap_hwmod_irq_info omap44xx_aess_irqs[] = { + { .irq = 99 + OMAP44XX_IRQ_GIC_START }, +}; + +static struct omap_hwmod_dma_info omap44xx_aess_sdma_reqs[] = { + { .name = "fifo0", .dma_req = 100 + OMAP44XX_DMA_REQ_START }, + { .name = "fifo1", .dma_req = 101 + OMAP44XX_DMA_REQ_START }, + { .name = "fifo2", .dma_req = 102 + OMAP44XX_DMA_REQ_START }, + { .name = "fifo3", .dma_req = 103 + OMAP44XX_DMA_REQ_START }, + { .name = "fifo4", .dma_req = 104 + OMAP44XX_DMA_REQ_START }, + { .name = "fifo5", .dma_req = 105 + OMAP44XX_DMA_REQ_START }, + { .name = "fifo6", .dma_req = 106 + OMAP44XX_DMA_REQ_START }, + { .name = "fifo7", .dma_req = 107 + OMAP44XX_DMA_REQ_START }, +}; + +/* aess master ports */ +static struct omap_hwmod_ocp_if *omap44xx_aess_masters[] = { + &omap44xx_aess__l4_abe, +}; + +static struct omap_hwmod_addr_space omap44xx_aess_addrs[] = { + { + .pa_start = 0x401f1000, + .pa_end = 0x401f13ff, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_abe -> aess */ +static struct omap_hwmod_ocp_if omap44xx_l4_abe__aess = { + .master = &omap44xx_l4_abe_hwmod, + .slave = &omap44xx_aess_hwmod, + .clk = "ocp_abe_iclk", + .addr = omap44xx_aess_addrs, + .addr_cnt = ARRAY_SIZE(omap44xx_aess_addrs), + .user = OCP_USER_MPU, +}; + +static struct omap_hwmod_addr_space omap44xx_aess_dma_addrs[] = { + { + .pa_start = 0x490f1000, + .pa_end = 0x490f13ff, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_abe -> aess (dma) */ +static struct omap_hwmod_ocp_if omap44xx_l4_abe__aess_dma = { + .master = &omap44xx_l4_abe_hwmod, + .slave = &omap44xx_aess_hwmod, + .clk = "ocp_abe_iclk", + .addr = omap44xx_aess_dma_addrs, + .addr_cnt = ARRAY_SIZE(omap44xx_aess_dma_addrs), + .user = OCP_USER_SDMA, +}; + +/* aess slave ports */ +static struct omap_hwmod_ocp_if *omap44xx_aess_slaves[] = { + &omap44xx_l4_abe__aess, + &omap44xx_l4_abe__aess_dma, +}; + +static struct omap_hwmod omap44xx_aess_hwmod = { + .name = "aess", + .class = &omap44xx_aess_hwmod_class, + .mpu_irqs = omap44xx_aess_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap44xx_aess_irqs), + .sdma_reqs = omap44xx_aess_sdma_reqs, + .sdma_reqs_cnt = ARRAY_SIZE(omap44xx_aess_sdma_reqs), + .main_clk = "aess_fck", + .prcm = { + .omap4 = { + .clkctrl_reg = OMAP4430_CM1_ABE_AESS_CLKCTRL, + }, + }, + .slaves = omap44xx_aess_slaves, + .slaves_cnt = ARRAY_SIZE(omap44xx_aess_slaves), + .masters = omap44xx_aess_masters, + .masters_cnt = ARRAY_SIZE(omap44xx_aess_masters), + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430), +}; + +/* + * 'bandgap' class + * bangap reference for ldo regulators + */ + +static struct omap_hwmod_class omap44xx_bandgap_hwmod_class = { + .name = "bandgap", +}; + +/* bandgap */ +static struct omap_hwmod_opt_clk bandgap_opt_clks[] = { + { .role = "fclk", .clk = "bandgap_fclk" }, +}; + +static struct omap_hwmod omap44xx_bandgap_hwmod = { + .name = "bandgap", + .class = &omap44xx_bandgap_hwmod_class, + .prcm = { + .omap4 = { + .clkctrl_reg = OMAP4430_CM_WKUP_BANDGAP_CLKCTRL, + }, + }, + .opt_clks = bandgap_opt_clks, + .opt_clks_cnt = ARRAY_SIZE(bandgap_opt_clks), + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430), +}; + +/* + * 'counter' class + * 32-bit ordinary counter, clocked by the falling edge of the 32 khz clock + */ + +static struct omap_hwmod_class_sysconfig omap44xx_counter_sysc = { + .rev_offs = 0x0000, + .sysc_offs = 0x0004, + .sysc_flags = SYSC_HAS_SIDLEMODE, + .idlemodes = (SIDLE_FORCE | SIDLE_NO | SIDLE_SMART | + SIDLE_SMART_WKUP), + .sysc_fields = &omap_hwmod_sysc_type1, +}; + +static struct omap_hwmod_class omap44xx_counter_hwmod_class = { + .name = "counter", + .sysc = &omap44xx_counter_sysc, +}; + +/* counter_32k */ +static struct omap_hwmod omap44xx_counter_32k_hwmod; +static struct omap_hwmod_addr_space omap44xx_counter_32k_addrs[] = { + { + .pa_start = 0x4a304000, + .pa_end = 0x4a30401f, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_wkup -> counter_32k */ +static struct omap_hwmod_ocp_if omap44xx_l4_wkup__counter_32k = { + .master = &omap44xx_l4_wkup_hwmod, + .slave = &omap44xx_counter_32k_hwmod, + .clk = "l4_wkup_clk_mux_ck", + .addr = omap44xx_counter_32k_addrs, + .addr_cnt = ARRAY_SIZE(omap44xx_counter_32k_addrs), + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* counter_32k slave ports */ +static struct omap_hwmod_ocp_if *omap44xx_counter_32k_slaves[] = { + &omap44xx_l4_wkup__counter_32k, +}; + +static struct omap_hwmod omap44xx_counter_32k_hwmod = { + .name = "counter_32k", + .class = &omap44xx_counter_hwmod_class, + .flags = HWMOD_SWSUP_SIDLE, + .main_clk = "sys_32k_ck", + .prcm = { + .omap4 = { + .clkctrl_reg = OMAP4430_CM_WKUP_SYNCTIMER_CLKCTRL, + }, + }, + .slaves = omap44xx_counter_32k_slaves, + .slaves_cnt = ARRAY_SIZE(omap44xx_counter_32k_slaves), + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430), +}; + +/* * 'dma' class * dma controller for data exchange between memory to memory (i.e. internal or * external memory) and gp peripherals to memory or memory to gp peripherals @@ -662,6 +925,96 @@ static struct omap_hwmod omap44xx_dma_system_hwmod = { }; /* + * 'dmic' class + * digital microphone controller + */ + +static struct omap_hwmod_class_sysconfig omap44xx_dmic_sysc = { + .rev_offs = 0x0000, + .sysc_offs = 0x0010, + .sysc_flags = (SYSC_HAS_EMUFREE | SYSC_HAS_RESET_STATUS | + SYSC_HAS_SIDLEMODE | SYSC_HAS_SOFTRESET), + .idlemodes = (SIDLE_FORCE | SIDLE_NO | SIDLE_SMART | + SIDLE_SMART_WKUP), + .sysc_fields = &omap_hwmod_sysc_type2, +}; + +static struct omap_hwmod_class omap44xx_dmic_hwmod_class = { + .name = "dmic", + .sysc = &omap44xx_dmic_sysc, +}; + +/* dmic */ +static struct omap_hwmod omap44xx_dmic_hwmod; +static struct omap_hwmod_irq_info omap44xx_dmic_irqs[] = { + { .irq = 114 + OMAP44XX_IRQ_GIC_START }, +}; + +static struct omap_hwmod_dma_info omap44xx_dmic_sdma_reqs[] = { + { .dma_req = 66 + OMAP44XX_DMA_REQ_START }, +}; + +static struct omap_hwmod_addr_space omap44xx_dmic_addrs[] = { + { + .pa_start = 0x4012e000, + .pa_end = 0x4012e07f, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_abe -> dmic */ +static struct omap_hwmod_ocp_if omap44xx_l4_abe__dmic = { + .master = &omap44xx_l4_abe_hwmod, + .slave = &omap44xx_dmic_hwmod, + .clk = "ocp_abe_iclk", + .addr = omap44xx_dmic_addrs, + .addr_cnt = ARRAY_SIZE(omap44xx_dmic_addrs), + .user = OCP_USER_MPU, +}; + +static struct omap_hwmod_addr_space omap44xx_dmic_dma_addrs[] = { + { + .pa_start = 0x4902e000, + .pa_end = 0x4902e07f, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_abe -> dmic (dma) */ +static struct omap_hwmod_ocp_if omap44xx_l4_abe__dmic_dma = { + .master = &omap44xx_l4_abe_hwmod, + .slave = &omap44xx_dmic_hwmod, + .clk = "ocp_abe_iclk", + .addr = omap44xx_dmic_dma_addrs, + .addr_cnt = ARRAY_SIZE(omap44xx_dmic_dma_addrs), + .user = OCP_USER_SDMA, +}; + +/* dmic slave ports */ +static struct omap_hwmod_ocp_if *omap44xx_dmic_slaves[] = { + &omap44xx_l4_abe__dmic, + &omap44xx_l4_abe__dmic_dma, +}; + +static struct omap_hwmod omap44xx_dmic_hwmod = { + .name = "dmic", + .class = &omap44xx_dmic_hwmod_class, + .mpu_irqs = omap44xx_dmic_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap44xx_dmic_irqs), + .sdma_reqs = omap44xx_dmic_sdma_reqs, + .sdma_reqs_cnt = ARRAY_SIZE(omap44xx_dmic_sdma_reqs), + .main_clk = "dmic_fck", + .prcm = { + .omap4 = { + .clkctrl_reg = OMAP4430_CM1_ABE_DMIC_CLKCTRL, + }, + }, + .slaves = omap44xx_dmic_slaves, + .slaves_cnt = ARRAY_SIZE(omap44xx_dmic_slaves), + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430), +}; + +/* * 'dsp' class * dsp sub-system */ @@ -747,6 +1100,590 @@ static struct omap_hwmod omap44xx_dsp_hwmod = { }; /* + * 'dss' class + * display sub-system + */ + +static struct omap_hwmod_class_sysconfig omap44xx_dss_sysc = { + .rev_offs = 0x0000, + .syss_offs = 0x0014, + .sysc_flags = SYSS_HAS_RESET_STATUS, +}; + +static struct omap_hwmod_class omap44xx_dss_hwmod_class = { + .name = "dss", + .sysc = &omap44xx_dss_sysc, +}; + +/* dss */ +/* dss master ports */ +static struct omap_hwmod_ocp_if *omap44xx_dss_masters[] = { + &omap44xx_dss__l3_main_1, +}; + +static struct omap_hwmod_addr_space omap44xx_dss_dma_addrs[] = { + { + .pa_start = 0x58000000, + .pa_end = 0x5800007f, + .flags = ADDR_TYPE_RT + }, +}; + +/* l3_main_2 -> dss */ +static struct omap_hwmod_ocp_if omap44xx_l3_main_2__dss = { + .master = &omap44xx_l3_main_2_hwmod, + .slave = &omap44xx_dss_hwmod, + .clk = "l3_div_ck", + .addr = omap44xx_dss_dma_addrs, + .addr_cnt = ARRAY_SIZE(omap44xx_dss_dma_addrs), + .user = OCP_USER_SDMA, +}; + +static struct omap_hwmod_addr_space omap44xx_dss_addrs[] = { + { + .pa_start = 0x48040000, + .pa_end = 0x4804007f, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_per -> dss */ +static struct omap_hwmod_ocp_if omap44xx_l4_per__dss = { + .master = &omap44xx_l4_per_hwmod, + .slave = &omap44xx_dss_hwmod, + .clk = "l4_div_ck", + .addr = omap44xx_dss_addrs, + .addr_cnt = ARRAY_SIZE(omap44xx_dss_addrs), + .user = OCP_USER_MPU, +}; + +/* dss slave ports */ +static struct omap_hwmod_ocp_if *omap44xx_dss_slaves[] = { + &omap44xx_l3_main_2__dss, + &omap44xx_l4_per__dss, +}; + +static struct omap_hwmod_opt_clk dss_opt_clks[] = { + { .role = "sys_clk", .clk = "dss_sys_clk" }, + { .role = "tv_clk", .clk = "dss_tv_clk" }, + { .role = "dss_clk", .clk = "dss_dss_clk" }, + { .role = "video_clk", .clk = "dss_48mhz_clk" }, +}; + +static struct omap_hwmod omap44xx_dss_hwmod = { + .name = "dss_core", + .class = &omap44xx_dss_hwmod_class, + .main_clk = "dss_fck", + .prcm = { + .omap4 = { + .clkctrl_reg = OMAP4430_CM_DSS_DSS_CLKCTRL, + }, + }, + .opt_clks = dss_opt_clks, + .opt_clks_cnt = ARRAY_SIZE(dss_opt_clks), + .slaves = omap44xx_dss_slaves, + .slaves_cnt = ARRAY_SIZE(omap44xx_dss_slaves), + .masters = omap44xx_dss_masters, + .masters_cnt = ARRAY_SIZE(omap44xx_dss_masters), + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430), +}; + +/* + * 'dispc' class + * display controller + */ + +static struct omap_hwmod_class_sysconfig omap44xx_dispc_sysc = { + .rev_offs = 0x0000, + .sysc_offs = 0x0010, + .syss_offs = 0x0014, + .sysc_flags = (SYSC_HAS_AUTOIDLE | SYSC_HAS_CLOCKACTIVITY | + SYSC_HAS_ENAWAKEUP | SYSC_HAS_MIDLEMODE | + SYSC_HAS_SIDLEMODE | SYSC_HAS_SOFTRESET | + SYSS_HAS_RESET_STATUS), + .idlemodes = (SIDLE_FORCE | SIDLE_NO | SIDLE_SMART | + MSTANDBY_FORCE | MSTANDBY_NO | MSTANDBY_SMART), + .sysc_fields = &omap_hwmod_sysc_type1, +}; + +static struct omap_hwmod_class omap44xx_dispc_hwmod_class = { + .name = "dispc", + .sysc = &omap44xx_dispc_sysc, +}; + +/* dss_dispc */ +static struct omap_hwmod omap44xx_dss_dispc_hwmod; +static struct omap_hwmod_irq_info omap44xx_dss_dispc_irqs[] = { + { .irq = 25 + OMAP44XX_IRQ_GIC_START }, +}; + +static struct omap_hwmod_dma_info omap44xx_dss_dispc_sdma_reqs[] = { + { .dma_req = 5 + OMAP44XX_DMA_REQ_START }, +}; + +static struct omap_hwmod_addr_space omap44xx_dss_dispc_dma_addrs[] = { + { + .pa_start = 0x58001000, + .pa_end = 0x58001fff, + .flags = ADDR_TYPE_RT + }, +}; + +/* l3_main_2 -> dss_dispc */ +static struct omap_hwmod_ocp_if omap44xx_l3_main_2__dss_dispc = { + .master = &omap44xx_l3_main_2_hwmod, + .slave = &omap44xx_dss_dispc_hwmod, + .clk = "l3_div_ck", + .addr = omap44xx_dss_dispc_dma_addrs, + .addr_cnt = ARRAY_SIZE(omap44xx_dss_dispc_dma_addrs), + .user = OCP_USER_SDMA, +}; + +static struct omap_hwmod_addr_space omap44xx_dss_dispc_addrs[] = { + { + .pa_start = 0x48041000, + .pa_end = 0x48041fff, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_per -> dss_dispc */ +static struct omap_hwmod_ocp_if omap44xx_l4_per__dss_dispc = { + .master = &omap44xx_l4_per_hwmod, + .slave = &omap44xx_dss_dispc_hwmod, + .clk = "l4_div_ck", + .addr = omap44xx_dss_dispc_addrs, + .addr_cnt = ARRAY_SIZE(omap44xx_dss_dispc_addrs), + .user = OCP_USER_MPU, +}; + +/* dss_dispc slave ports */ +static struct omap_hwmod_ocp_if *omap44xx_dss_dispc_slaves[] = { + &omap44xx_l3_main_2__dss_dispc, + &omap44xx_l4_per__dss_dispc, +}; + +static struct omap_hwmod omap44xx_dss_dispc_hwmod = { + .name = "dss_dispc", + .class = &omap44xx_dispc_hwmod_class, + .mpu_irqs = omap44xx_dss_dispc_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap44xx_dss_dispc_irqs), + .sdma_reqs = omap44xx_dss_dispc_sdma_reqs, + .sdma_reqs_cnt = ARRAY_SIZE(omap44xx_dss_dispc_sdma_reqs), + .main_clk = "dss_fck", + .prcm = { + .omap4 = { + .clkctrl_reg = OMAP4430_CM_DSS_DSS_CLKCTRL, + }, + }, + .slaves = omap44xx_dss_dispc_slaves, + .slaves_cnt = ARRAY_SIZE(omap44xx_dss_dispc_slaves), + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430), +}; + +/* + * 'dsi' class + * display serial interface controller + */ + +static struct omap_hwmod_class_sysconfig omap44xx_dsi_sysc = { + .rev_offs = 0x0000, + .sysc_offs = 0x0010, + .syss_offs = 0x0014, + .sysc_flags = (SYSC_HAS_AUTOIDLE | SYSC_HAS_CLOCKACTIVITY | + SYSC_HAS_ENAWAKEUP | SYSC_HAS_SIDLEMODE | + SYSC_HAS_SOFTRESET | SYSS_HAS_RESET_STATUS), + .idlemodes = (SIDLE_FORCE | SIDLE_NO | SIDLE_SMART), + .sysc_fields = &omap_hwmod_sysc_type1, +}; + +static struct omap_hwmod_class omap44xx_dsi_hwmod_class = { + .name = "dsi", + .sysc = &omap44xx_dsi_sysc, +}; + +/* dss_dsi1 */ +static struct omap_hwmod omap44xx_dss_dsi1_hwmod; +static struct omap_hwmod_irq_info omap44xx_dss_dsi1_irqs[] = { + { .irq = 53 + OMAP44XX_IRQ_GIC_START }, +}; + +static struct omap_hwmod_dma_info omap44xx_dss_dsi1_sdma_reqs[] = { + { .dma_req = 74 + OMAP44XX_DMA_REQ_START }, +}; + +static struct omap_hwmod_addr_space omap44xx_dss_dsi1_dma_addrs[] = { + { + .pa_start = 0x58004000, + .pa_end = 0x580041ff, + .flags = ADDR_TYPE_RT + }, +}; + +/* l3_main_2 -> dss_dsi1 */ +static struct omap_hwmod_ocp_if omap44xx_l3_main_2__dss_dsi1 = { + .master = &omap44xx_l3_main_2_hwmod, + .slave = &omap44xx_dss_dsi1_hwmod, + .clk = "l3_div_ck", + .addr = omap44xx_dss_dsi1_dma_addrs, + .addr_cnt = ARRAY_SIZE(omap44xx_dss_dsi1_dma_addrs), + .user = OCP_USER_SDMA, +}; + +static struct omap_hwmod_addr_space omap44xx_dss_dsi1_addrs[] = { + { + .pa_start = 0x48044000, + .pa_end = 0x480441ff, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_per -> dss_dsi1 */ +static struct omap_hwmod_ocp_if omap44xx_l4_per__dss_dsi1 = { + .master = &omap44xx_l4_per_hwmod, + .slave = &omap44xx_dss_dsi1_hwmod, + .clk = "l4_div_ck", + .addr = omap44xx_dss_dsi1_addrs, + .addr_cnt = ARRAY_SIZE(omap44xx_dss_dsi1_addrs), + .user = OCP_USER_MPU, +}; + +/* dss_dsi1 slave ports */ +static struct omap_hwmod_ocp_if *omap44xx_dss_dsi1_slaves[] = { + &omap44xx_l3_main_2__dss_dsi1, + &omap44xx_l4_per__dss_dsi1, +}; + +static struct omap_hwmod omap44xx_dss_dsi1_hwmod = { + .name = "dss_dsi1", + .class = &omap44xx_dsi_hwmod_class, + .mpu_irqs = omap44xx_dss_dsi1_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap44xx_dss_dsi1_irqs), + .sdma_reqs = omap44xx_dss_dsi1_sdma_reqs, + .sdma_reqs_cnt = ARRAY_SIZE(omap44xx_dss_dsi1_sdma_reqs), + .main_clk = "dss_fck", + .prcm = { + .omap4 = { + .clkctrl_reg = OMAP4430_CM_DSS_DSS_CLKCTRL, + }, + }, + .slaves = omap44xx_dss_dsi1_slaves, + .slaves_cnt = ARRAY_SIZE(omap44xx_dss_dsi1_slaves), + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430), +}; + +/* dss_dsi2 */ +static struct omap_hwmod omap44xx_dss_dsi2_hwmod; +static struct omap_hwmod_irq_info omap44xx_dss_dsi2_irqs[] = { + { .irq = 84 + OMAP44XX_IRQ_GIC_START }, +}; + +static struct omap_hwmod_dma_info omap44xx_dss_dsi2_sdma_reqs[] = { + { .dma_req = 83 + OMAP44XX_DMA_REQ_START }, +}; + +static struct omap_hwmod_addr_space omap44xx_dss_dsi2_dma_addrs[] = { + { + .pa_start = 0x58005000, + .pa_end = 0x580051ff, + .flags = ADDR_TYPE_RT + }, +}; + +/* l3_main_2 -> dss_dsi2 */ +static struct omap_hwmod_ocp_if omap44xx_l3_main_2__dss_dsi2 = { + .master = &omap44xx_l3_main_2_hwmod, + .slave = &omap44xx_dss_dsi2_hwmod, + .clk = "l3_div_ck", + .addr = omap44xx_dss_dsi2_dma_addrs, + .addr_cnt = ARRAY_SIZE(omap44xx_dss_dsi2_dma_addrs), + .user = OCP_USER_SDMA, +}; + +static struct omap_hwmod_addr_space omap44xx_dss_dsi2_addrs[] = { + { + .pa_start = 0x48045000, + .pa_end = 0x480451ff, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_per -> dss_dsi2 */ +static struct omap_hwmod_ocp_if omap44xx_l4_per__dss_dsi2 = { + .master = &omap44xx_l4_per_hwmod, + .slave = &omap44xx_dss_dsi2_hwmod, + .clk = "l4_div_ck", + .addr = omap44xx_dss_dsi2_addrs, + .addr_cnt = ARRAY_SIZE(omap44xx_dss_dsi2_addrs), + .user = OCP_USER_MPU, +}; + +/* dss_dsi2 slave ports */ +static struct omap_hwmod_ocp_if *omap44xx_dss_dsi2_slaves[] = { + &omap44xx_l3_main_2__dss_dsi2, + &omap44xx_l4_per__dss_dsi2, +}; + +static struct omap_hwmod omap44xx_dss_dsi2_hwmod = { + .name = "dss_dsi2", + .class = &omap44xx_dsi_hwmod_class, + .mpu_irqs = omap44xx_dss_dsi2_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap44xx_dss_dsi2_irqs), + .sdma_reqs = omap44xx_dss_dsi2_sdma_reqs, + .sdma_reqs_cnt = ARRAY_SIZE(omap44xx_dss_dsi2_sdma_reqs), + .main_clk = "dss_fck", + .prcm = { + .omap4 = { + .clkctrl_reg = OMAP4430_CM_DSS_DSS_CLKCTRL, + }, + }, + .slaves = omap44xx_dss_dsi2_slaves, + .slaves_cnt = ARRAY_SIZE(omap44xx_dss_dsi2_slaves), + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430), +}; + +/* + * 'hdmi' class + * hdmi controller + */ + +static struct omap_hwmod_class_sysconfig omap44xx_hdmi_sysc = { + .rev_offs = 0x0000, + .sysc_offs = 0x0010, + .sysc_flags = (SYSC_HAS_RESET_STATUS | SYSC_HAS_SIDLEMODE | + SYSC_HAS_SOFTRESET), + .idlemodes = (SIDLE_FORCE | SIDLE_NO | SIDLE_SMART | + SIDLE_SMART_WKUP), + .sysc_fields = &omap_hwmod_sysc_type2, +}; + +static struct omap_hwmod_class omap44xx_hdmi_hwmod_class = { + .name = "hdmi", + .sysc = &omap44xx_hdmi_sysc, +}; + +/* dss_hdmi */ +static struct omap_hwmod omap44xx_dss_hdmi_hwmod; +static struct omap_hwmod_irq_info omap44xx_dss_hdmi_irqs[] = { + { .irq = 101 + OMAP44XX_IRQ_GIC_START }, +}; + +static struct omap_hwmod_dma_info omap44xx_dss_hdmi_sdma_reqs[] = { + { .dma_req = 75 + OMAP44XX_DMA_REQ_START }, +}; + +static struct omap_hwmod_addr_space omap44xx_dss_hdmi_dma_addrs[] = { + { + .pa_start = 0x58006000, + .pa_end = 0x58006fff, + .flags = ADDR_TYPE_RT + }, +}; + +/* l3_main_2 -> dss_hdmi */ +static struct omap_hwmod_ocp_if omap44xx_l3_main_2__dss_hdmi = { + .master = &omap44xx_l3_main_2_hwmod, + .slave = &omap44xx_dss_hdmi_hwmod, + .clk = "l3_div_ck", + .addr = omap44xx_dss_hdmi_dma_addrs, + .addr_cnt = ARRAY_SIZE(omap44xx_dss_hdmi_dma_addrs), + .user = OCP_USER_SDMA, +}; + +static struct omap_hwmod_addr_space omap44xx_dss_hdmi_addrs[] = { + { + .pa_start = 0x48046000, + .pa_end = 0x48046fff, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_per -> dss_hdmi */ +static struct omap_hwmod_ocp_if omap44xx_l4_per__dss_hdmi = { + .master = &omap44xx_l4_per_hwmod, + .slave = &omap44xx_dss_hdmi_hwmod, + .clk = "l4_div_ck", + .addr = omap44xx_dss_hdmi_addrs, + .addr_cnt = ARRAY_SIZE(omap44xx_dss_hdmi_addrs), + .user = OCP_USER_MPU, +}; + +/* dss_hdmi slave ports */ +static struct omap_hwmod_ocp_if *omap44xx_dss_hdmi_slaves[] = { + &omap44xx_l3_main_2__dss_hdmi, + &omap44xx_l4_per__dss_hdmi, +}; + +static struct omap_hwmod omap44xx_dss_hdmi_hwmod = { + .name = "dss_hdmi", + .class = &omap44xx_hdmi_hwmod_class, + .mpu_irqs = omap44xx_dss_hdmi_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap44xx_dss_hdmi_irqs), + .sdma_reqs = omap44xx_dss_hdmi_sdma_reqs, + .sdma_reqs_cnt = ARRAY_SIZE(omap44xx_dss_hdmi_sdma_reqs), + .main_clk = "dss_fck", + .prcm = { + .omap4 = { + .clkctrl_reg = OMAP4430_CM_DSS_DSS_CLKCTRL, + }, + }, + .slaves = omap44xx_dss_hdmi_slaves, + .slaves_cnt = ARRAY_SIZE(omap44xx_dss_hdmi_slaves), + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430), +}; + +/* + * 'rfbi' class + * remote frame buffer interface + */ + +static struct omap_hwmod_class_sysconfig omap44xx_rfbi_sysc = { + .rev_offs = 0x0000, + .sysc_offs = 0x0010, + .syss_offs = 0x0014, + .sysc_flags = (SYSC_HAS_AUTOIDLE | SYSC_HAS_SIDLEMODE | + SYSC_HAS_SOFTRESET | SYSS_HAS_RESET_STATUS), + .idlemodes = (SIDLE_FORCE | SIDLE_NO | SIDLE_SMART), + .sysc_fields = &omap_hwmod_sysc_type1, +}; + +static struct omap_hwmod_class omap44xx_rfbi_hwmod_class = { + .name = "rfbi", + .sysc = &omap44xx_rfbi_sysc, +}; + +/* dss_rfbi */ +static struct omap_hwmod omap44xx_dss_rfbi_hwmod; +static struct omap_hwmod_dma_info omap44xx_dss_rfbi_sdma_reqs[] = { + { .dma_req = 13 + OMAP44XX_DMA_REQ_START }, +}; + +static struct omap_hwmod_addr_space omap44xx_dss_rfbi_dma_addrs[] = { + { + .pa_start = 0x58002000, + .pa_end = 0x580020ff, + .flags = ADDR_TYPE_RT + }, +}; + +/* l3_main_2 -> dss_rfbi */ +static struct omap_hwmod_ocp_if omap44xx_l3_main_2__dss_rfbi = { + .master = &omap44xx_l3_main_2_hwmod, + .slave = &omap44xx_dss_rfbi_hwmod, + .clk = "l3_div_ck", + .addr = omap44xx_dss_rfbi_dma_addrs, + .addr_cnt = ARRAY_SIZE(omap44xx_dss_rfbi_dma_addrs), + .user = OCP_USER_SDMA, +}; + +static struct omap_hwmod_addr_space omap44xx_dss_rfbi_addrs[] = { + { + .pa_start = 0x48042000, + .pa_end = 0x480420ff, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_per -> dss_rfbi */ +static struct omap_hwmod_ocp_if omap44xx_l4_per__dss_rfbi = { + .master = &omap44xx_l4_per_hwmod, + .slave = &omap44xx_dss_rfbi_hwmod, + .clk = "l4_div_ck", + .addr = omap44xx_dss_rfbi_addrs, + .addr_cnt = ARRAY_SIZE(omap44xx_dss_rfbi_addrs), + .user = OCP_USER_MPU, +}; + +/* dss_rfbi slave ports */ +static struct omap_hwmod_ocp_if *omap44xx_dss_rfbi_slaves[] = { + &omap44xx_l3_main_2__dss_rfbi, + &omap44xx_l4_per__dss_rfbi, +}; + +static struct omap_hwmod omap44xx_dss_rfbi_hwmod = { + .name = "dss_rfbi", + .class = &omap44xx_rfbi_hwmod_class, + .sdma_reqs = omap44xx_dss_rfbi_sdma_reqs, + .sdma_reqs_cnt = ARRAY_SIZE(omap44xx_dss_rfbi_sdma_reqs), + .main_clk = "dss_fck", + .prcm = { + .omap4 = { + .clkctrl_reg = OMAP4430_CM_DSS_DSS_CLKCTRL, + }, + }, + .slaves = omap44xx_dss_rfbi_slaves, + .slaves_cnt = ARRAY_SIZE(omap44xx_dss_rfbi_slaves), + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430), +}; + +/* + * 'venc' class + * video encoder + */ + +static struct omap_hwmod_class omap44xx_venc_hwmod_class = { + .name = "venc", +}; + +/* dss_venc */ +static struct omap_hwmod omap44xx_dss_venc_hwmod; +static struct omap_hwmod_addr_space omap44xx_dss_venc_dma_addrs[] = { + { + .pa_start = 0x58003000, + .pa_end = 0x580030ff, + .flags = ADDR_TYPE_RT + }, +}; + +/* l3_main_2 -> dss_venc */ +static struct omap_hwmod_ocp_if omap44xx_l3_main_2__dss_venc = { + .master = &omap44xx_l3_main_2_hwmod, + .slave = &omap44xx_dss_venc_hwmod, + .clk = "l3_div_ck", + .addr = omap44xx_dss_venc_dma_addrs, + .addr_cnt = ARRAY_SIZE(omap44xx_dss_venc_dma_addrs), + .user = OCP_USER_SDMA, +}; + +static struct omap_hwmod_addr_space omap44xx_dss_venc_addrs[] = { + { + .pa_start = 0x48043000, + .pa_end = 0x480430ff, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_per -> dss_venc */ +static struct omap_hwmod_ocp_if omap44xx_l4_per__dss_venc = { + .master = &omap44xx_l4_per_hwmod, + .slave = &omap44xx_dss_venc_hwmod, + .clk = "l4_div_ck", + .addr = omap44xx_dss_venc_addrs, + .addr_cnt = ARRAY_SIZE(omap44xx_dss_venc_addrs), + .user = OCP_USER_MPU, +}; + +/* dss_venc slave ports */ +static struct omap_hwmod_ocp_if *omap44xx_dss_venc_slaves[] = { + &omap44xx_l3_main_2__dss_venc, + &omap44xx_l4_per__dss_venc, +}; + +static struct omap_hwmod omap44xx_dss_venc_hwmod = { + .name = "dss_venc", + .class = &omap44xx_venc_hwmod_class, + .main_clk = "dss_fck", + .prcm = { + .omap4 = { + .clkctrl_reg = OMAP4430_CM_DSS_DSS_CLKCTRL, + }, + }, + .slaves = omap44xx_dss_venc_slaves, + .slaves_cnt = ARRAY_SIZE(omap44xx_dss_venc_slaves), + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430), +}; + +/* * 'gpio' class * general purpose io module */ @@ -1093,6 +2030,83 @@ static struct omap_hwmod omap44xx_gpio6_hwmod = { }; /* + * 'hsi' class + * mipi high-speed synchronous serial interface (multichannel and full-duplex + * serial if) + */ + +static struct omap_hwmod_class_sysconfig omap44xx_hsi_sysc = { + .rev_offs = 0x0000, + .sysc_offs = 0x0010, + .syss_offs = 0x0014, + .sysc_flags = (SYSC_HAS_AUTOIDLE | SYSC_HAS_EMUFREE | + SYSC_HAS_MIDLEMODE | SYSC_HAS_SIDLEMODE | + SYSC_HAS_SOFTRESET | SYSS_HAS_RESET_STATUS), + .idlemodes = (SIDLE_FORCE | SIDLE_NO | SIDLE_SMART | + SIDLE_SMART_WKUP | MSTANDBY_FORCE | MSTANDBY_NO | + MSTANDBY_SMART), + .sysc_fields = &omap_hwmod_sysc_type1, +}; + +static struct omap_hwmod_class omap44xx_hsi_hwmod_class = { + .name = "hsi", + .sysc = &omap44xx_hsi_sysc, +}; + +/* hsi */ +static struct omap_hwmod_irq_info omap44xx_hsi_irqs[] = { + { .name = "mpu_p1", .irq = 67 + OMAP44XX_IRQ_GIC_START }, + { .name = "mpu_p2", .irq = 68 + OMAP44XX_IRQ_GIC_START }, + { .name = "mpu_dma", .irq = 71 + OMAP44XX_IRQ_GIC_START }, +}; + +/* hsi master ports */ +static struct omap_hwmod_ocp_if *omap44xx_hsi_masters[] = { + &omap44xx_hsi__l3_main_2, +}; + +static struct omap_hwmod_addr_space omap44xx_hsi_addrs[] = { + { + .pa_start = 0x4a058000, + .pa_end = 0x4a05bfff, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_cfg -> hsi */ +static struct omap_hwmod_ocp_if omap44xx_l4_cfg__hsi = { + .master = &omap44xx_l4_cfg_hwmod, + .slave = &omap44xx_hsi_hwmod, + .clk = "l4_div_ck", + .addr = omap44xx_hsi_addrs, + .addr_cnt = ARRAY_SIZE(omap44xx_hsi_addrs), + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* hsi slave ports */ +static struct omap_hwmod_ocp_if *omap44xx_hsi_slaves[] = { + &omap44xx_l4_cfg__hsi, +}; + +static struct omap_hwmod omap44xx_hsi_hwmod = { + .name = "hsi", + .class = &omap44xx_hsi_hwmod_class, + .mpu_irqs = omap44xx_hsi_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap44xx_hsi_irqs), + .main_clk = "hsi_fck", + .prcm = { + .omap4 = { + .clkctrl_reg = OMAP4430_CM_L3INIT_HSI_CLKCTRL, + }, + }, + .slaves = omap44xx_hsi_slaves, + .slaves_cnt = ARRAY_SIZE(omap44xx_hsi_slaves), + .masters = omap44xx_hsi_masters, + .masters_cnt = ARRAY_SIZE(omap44xx_hsi_masters), + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430), +}; + +/* * 'i2c' class * multimaster high-speed i2c controller */ @@ -1326,6 +2340,188 @@ static struct omap_hwmod omap44xx_i2c4_hwmod = { }; /* + * 'ipu' class + * imaging processor unit + */ + +static struct omap_hwmod_class omap44xx_ipu_hwmod_class = { + .name = "ipu", +}; + +/* ipu */ +static struct omap_hwmod_irq_info omap44xx_ipu_irqs[] = { + { .irq = 100 + OMAP44XX_IRQ_GIC_START }, +}; + +static struct omap_hwmod_rst_info omap44xx_ipu_c0_resets[] = { + { .name = "cpu0", .rst_shift = 0 }, +}; + +static struct omap_hwmod_rst_info omap44xx_ipu_c1_resets[] = { + { .name = "cpu1", .rst_shift = 1 }, +}; + +static struct omap_hwmod_rst_info omap44xx_ipu_resets[] = { + { .name = "mmu_cache", .rst_shift = 2 }, +}; + +/* ipu master ports */ +static struct omap_hwmod_ocp_if *omap44xx_ipu_masters[] = { + &omap44xx_ipu__l3_main_2, +}; + +/* l3_main_2 -> ipu */ +static struct omap_hwmod_ocp_if omap44xx_l3_main_2__ipu = { + .master = &omap44xx_l3_main_2_hwmod, + .slave = &omap44xx_ipu_hwmod, + .clk = "l3_div_ck", + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* ipu slave ports */ +static struct omap_hwmod_ocp_if *omap44xx_ipu_slaves[] = { + &omap44xx_l3_main_2__ipu, +}; + +/* Pseudo hwmod for reset control purpose only */ +static struct omap_hwmod omap44xx_ipu_c0_hwmod = { + .name = "ipu_c0", + .class = &omap44xx_ipu_hwmod_class, + .flags = HWMOD_INIT_NO_RESET, + .rst_lines = omap44xx_ipu_c0_resets, + .rst_lines_cnt = ARRAY_SIZE(omap44xx_ipu_c0_resets), + .prcm = { + .omap4 = { + .rstctrl_reg = OMAP4430_RM_DUCATI_RSTCTRL, + }, + }, + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430), +}; + +/* Pseudo hwmod for reset control purpose only */ +static struct omap_hwmod omap44xx_ipu_c1_hwmod = { + .name = "ipu_c1", + .class = &omap44xx_ipu_hwmod_class, + .flags = HWMOD_INIT_NO_RESET, + .rst_lines = omap44xx_ipu_c1_resets, + .rst_lines_cnt = ARRAY_SIZE(omap44xx_ipu_c1_resets), + .prcm = { + .omap4 = { + .rstctrl_reg = OMAP4430_RM_DUCATI_RSTCTRL, + }, + }, + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430), +}; + +static struct omap_hwmod omap44xx_ipu_hwmod = { + .name = "ipu", + .class = &omap44xx_ipu_hwmod_class, + .mpu_irqs = omap44xx_ipu_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap44xx_ipu_irqs), + .rst_lines = omap44xx_ipu_resets, + .rst_lines_cnt = ARRAY_SIZE(omap44xx_ipu_resets), + .main_clk = "ipu_fck", + .prcm = { + .omap4 = { + .clkctrl_reg = OMAP4430_CM_DUCATI_DUCATI_CLKCTRL, + .rstctrl_reg = OMAP4430_RM_DUCATI_RSTCTRL, + }, + }, + .slaves = omap44xx_ipu_slaves, + .slaves_cnt = ARRAY_SIZE(omap44xx_ipu_slaves), + .masters = omap44xx_ipu_masters, + .masters_cnt = ARRAY_SIZE(omap44xx_ipu_masters), + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430), +}; + +/* + * 'iss' class + * external images sensor pixel data processor + */ + +static struct omap_hwmod_class_sysconfig omap44xx_iss_sysc = { + .rev_offs = 0x0000, + .sysc_offs = 0x0010, + .sysc_flags = (SYSC_HAS_MIDLEMODE | SYSC_HAS_RESET_STATUS | + SYSC_HAS_SIDLEMODE | SYSC_HAS_SOFTRESET), + .idlemodes = (SIDLE_FORCE | SIDLE_NO | SIDLE_SMART | + SIDLE_SMART_WKUP | MSTANDBY_FORCE | MSTANDBY_NO | + MSTANDBY_SMART), + .sysc_fields = &omap_hwmod_sysc_type2, +}; + +static struct omap_hwmod_class omap44xx_iss_hwmod_class = { + .name = "iss", + .sysc = &omap44xx_iss_sysc, +}; + +/* iss */ +static struct omap_hwmod_irq_info omap44xx_iss_irqs[] = { + { .irq = 24 + OMAP44XX_IRQ_GIC_START }, +}; + +static struct omap_hwmod_dma_info omap44xx_iss_sdma_reqs[] = { + { .name = "1", .dma_req = 8 + OMAP44XX_DMA_REQ_START }, + { .name = "2", .dma_req = 9 + OMAP44XX_DMA_REQ_START }, + { .name = "3", .dma_req = 11 + OMAP44XX_DMA_REQ_START }, + { .name = "4", .dma_req = 12 + OMAP44XX_DMA_REQ_START }, +}; + +/* iss master ports */ +static struct omap_hwmod_ocp_if *omap44xx_iss_masters[] = { + &omap44xx_iss__l3_main_2, +}; + +static struct omap_hwmod_addr_space omap44xx_iss_addrs[] = { + { + .pa_start = 0x52000000, + .pa_end = 0x520000ff, + .flags = ADDR_TYPE_RT + }, +}; + +/* l3_main_2 -> iss */ +static struct omap_hwmod_ocp_if omap44xx_l3_main_2__iss = { + .master = &omap44xx_l3_main_2_hwmod, + .slave = &omap44xx_iss_hwmod, + .clk = "l3_div_ck", + .addr = omap44xx_iss_addrs, + .addr_cnt = ARRAY_SIZE(omap44xx_iss_addrs), + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* iss slave ports */ +static struct omap_hwmod_ocp_if *omap44xx_iss_slaves[] = { + &omap44xx_l3_main_2__iss, +}; + +static struct omap_hwmod_opt_clk iss_opt_clks[] = { + { .role = "ctrlclk", .clk = "iss_ctrlclk" }, +}; + +static struct omap_hwmod omap44xx_iss_hwmod = { + .name = "iss", + .class = &omap44xx_iss_hwmod_class, + .mpu_irqs = omap44xx_iss_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap44xx_iss_irqs), + .sdma_reqs = omap44xx_iss_sdma_reqs, + .sdma_reqs_cnt = ARRAY_SIZE(omap44xx_iss_sdma_reqs), + .main_clk = "iss_fck", + .prcm = { + .omap4 = { + .clkctrl_reg = OMAP4430_CM_CAM_ISS_CLKCTRL, + }, + }, + .opt_clks = iss_opt_clks, + .opt_clks_cnt = ARRAY_SIZE(iss_opt_clks), + .slaves = omap44xx_iss_slaves, + .slaves_cnt = ARRAY_SIZE(omap44xx_iss_slaves), + .masters = omap44xx_iss_masters, + .masters_cnt = ARRAY_SIZE(omap44xx_iss_masters), + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430), +}; + +/* * 'iva' class * multi-standard video encoder/decoder hardware accelerator */ @@ -1435,6 +2631,1084 @@ static struct omap_hwmod omap44xx_iva_hwmod = { }; /* + * 'kbd' class + * keyboard controller + */ + +static struct omap_hwmod_class_sysconfig omap44xx_kbd_sysc = { + .rev_offs = 0x0000, + .sysc_offs = 0x0010, + .syss_offs = 0x0014, + .sysc_flags = (SYSC_HAS_AUTOIDLE | SYSC_HAS_CLOCKACTIVITY | + SYSC_HAS_EMUFREE | SYSC_HAS_ENAWAKEUP | + SYSC_HAS_SIDLEMODE | SYSC_HAS_SOFTRESET | + SYSS_HAS_RESET_STATUS), + .idlemodes = (SIDLE_FORCE | SIDLE_NO | SIDLE_SMART), + .sysc_fields = &omap_hwmod_sysc_type1, +}; + +static struct omap_hwmod_class omap44xx_kbd_hwmod_class = { + .name = "kbd", + .sysc = &omap44xx_kbd_sysc, +}; + +/* kbd */ +static struct omap_hwmod omap44xx_kbd_hwmod; +static struct omap_hwmod_irq_info omap44xx_kbd_irqs[] = { + { .irq = 120 + OMAP44XX_IRQ_GIC_START }, +}; + +static struct omap_hwmod_addr_space omap44xx_kbd_addrs[] = { + { + .pa_start = 0x4a31c000, + .pa_end = 0x4a31c07f, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_wkup -> kbd */ +static struct omap_hwmod_ocp_if omap44xx_l4_wkup__kbd = { + .master = &omap44xx_l4_wkup_hwmod, + .slave = &omap44xx_kbd_hwmod, + .clk = "l4_wkup_clk_mux_ck", + .addr = omap44xx_kbd_addrs, + .addr_cnt = ARRAY_SIZE(omap44xx_kbd_addrs), + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* kbd slave ports */ +static struct omap_hwmod_ocp_if *omap44xx_kbd_slaves[] = { + &omap44xx_l4_wkup__kbd, +}; + +static struct omap_hwmod omap44xx_kbd_hwmod = { + .name = "kbd", + .class = &omap44xx_kbd_hwmod_class, + .mpu_irqs = omap44xx_kbd_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap44xx_kbd_irqs), + .main_clk = "kbd_fck", + .prcm = { + .omap4 = { + .clkctrl_reg = OMAP4430_CM_WKUP_KEYBOARD_CLKCTRL, + }, + }, + .slaves = omap44xx_kbd_slaves, + .slaves_cnt = ARRAY_SIZE(omap44xx_kbd_slaves), + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430), +}; + +/* + * 'mailbox' class + * mailbox module allowing communication between the on-chip processors using a + * queued mailbox-interrupt mechanism. + */ + +static struct omap_hwmod_class_sysconfig omap44xx_mailbox_sysc = { + .rev_offs = 0x0000, + .sysc_offs = 0x0010, + .sysc_flags = (SYSC_HAS_RESET_STATUS | SYSC_HAS_SIDLEMODE | + SYSC_HAS_SOFTRESET), + .idlemodes = (SIDLE_FORCE | SIDLE_NO | SIDLE_SMART), + .sysc_fields = &omap_hwmod_sysc_type2, +}; + +static struct omap_hwmod_class omap44xx_mailbox_hwmod_class = { + .name = "mailbox", + .sysc = &omap44xx_mailbox_sysc, +}; + +/* mailbox */ +static struct omap_hwmod omap44xx_mailbox_hwmod; +static struct omap_hwmod_irq_info omap44xx_mailbox_irqs[] = { + { .irq = 26 + OMAP44XX_IRQ_GIC_START }, +}; + +static struct omap_hwmod_addr_space omap44xx_mailbox_addrs[] = { + { + .pa_start = 0x4a0f4000, + .pa_end = 0x4a0f41ff, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_cfg -> mailbox */ +static struct omap_hwmod_ocp_if omap44xx_l4_cfg__mailbox = { + .master = &omap44xx_l4_cfg_hwmod, + .slave = &omap44xx_mailbox_hwmod, + .clk = "l4_div_ck", + .addr = omap44xx_mailbox_addrs, + .addr_cnt = ARRAY_SIZE(omap44xx_mailbox_addrs), + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* mailbox slave ports */ +static struct omap_hwmod_ocp_if *omap44xx_mailbox_slaves[] = { + &omap44xx_l4_cfg__mailbox, +}; + +static struct omap_hwmod omap44xx_mailbox_hwmod = { + .name = "mailbox", + .class = &omap44xx_mailbox_hwmod_class, + .mpu_irqs = omap44xx_mailbox_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap44xx_mailbox_irqs), + .prcm = { + .omap4 = { + .clkctrl_reg = OMAP4430_CM_L4CFG_MAILBOX_CLKCTRL, + }, + }, + .slaves = omap44xx_mailbox_slaves, + .slaves_cnt = ARRAY_SIZE(omap44xx_mailbox_slaves), + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430), +}; + +/* + * 'mcbsp' class + * multi channel buffered serial port controller + */ + +static struct omap_hwmod_class_sysconfig omap44xx_mcbsp_sysc = { + .sysc_offs = 0x008c, + .sysc_flags = (SYSC_HAS_CLOCKACTIVITY | SYSC_HAS_ENAWAKEUP | + SYSC_HAS_SIDLEMODE | SYSC_HAS_SOFTRESET), + .idlemodes = (SIDLE_FORCE | SIDLE_NO | SIDLE_SMART), + .sysc_fields = &omap_hwmod_sysc_type1, +}; + +static struct omap_hwmod_class omap44xx_mcbsp_hwmod_class = { + .name = "mcbsp", + .sysc = &omap44xx_mcbsp_sysc, + .rev = MCBSP_CONFIG_TYPE4, +}; + +/* mcbsp1 */ +static struct omap_hwmod omap44xx_mcbsp1_hwmod; +static struct omap_hwmod_irq_info omap44xx_mcbsp1_irqs[] = { + { .irq = 17 + OMAP44XX_IRQ_GIC_START }, +}; + +static struct omap_hwmod_dma_info omap44xx_mcbsp1_sdma_reqs[] = { + { .name = "tx", .dma_req = 32 + OMAP44XX_DMA_REQ_START }, + { .name = "rx", .dma_req = 33 + OMAP44XX_DMA_REQ_START }, +}; + +static struct omap_hwmod_addr_space omap44xx_mcbsp1_addrs[] = { + { + .name = "mpu", + .pa_start = 0x40122000, + .pa_end = 0x401220ff, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_abe -> mcbsp1 */ +static struct omap_hwmod_ocp_if omap44xx_l4_abe__mcbsp1 = { + .master = &omap44xx_l4_abe_hwmod, + .slave = &omap44xx_mcbsp1_hwmod, + .clk = "ocp_abe_iclk", + .addr = omap44xx_mcbsp1_addrs, + .addr_cnt = ARRAY_SIZE(omap44xx_mcbsp1_addrs), + .user = OCP_USER_MPU, +}; + +static struct omap_hwmod_addr_space omap44xx_mcbsp1_dma_addrs[] = { + { + .name = "dma", + .pa_start = 0x49022000, + .pa_end = 0x490220ff, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_abe -> mcbsp1 (dma) */ +static struct omap_hwmod_ocp_if omap44xx_l4_abe__mcbsp1_dma = { + .master = &omap44xx_l4_abe_hwmod, + .slave = &omap44xx_mcbsp1_hwmod, + .clk = "ocp_abe_iclk", + .addr = omap44xx_mcbsp1_dma_addrs, + .addr_cnt = ARRAY_SIZE(omap44xx_mcbsp1_dma_addrs), + .user = OCP_USER_SDMA, +}; + +/* mcbsp1 slave ports */ +static struct omap_hwmod_ocp_if *omap44xx_mcbsp1_slaves[] = { + &omap44xx_l4_abe__mcbsp1, + &omap44xx_l4_abe__mcbsp1_dma, +}; + +static struct omap_hwmod omap44xx_mcbsp1_hwmod = { + .name = "mcbsp1", + .class = &omap44xx_mcbsp_hwmod_class, + .mpu_irqs = omap44xx_mcbsp1_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap44xx_mcbsp1_irqs), + .sdma_reqs = omap44xx_mcbsp1_sdma_reqs, + .sdma_reqs_cnt = ARRAY_SIZE(omap44xx_mcbsp1_sdma_reqs), + .main_clk = "mcbsp1_fck", + .prcm = { + .omap4 = { + .clkctrl_reg = OMAP4430_CM1_ABE_MCBSP1_CLKCTRL, + }, + }, + .slaves = omap44xx_mcbsp1_slaves, + .slaves_cnt = ARRAY_SIZE(omap44xx_mcbsp1_slaves), + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430), +}; + +/* mcbsp2 */ +static struct omap_hwmod omap44xx_mcbsp2_hwmod; +static struct omap_hwmod_irq_info omap44xx_mcbsp2_irqs[] = { + { .irq = 22 + OMAP44XX_IRQ_GIC_START }, +}; + +static struct omap_hwmod_dma_info omap44xx_mcbsp2_sdma_reqs[] = { + { .name = "tx", .dma_req = 16 + OMAP44XX_DMA_REQ_START }, + { .name = "rx", .dma_req = 17 + OMAP44XX_DMA_REQ_START }, +}; + +static struct omap_hwmod_addr_space omap44xx_mcbsp2_addrs[] = { + { + .name = "mpu", + .pa_start = 0x40124000, + .pa_end = 0x401240ff, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_abe -> mcbsp2 */ +static struct omap_hwmod_ocp_if omap44xx_l4_abe__mcbsp2 = { + .master = &omap44xx_l4_abe_hwmod, + .slave = &omap44xx_mcbsp2_hwmod, + .clk = "ocp_abe_iclk", + .addr = omap44xx_mcbsp2_addrs, + .addr_cnt = ARRAY_SIZE(omap44xx_mcbsp2_addrs), + .user = OCP_USER_MPU, +}; + +static struct omap_hwmod_addr_space omap44xx_mcbsp2_dma_addrs[] = { + { + .name = "dma", + .pa_start = 0x49024000, + .pa_end = 0x490240ff, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_abe -> mcbsp2 (dma) */ +static struct omap_hwmod_ocp_if omap44xx_l4_abe__mcbsp2_dma = { + .master = &omap44xx_l4_abe_hwmod, + .slave = &omap44xx_mcbsp2_hwmod, + .clk = "ocp_abe_iclk", + .addr = omap44xx_mcbsp2_dma_addrs, + .addr_cnt = ARRAY_SIZE(omap44xx_mcbsp2_dma_addrs), + .user = OCP_USER_SDMA, +}; + +/* mcbsp2 slave ports */ +static struct omap_hwmod_ocp_if *omap44xx_mcbsp2_slaves[] = { + &omap44xx_l4_abe__mcbsp2, + &omap44xx_l4_abe__mcbsp2_dma, +}; + +static struct omap_hwmod omap44xx_mcbsp2_hwmod = { + .name = "mcbsp2", + .class = &omap44xx_mcbsp_hwmod_class, + .mpu_irqs = omap44xx_mcbsp2_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap44xx_mcbsp2_irqs), + .sdma_reqs = omap44xx_mcbsp2_sdma_reqs, + .sdma_reqs_cnt = ARRAY_SIZE(omap44xx_mcbsp2_sdma_reqs), + .main_clk = "mcbsp2_fck", + .prcm = { + .omap4 = { + .clkctrl_reg = OMAP4430_CM1_ABE_MCBSP2_CLKCTRL, + }, + }, + .slaves = omap44xx_mcbsp2_slaves, + .slaves_cnt = ARRAY_SIZE(omap44xx_mcbsp2_slaves), + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430), +}; + +/* mcbsp3 */ +static struct omap_hwmod omap44xx_mcbsp3_hwmod; +static struct omap_hwmod_irq_info omap44xx_mcbsp3_irqs[] = { + { .irq = 23 + OMAP44XX_IRQ_GIC_START }, +}; + +static struct omap_hwmod_dma_info omap44xx_mcbsp3_sdma_reqs[] = { + { .name = "tx", .dma_req = 18 + OMAP44XX_DMA_REQ_START }, + { .name = "rx", .dma_req = 19 + OMAP44XX_DMA_REQ_START }, +}; + +static struct omap_hwmod_addr_space omap44xx_mcbsp3_addrs[] = { + { + .name = "mpu", + .pa_start = 0x40126000, + .pa_end = 0x401260ff, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_abe -> mcbsp3 */ +static struct omap_hwmod_ocp_if omap44xx_l4_abe__mcbsp3 = { + .master = &omap44xx_l4_abe_hwmod, + .slave = &omap44xx_mcbsp3_hwmod, + .clk = "ocp_abe_iclk", + .addr = omap44xx_mcbsp3_addrs, + .addr_cnt = ARRAY_SIZE(omap44xx_mcbsp3_addrs), + .user = OCP_USER_MPU, +}; + +static struct omap_hwmod_addr_space omap44xx_mcbsp3_dma_addrs[] = { + { + .name = "dma", + .pa_start = 0x49026000, + .pa_end = 0x490260ff, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_abe -> mcbsp3 (dma) */ +static struct omap_hwmod_ocp_if omap44xx_l4_abe__mcbsp3_dma = { + .master = &omap44xx_l4_abe_hwmod, + .slave = &omap44xx_mcbsp3_hwmod, + .clk = "ocp_abe_iclk", + .addr = omap44xx_mcbsp3_dma_addrs, + .addr_cnt = ARRAY_SIZE(omap44xx_mcbsp3_dma_addrs), + .user = OCP_USER_SDMA, +}; + +/* mcbsp3 slave ports */ +static struct omap_hwmod_ocp_if *omap44xx_mcbsp3_slaves[] = { + &omap44xx_l4_abe__mcbsp3, + &omap44xx_l4_abe__mcbsp3_dma, +}; + +static struct omap_hwmod omap44xx_mcbsp3_hwmod = { + .name = "mcbsp3", + .class = &omap44xx_mcbsp_hwmod_class, + .mpu_irqs = omap44xx_mcbsp3_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap44xx_mcbsp3_irqs), + .sdma_reqs = omap44xx_mcbsp3_sdma_reqs, + .sdma_reqs_cnt = ARRAY_SIZE(omap44xx_mcbsp3_sdma_reqs), + .main_clk = "mcbsp3_fck", + .prcm = { + .omap4 = { + .clkctrl_reg = OMAP4430_CM1_ABE_MCBSP3_CLKCTRL, + }, + }, + .slaves = omap44xx_mcbsp3_slaves, + .slaves_cnt = ARRAY_SIZE(omap44xx_mcbsp3_slaves), + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430), +}; + +/* mcbsp4 */ +static struct omap_hwmod omap44xx_mcbsp4_hwmod; +static struct omap_hwmod_irq_info omap44xx_mcbsp4_irqs[] = { + { .irq = 16 + OMAP44XX_IRQ_GIC_START }, +}; + +static struct omap_hwmod_dma_info omap44xx_mcbsp4_sdma_reqs[] = { + { .name = "tx", .dma_req = 30 + OMAP44XX_DMA_REQ_START }, + { .name = "rx", .dma_req = 31 + OMAP44XX_DMA_REQ_START }, +}; + +static struct omap_hwmod_addr_space omap44xx_mcbsp4_addrs[] = { + { + .pa_start = 0x48096000, + .pa_end = 0x480960ff, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_per -> mcbsp4 */ +static struct omap_hwmod_ocp_if omap44xx_l4_per__mcbsp4 = { + .master = &omap44xx_l4_per_hwmod, + .slave = &omap44xx_mcbsp4_hwmod, + .clk = "l4_div_ck", + .addr = omap44xx_mcbsp4_addrs, + .addr_cnt = ARRAY_SIZE(omap44xx_mcbsp4_addrs), + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* mcbsp4 slave ports */ +static struct omap_hwmod_ocp_if *omap44xx_mcbsp4_slaves[] = { + &omap44xx_l4_per__mcbsp4, +}; + +static struct omap_hwmod omap44xx_mcbsp4_hwmod = { + .name = "mcbsp4", + .class = &omap44xx_mcbsp_hwmod_class, + .mpu_irqs = omap44xx_mcbsp4_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap44xx_mcbsp4_irqs), + .sdma_reqs = omap44xx_mcbsp4_sdma_reqs, + .sdma_reqs_cnt = ARRAY_SIZE(omap44xx_mcbsp4_sdma_reqs), + .main_clk = "mcbsp4_fck", + .prcm = { + .omap4 = { + .clkctrl_reg = OMAP4430_CM_L4PER_MCBSP4_CLKCTRL, + }, + }, + .slaves = omap44xx_mcbsp4_slaves, + .slaves_cnt = ARRAY_SIZE(omap44xx_mcbsp4_slaves), + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430), +}; + +/* + * 'mcpdm' class + * multi channel pdm controller (proprietary interface with phoenix power + * ic) + */ + +static struct omap_hwmod_class_sysconfig omap44xx_mcpdm_sysc = { + .rev_offs = 0x0000, + .sysc_offs = 0x0010, + .sysc_flags = (SYSC_HAS_EMUFREE | SYSC_HAS_RESET_STATUS | + SYSC_HAS_SIDLEMODE | SYSC_HAS_SOFTRESET), + .idlemodes = (SIDLE_FORCE | SIDLE_NO | SIDLE_SMART | + SIDLE_SMART_WKUP), + .sysc_fields = &omap_hwmod_sysc_type2, +}; + +static struct omap_hwmod_class omap44xx_mcpdm_hwmod_class = { + .name = "mcpdm", + .sysc = &omap44xx_mcpdm_sysc, +}; + +/* mcpdm */ +static struct omap_hwmod omap44xx_mcpdm_hwmod; +static struct omap_hwmod_irq_info omap44xx_mcpdm_irqs[] = { + { .irq = 112 + OMAP44XX_IRQ_GIC_START }, +}; + +static struct omap_hwmod_dma_info omap44xx_mcpdm_sdma_reqs[] = { + { .name = "up_link", .dma_req = 64 + OMAP44XX_DMA_REQ_START }, + { .name = "dn_link", .dma_req = 65 + OMAP44XX_DMA_REQ_START }, +}; + +static struct omap_hwmod_addr_space omap44xx_mcpdm_addrs[] = { + { + .pa_start = 0x40132000, + .pa_end = 0x4013207f, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_abe -> mcpdm */ +static struct omap_hwmod_ocp_if omap44xx_l4_abe__mcpdm = { + .master = &omap44xx_l4_abe_hwmod, + .slave = &omap44xx_mcpdm_hwmod, + .clk = "ocp_abe_iclk", + .addr = omap44xx_mcpdm_addrs, + .addr_cnt = ARRAY_SIZE(omap44xx_mcpdm_addrs), + .user = OCP_USER_MPU, +}; + +static struct omap_hwmod_addr_space omap44xx_mcpdm_dma_addrs[] = { + { + .pa_start = 0x49032000, + .pa_end = 0x4903207f, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_abe -> mcpdm (dma) */ +static struct omap_hwmod_ocp_if omap44xx_l4_abe__mcpdm_dma = { + .master = &omap44xx_l4_abe_hwmod, + .slave = &omap44xx_mcpdm_hwmod, + .clk = "ocp_abe_iclk", + .addr = omap44xx_mcpdm_dma_addrs, + .addr_cnt = ARRAY_SIZE(omap44xx_mcpdm_dma_addrs), + .user = OCP_USER_SDMA, +}; + +/* mcpdm slave ports */ +static struct omap_hwmod_ocp_if *omap44xx_mcpdm_slaves[] = { + &omap44xx_l4_abe__mcpdm, + &omap44xx_l4_abe__mcpdm_dma, +}; + +static struct omap_hwmod omap44xx_mcpdm_hwmod = { + .name = "mcpdm", + .class = &omap44xx_mcpdm_hwmod_class, + .mpu_irqs = omap44xx_mcpdm_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap44xx_mcpdm_irqs), + .sdma_reqs = omap44xx_mcpdm_sdma_reqs, + .sdma_reqs_cnt = ARRAY_SIZE(omap44xx_mcpdm_sdma_reqs), + .main_clk = "mcpdm_fck", + .prcm = { + .omap4 = { + .clkctrl_reg = OMAP4430_CM1_ABE_PDM_CLKCTRL, + }, + }, + .slaves = omap44xx_mcpdm_slaves, + .slaves_cnt = ARRAY_SIZE(omap44xx_mcpdm_slaves), + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430), +}; + +/* + * 'mcspi' class + * multichannel serial port interface (mcspi) / master/slave synchronous serial + * bus + */ + +static struct omap_hwmod_class_sysconfig omap44xx_mcspi_sysc = { + .rev_offs = 0x0000, + .sysc_offs = 0x0010, + .sysc_flags = (SYSC_HAS_EMUFREE | SYSC_HAS_RESET_STATUS | + SYSC_HAS_SIDLEMODE | SYSC_HAS_SOFTRESET), + .idlemodes = (SIDLE_FORCE | SIDLE_NO | SIDLE_SMART | + SIDLE_SMART_WKUP), + .sysc_fields = &omap_hwmod_sysc_type2, +}; + +static struct omap_hwmod_class omap44xx_mcspi_hwmod_class = { + .name = "mcspi", + .sysc = &omap44xx_mcspi_sysc, + .rev = OMAP4_MCSPI_REV, +}; + +/* mcspi1 */ +static struct omap_hwmod omap44xx_mcspi1_hwmod; +static struct omap_hwmod_irq_info omap44xx_mcspi1_irqs[] = { + { .irq = 65 + OMAP44XX_IRQ_GIC_START }, +}; + +static struct omap_hwmod_dma_info omap44xx_mcspi1_sdma_reqs[] = { + { .name = "tx0", .dma_req = 34 + OMAP44XX_DMA_REQ_START }, + { .name = "rx0", .dma_req = 35 + OMAP44XX_DMA_REQ_START }, + { .name = "tx1", .dma_req = 36 + OMAP44XX_DMA_REQ_START }, + { .name = "rx1", .dma_req = 37 + OMAP44XX_DMA_REQ_START }, + { .name = "tx2", .dma_req = 38 + OMAP44XX_DMA_REQ_START }, + { .name = "rx2", .dma_req = 39 + OMAP44XX_DMA_REQ_START }, + { .name = "tx3", .dma_req = 40 + OMAP44XX_DMA_REQ_START }, + { .name = "rx3", .dma_req = 41 + OMAP44XX_DMA_REQ_START }, +}; + +static struct omap_hwmod_addr_space omap44xx_mcspi1_addrs[] = { + { + .pa_start = 0x48098000, + .pa_end = 0x480981ff, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_per -> mcspi1 */ +static struct omap_hwmod_ocp_if omap44xx_l4_per__mcspi1 = { + .master = &omap44xx_l4_per_hwmod, + .slave = &omap44xx_mcspi1_hwmod, + .clk = "l4_div_ck", + .addr = omap44xx_mcspi1_addrs, + .addr_cnt = ARRAY_SIZE(omap44xx_mcspi1_addrs), + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* mcspi1 slave ports */ +static struct omap_hwmod_ocp_if *omap44xx_mcspi1_slaves[] = { + &omap44xx_l4_per__mcspi1, +}; + +/* mcspi1 dev_attr */ +static struct omap2_mcspi_dev_attr mcspi1_dev_attr = { + .num_chipselect = 4, +}; + +static struct omap_hwmod omap44xx_mcspi1_hwmod = { + .name = "mcspi1", + .class = &omap44xx_mcspi_hwmod_class, + .mpu_irqs = omap44xx_mcspi1_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap44xx_mcspi1_irqs), + .sdma_reqs = omap44xx_mcspi1_sdma_reqs, + .sdma_reqs_cnt = ARRAY_SIZE(omap44xx_mcspi1_sdma_reqs), + .main_clk = "mcspi1_fck", + .prcm = { + .omap4 = { + .clkctrl_reg = OMAP4430_CM_L4PER_MCSPI1_CLKCTRL, + }, + }, + .dev_attr = &mcspi1_dev_attr, + .slaves = omap44xx_mcspi1_slaves, + .slaves_cnt = ARRAY_SIZE(omap44xx_mcspi1_slaves), + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430), +}; + +/* mcspi2 */ +static struct omap_hwmod omap44xx_mcspi2_hwmod; +static struct omap_hwmod_irq_info omap44xx_mcspi2_irqs[] = { + { .irq = 66 + OMAP44XX_IRQ_GIC_START }, +}; + +static struct omap_hwmod_dma_info omap44xx_mcspi2_sdma_reqs[] = { + { .name = "tx0", .dma_req = 42 + OMAP44XX_DMA_REQ_START }, + { .name = "rx0", .dma_req = 43 + OMAP44XX_DMA_REQ_START }, + { .name = "tx1", .dma_req = 44 + OMAP44XX_DMA_REQ_START }, + { .name = "rx1", .dma_req = 45 + OMAP44XX_DMA_REQ_START }, +}; + +static struct omap_hwmod_addr_space omap44xx_mcspi2_addrs[] = { + { + .pa_start = 0x4809a000, + .pa_end = 0x4809a1ff, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_per -> mcspi2 */ +static struct omap_hwmod_ocp_if omap44xx_l4_per__mcspi2 = { + .master = &omap44xx_l4_per_hwmod, + .slave = &omap44xx_mcspi2_hwmod, + .clk = "l4_div_ck", + .addr = omap44xx_mcspi2_addrs, + .addr_cnt = ARRAY_SIZE(omap44xx_mcspi2_addrs), + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* mcspi2 slave ports */ +static struct omap_hwmod_ocp_if *omap44xx_mcspi2_slaves[] = { + &omap44xx_l4_per__mcspi2, +}; + +/* mcspi2 dev_attr */ +static struct omap2_mcspi_dev_attr mcspi2_dev_attr = { + .num_chipselect = 2, +}; + +static struct omap_hwmod omap44xx_mcspi2_hwmod = { + .name = "mcspi2", + .class = &omap44xx_mcspi_hwmod_class, + .mpu_irqs = omap44xx_mcspi2_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap44xx_mcspi2_irqs), + .sdma_reqs = omap44xx_mcspi2_sdma_reqs, + .sdma_reqs_cnt = ARRAY_SIZE(omap44xx_mcspi2_sdma_reqs), + .main_clk = "mcspi2_fck", + .prcm = { + .omap4 = { + .clkctrl_reg = OMAP4430_CM_L4PER_MCSPI2_CLKCTRL, + }, + }, + .dev_attr = &mcspi2_dev_attr, + .slaves = omap44xx_mcspi2_slaves, + .slaves_cnt = ARRAY_SIZE(omap44xx_mcspi2_slaves), + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430), +}; + +/* mcspi3 */ +static struct omap_hwmod omap44xx_mcspi3_hwmod; +static struct omap_hwmod_irq_info omap44xx_mcspi3_irqs[] = { + { .irq = 91 + OMAP44XX_IRQ_GIC_START }, +}; + +static struct omap_hwmod_dma_info omap44xx_mcspi3_sdma_reqs[] = { + { .name = "tx0", .dma_req = 14 + OMAP44XX_DMA_REQ_START }, + { .name = "rx0", .dma_req = 15 + OMAP44XX_DMA_REQ_START }, + { .name = "tx1", .dma_req = 22 + OMAP44XX_DMA_REQ_START }, + { .name = "rx1", .dma_req = 23 + OMAP44XX_DMA_REQ_START }, +}; + +static struct omap_hwmod_addr_space omap44xx_mcspi3_addrs[] = { + { + .pa_start = 0x480b8000, + .pa_end = 0x480b81ff, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_per -> mcspi3 */ +static struct omap_hwmod_ocp_if omap44xx_l4_per__mcspi3 = { + .master = &omap44xx_l4_per_hwmod, + .slave = &omap44xx_mcspi3_hwmod, + .clk = "l4_div_ck", + .addr = omap44xx_mcspi3_addrs, + .addr_cnt = ARRAY_SIZE(omap44xx_mcspi3_addrs), + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* mcspi3 slave ports */ +static struct omap_hwmod_ocp_if *omap44xx_mcspi3_slaves[] = { + &omap44xx_l4_per__mcspi3, +}; + +/* mcspi3 dev_attr */ +static struct omap2_mcspi_dev_attr mcspi3_dev_attr = { + .num_chipselect = 2, +}; + +static struct omap_hwmod omap44xx_mcspi3_hwmod = { + .name = "mcspi3", + .class = &omap44xx_mcspi_hwmod_class, + .mpu_irqs = omap44xx_mcspi3_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap44xx_mcspi3_irqs), + .sdma_reqs = omap44xx_mcspi3_sdma_reqs, + .sdma_reqs_cnt = ARRAY_SIZE(omap44xx_mcspi3_sdma_reqs), + .main_clk = "mcspi3_fck", + .prcm = { + .omap4 = { + .clkctrl_reg = OMAP4430_CM_L4PER_MCSPI3_CLKCTRL, + }, + }, + .dev_attr = &mcspi3_dev_attr, + .slaves = omap44xx_mcspi3_slaves, + .slaves_cnt = ARRAY_SIZE(omap44xx_mcspi3_slaves), + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430), +}; + +/* mcspi4 */ +static struct omap_hwmod omap44xx_mcspi4_hwmod; +static struct omap_hwmod_irq_info omap44xx_mcspi4_irqs[] = { + { .irq = 48 + OMAP44XX_IRQ_GIC_START }, +}; + +static struct omap_hwmod_dma_info omap44xx_mcspi4_sdma_reqs[] = { + { .name = "tx0", .dma_req = 69 + OMAP44XX_DMA_REQ_START }, + { .name = "rx0", .dma_req = 70 + OMAP44XX_DMA_REQ_START }, +}; + +static struct omap_hwmod_addr_space omap44xx_mcspi4_addrs[] = { + { + .pa_start = 0x480ba000, + .pa_end = 0x480ba1ff, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_per -> mcspi4 */ +static struct omap_hwmod_ocp_if omap44xx_l4_per__mcspi4 = { + .master = &omap44xx_l4_per_hwmod, + .slave = &omap44xx_mcspi4_hwmod, + .clk = "l4_div_ck", + .addr = omap44xx_mcspi4_addrs, + .addr_cnt = ARRAY_SIZE(omap44xx_mcspi4_addrs), + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* mcspi4 slave ports */ +static struct omap_hwmod_ocp_if *omap44xx_mcspi4_slaves[] = { + &omap44xx_l4_per__mcspi4, +}; + +/* mcspi4 dev_attr */ +static struct omap2_mcspi_dev_attr mcspi4_dev_attr = { + .num_chipselect = 1, +}; + +static struct omap_hwmod omap44xx_mcspi4_hwmod = { + .name = "mcspi4", + .class = &omap44xx_mcspi_hwmod_class, + .mpu_irqs = omap44xx_mcspi4_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap44xx_mcspi4_irqs), + .sdma_reqs = omap44xx_mcspi4_sdma_reqs, + .sdma_reqs_cnt = ARRAY_SIZE(omap44xx_mcspi4_sdma_reqs), + .main_clk = "mcspi4_fck", + .prcm = { + .omap4 = { + .clkctrl_reg = OMAP4430_CM_L4PER_MCSPI4_CLKCTRL, + }, + }, + .dev_attr = &mcspi4_dev_attr, + .slaves = omap44xx_mcspi4_slaves, + .slaves_cnt = ARRAY_SIZE(omap44xx_mcspi4_slaves), + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430), +}; + +/* + * 'mmc' class + * multimedia card high-speed/sd/sdio (mmc/sd/sdio) host controller + */ + +static struct omap_hwmod_class_sysconfig omap44xx_mmc_sysc = { + .rev_offs = 0x0000, + .sysc_offs = 0x0010, + .sysc_flags = (SYSC_HAS_EMUFREE | SYSC_HAS_MIDLEMODE | + SYSC_HAS_RESET_STATUS | SYSC_HAS_SIDLEMODE | + SYSC_HAS_SOFTRESET), + .idlemodes = (SIDLE_FORCE | SIDLE_NO | SIDLE_SMART | + SIDLE_SMART_WKUP | MSTANDBY_FORCE | MSTANDBY_NO | + MSTANDBY_SMART), + .sysc_fields = &omap_hwmod_sysc_type2, +}; + +static struct omap_hwmod_class omap44xx_mmc_hwmod_class = { + .name = "mmc", + .sysc = &omap44xx_mmc_sysc, +}; + +/* mmc1 */ + +static struct omap_hwmod_irq_info omap44xx_mmc1_irqs[] = { + { .irq = 83 + OMAP44XX_IRQ_GIC_START }, +}; + +static struct omap_hwmod_dma_info omap44xx_mmc1_sdma_reqs[] = { + { .name = "tx", .dma_req = 60 + OMAP44XX_DMA_REQ_START }, + { .name = "rx", .dma_req = 61 + OMAP44XX_DMA_REQ_START }, +}; + +/* mmc1 master ports */ +static struct omap_hwmod_ocp_if *omap44xx_mmc1_masters[] = { + &omap44xx_mmc1__l3_main_1, +}; + +static struct omap_hwmod_addr_space omap44xx_mmc1_addrs[] = { + { + .pa_start = 0x4809c000, + .pa_end = 0x4809c3ff, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_per -> mmc1 */ +static struct omap_hwmod_ocp_if omap44xx_l4_per__mmc1 = { + .master = &omap44xx_l4_per_hwmod, + .slave = &omap44xx_mmc1_hwmod, + .clk = "l4_div_ck", + .addr = omap44xx_mmc1_addrs, + .addr_cnt = ARRAY_SIZE(omap44xx_mmc1_addrs), + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* mmc1 slave ports */ +static struct omap_hwmod_ocp_if *omap44xx_mmc1_slaves[] = { + &omap44xx_l4_per__mmc1, +}; + +/* mmc1 dev_attr */ +static struct omap_mmc_dev_attr mmc1_dev_attr = { + .flags = OMAP_HSMMC_SUPPORTS_DUAL_VOLT, +}; + +static struct omap_hwmod omap44xx_mmc1_hwmod = { + .name = "mmc1", + .class = &omap44xx_mmc_hwmod_class, + .mpu_irqs = omap44xx_mmc1_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap44xx_mmc1_irqs), + .sdma_reqs = omap44xx_mmc1_sdma_reqs, + .sdma_reqs_cnt = ARRAY_SIZE(omap44xx_mmc1_sdma_reqs), + .main_clk = "mmc1_fck", + .prcm = { + .omap4 = { + .clkctrl_reg = OMAP4430_CM_L3INIT_MMC1_CLKCTRL, + }, + }, + .dev_attr = &mmc1_dev_attr, + .slaves = omap44xx_mmc1_slaves, + .slaves_cnt = ARRAY_SIZE(omap44xx_mmc1_slaves), + .masters = omap44xx_mmc1_masters, + .masters_cnt = ARRAY_SIZE(omap44xx_mmc1_masters), + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430), +}; + +/* mmc2 */ +static struct omap_hwmod_irq_info omap44xx_mmc2_irqs[] = { + { .irq = 86 + OMAP44XX_IRQ_GIC_START }, +}; + +static struct omap_hwmod_dma_info omap44xx_mmc2_sdma_reqs[] = { + { .name = "tx", .dma_req = 46 + OMAP44XX_DMA_REQ_START }, + { .name = "rx", .dma_req = 47 + OMAP44XX_DMA_REQ_START }, +}; + +/* mmc2 master ports */ +static struct omap_hwmod_ocp_if *omap44xx_mmc2_masters[] = { + &omap44xx_mmc2__l3_main_1, +}; + +static struct omap_hwmod_addr_space omap44xx_mmc2_addrs[] = { + { + .pa_start = 0x480b4000, + .pa_end = 0x480b43ff, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_per -> mmc2 */ +static struct omap_hwmod_ocp_if omap44xx_l4_per__mmc2 = { + .master = &omap44xx_l4_per_hwmod, + .slave = &omap44xx_mmc2_hwmod, + .clk = "l4_div_ck", + .addr = omap44xx_mmc2_addrs, + .addr_cnt = ARRAY_SIZE(omap44xx_mmc2_addrs), + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* mmc2 slave ports */ +static struct omap_hwmod_ocp_if *omap44xx_mmc2_slaves[] = { + &omap44xx_l4_per__mmc2, +}; + +static struct omap_hwmod omap44xx_mmc2_hwmod = { + .name = "mmc2", + .class = &omap44xx_mmc_hwmod_class, + .mpu_irqs = omap44xx_mmc2_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap44xx_mmc2_irqs), + .sdma_reqs = omap44xx_mmc2_sdma_reqs, + .sdma_reqs_cnt = ARRAY_SIZE(omap44xx_mmc2_sdma_reqs), + .main_clk = "mmc2_fck", + .prcm = { + .omap4 = { + .clkctrl_reg = OMAP4430_CM_L3INIT_MMC2_CLKCTRL, + }, + }, + .slaves = omap44xx_mmc2_slaves, + .slaves_cnt = ARRAY_SIZE(omap44xx_mmc2_slaves), + .masters = omap44xx_mmc2_masters, + .masters_cnt = ARRAY_SIZE(omap44xx_mmc2_masters), + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430), +}; + +/* mmc3 */ +static struct omap_hwmod omap44xx_mmc3_hwmod; +static struct omap_hwmod_irq_info omap44xx_mmc3_irqs[] = { + { .irq = 94 + OMAP44XX_IRQ_GIC_START }, +}; + +static struct omap_hwmod_dma_info omap44xx_mmc3_sdma_reqs[] = { + { .name = "tx", .dma_req = 76 + OMAP44XX_DMA_REQ_START }, + { .name = "rx", .dma_req = 77 + OMAP44XX_DMA_REQ_START }, +}; + +static struct omap_hwmod_addr_space omap44xx_mmc3_addrs[] = { + { + .pa_start = 0x480ad000, + .pa_end = 0x480ad3ff, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_per -> mmc3 */ +static struct omap_hwmod_ocp_if omap44xx_l4_per__mmc3 = { + .master = &omap44xx_l4_per_hwmod, + .slave = &omap44xx_mmc3_hwmod, + .clk = "l4_div_ck", + .addr = omap44xx_mmc3_addrs, + .addr_cnt = ARRAY_SIZE(omap44xx_mmc3_addrs), + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* mmc3 slave ports */ +static struct omap_hwmod_ocp_if *omap44xx_mmc3_slaves[] = { + &omap44xx_l4_per__mmc3, +}; + +static struct omap_hwmod omap44xx_mmc3_hwmod = { + .name = "mmc3", + .class = &omap44xx_mmc_hwmod_class, + .mpu_irqs = omap44xx_mmc3_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap44xx_mmc3_irqs), + .sdma_reqs = omap44xx_mmc3_sdma_reqs, + .sdma_reqs_cnt = ARRAY_SIZE(omap44xx_mmc3_sdma_reqs), + .main_clk = "mmc3_fck", + .prcm = { + .omap4 = { + .clkctrl_reg = OMAP4430_CM_L4PER_MMCSD3_CLKCTRL, + }, + }, + .slaves = omap44xx_mmc3_slaves, + .slaves_cnt = ARRAY_SIZE(omap44xx_mmc3_slaves), + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430), +}; + +/* mmc4 */ +static struct omap_hwmod omap44xx_mmc4_hwmod; +static struct omap_hwmod_irq_info omap44xx_mmc4_irqs[] = { + { .irq = 96 + OMAP44XX_IRQ_GIC_START }, +}; + +static struct omap_hwmod_dma_info omap44xx_mmc4_sdma_reqs[] = { + { .name = "tx", .dma_req = 56 + OMAP44XX_DMA_REQ_START }, + { .name = "rx", .dma_req = 57 + OMAP44XX_DMA_REQ_START }, +}; + +static struct omap_hwmod_addr_space omap44xx_mmc4_addrs[] = { + { + .pa_start = 0x480d1000, + .pa_end = 0x480d13ff, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_per -> mmc4 */ +static struct omap_hwmod_ocp_if omap44xx_l4_per__mmc4 = { + .master = &omap44xx_l4_per_hwmod, + .slave = &omap44xx_mmc4_hwmod, + .clk = "l4_div_ck", + .addr = omap44xx_mmc4_addrs, + .addr_cnt = ARRAY_SIZE(omap44xx_mmc4_addrs), + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* mmc4 slave ports */ +static struct omap_hwmod_ocp_if *omap44xx_mmc4_slaves[] = { + &omap44xx_l4_per__mmc4, +}; + +static struct omap_hwmod omap44xx_mmc4_hwmod = { + .name = "mmc4", + .class = &omap44xx_mmc_hwmod_class, + .mpu_irqs = omap44xx_mmc4_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap44xx_mmc4_irqs), + .sdma_reqs = omap44xx_mmc4_sdma_reqs, + .sdma_reqs_cnt = ARRAY_SIZE(omap44xx_mmc4_sdma_reqs), + .main_clk = "mmc4_fck", + .prcm = { + .omap4 = { + .clkctrl_reg = OMAP4430_CM_L4PER_MMCSD4_CLKCTRL, + }, + }, + .slaves = omap44xx_mmc4_slaves, + .slaves_cnt = ARRAY_SIZE(omap44xx_mmc4_slaves), + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430), +}; + +/* mmc5 */ +static struct omap_hwmod omap44xx_mmc5_hwmod; +static struct omap_hwmod_irq_info omap44xx_mmc5_irqs[] = { + { .irq = 59 + OMAP44XX_IRQ_GIC_START }, +}; + +static struct omap_hwmod_dma_info omap44xx_mmc5_sdma_reqs[] = { + { .name = "tx", .dma_req = 58 + OMAP44XX_DMA_REQ_START }, + { .name = "rx", .dma_req = 59 + OMAP44XX_DMA_REQ_START }, +}; + +static struct omap_hwmod_addr_space omap44xx_mmc5_addrs[] = { + { + .pa_start = 0x480d5000, + .pa_end = 0x480d53ff, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_per -> mmc5 */ +static struct omap_hwmod_ocp_if omap44xx_l4_per__mmc5 = { + .master = &omap44xx_l4_per_hwmod, + .slave = &omap44xx_mmc5_hwmod, + .clk = "l4_div_ck", + .addr = omap44xx_mmc5_addrs, + .addr_cnt = ARRAY_SIZE(omap44xx_mmc5_addrs), + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* mmc5 slave ports */ +static struct omap_hwmod_ocp_if *omap44xx_mmc5_slaves[] = { + &omap44xx_l4_per__mmc5, +}; + +static struct omap_hwmod omap44xx_mmc5_hwmod = { + .name = "mmc5", + .class = &omap44xx_mmc_hwmod_class, + .mpu_irqs = omap44xx_mmc5_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap44xx_mmc5_irqs), + .sdma_reqs = omap44xx_mmc5_sdma_reqs, + .sdma_reqs_cnt = ARRAY_SIZE(omap44xx_mmc5_sdma_reqs), + .main_clk = "mmc5_fck", + .prcm = { + .omap4 = { + .clkctrl_reg = OMAP4430_CM_L4PER_MMCSD5_CLKCTRL, + }, + }, + .slaves = omap44xx_mmc5_slaves, + .slaves_cnt = ARRAY_SIZE(omap44xx_mmc5_slaves), + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430), +}; + +/* * 'mpu' class * mpu sub-system */ @@ -1639,6 +3913,676 @@ static struct omap_hwmod omap44xx_smartreflex_mpu_hwmod = { }; /* + * 'spinlock' class + * spinlock provides hardware assistance for synchronizing the processes + * running on multiple processors + */ + +static struct omap_hwmod_class_sysconfig omap44xx_spinlock_sysc = { + .rev_offs = 0x0000, + .sysc_offs = 0x0010, + .syss_offs = 0x0014, + .sysc_flags = (SYSC_HAS_AUTOIDLE | SYSC_HAS_CLOCKACTIVITY | + SYSC_HAS_ENAWAKEUP | SYSC_HAS_SIDLEMODE | + SYSC_HAS_SOFTRESET | SYSS_HAS_RESET_STATUS), + .idlemodes = (SIDLE_FORCE | SIDLE_NO | SIDLE_SMART | + SIDLE_SMART_WKUP), + .sysc_fields = &omap_hwmod_sysc_type1, +}; + +static struct omap_hwmod_class omap44xx_spinlock_hwmod_class = { + .name = "spinlock", + .sysc = &omap44xx_spinlock_sysc, +}; + +/* spinlock */ +static struct omap_hwmod omap44xx_spinlock_hwmod; +static struct omap_hwmod_addr_space omap44xx_spinlock_addrs[] = { + { + .pa_start = 0x4a0f6000, + .pa_end = 0x4a0f6fff, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_cfg -> spinlock */ +static struct omap_hwmod_ocp_if omap44xx_l4_cfg__spinlock = { + .master = &omap44xx_l4_cfg_hwmod, + .slave = &omap44xx_spinlock_hwmod, + .clk = "l4_div_ck", + .addr = omap44xx_spinlock_addrs, + .addr_cnt = ARRAY_SIZE(omap44xx_spinlock_addrs), + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* spinlock slave ports */ +static struct omap_hwmod_ocp_if *omap44xx_spinlock_slaves[] = { + &omap44xx_l4_cfg__spinlock, +}; + +static struct omap_hwmod omap44xx_spinlock_hwmod = { + .name = "spinlock", + .class = &omap44xx_spinlock_hwmod_class, + .prcm = { + .omap4 = { + .clkctrl_reg = OMAP4430_CM_L4CFG_HW_SEM_CLKCTRL, + }, + }, + .slaves = omap44xx_spinlock_slaves, + .slaves_cnt = ARRAY_SIZE(omap44xx_spinlock_slaves), + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430), +}; + +/* + * 'timer' class + * general purpose timer module with accurate 1ms tick + * This class contains several variants: ['timer_1ms', 'timer'] + */ + +static struct omap_hwmod_class_sysconfig omap44xx_timer_1ms_sysc = { + .rev_offs = 0x0000, + .sysc_offs = 0x0010, + .syss_offs = 0x0014, + .sysc_flags = (SYSC_HAS_AUTOIDLE | SYSC_HAS_CLOCKACTIVITY | + SYSC_HAS_EMUFREE | SYSC_HAS_ENAWAKEUP | + SYSC_HAS_SIDLEMODE | SYSC_HAS_SOFTRESET | + SYSS_HAS_RESET_STATUS), + .idlemodes = (SIDLE_FORCE | SIDLE_NO | SIDLE_SMART), + .sysc_fields = &omap_hwmod_sysc_type1, +}; + +static struct omap_hwmod_class omap44xx_timer_1ms_hwmod_class = { + .name = "timer", + .sysc = &omap44xx_timer_1ms_sysc, +}; + +static struct omap_hwmod_class_sysconfig omap44xx_timer_sysc = { + .rev_offs = 0x0000, + .sysc_offs = 0x0010, + .sysc_flags = (SYSC_HAS_EMUFREE | SYSC_HAS_RESET_STATUS | + SYSC_HAS_SIDLEMODE | SYSC_HAS_SOFTRESET), + .idlemodes = (SIDLE_FORCE | SIDLE_NO | SIDLE_SMART | + SIDLE_SMART_WKUP), + .sysc_fields = &omap_hwmod_sysc_type2, +}; + +static struct omap_hwmod_class omap44xx_timer_hwmod_class = { + .name = "timer", + .sysc = &omap44xx_timer_sysc, +}; + +/* timer1 */ +static struct omap_hwmod omap44xx_timer1_hwmod; +static struct omap_hwmod_irq_info omap44xx_timer1_irqs[] = { + { .irq = 37 + OMAP44XX_IRQ_GIC_START }, +}; + +static struct omap_hwmod_addr_space omap44xx_timer1_addrs[] = { + { + .pa_start = 0x4a318000, + .pa_end = 0x4a31807f, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_wkup -> timer1 */ +static struct omap_hwmod_ocp_if omap44xx_l4_wkup__timer1 = { + .master = &omap44xx_l4_wkup_hwmod, + .slave = &omap44xx_timer1_hwmod, + .clk = "l4_wkup_clk_mux_ck", + .addr = omap44xx_timer1_addrs, + .addr_cnt = ARRAY_SIZE(omap44xx_timer1_addrs), + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* timer1 slave ports */ +static struct omap_hwmod_ocp_if *omap44xx_timer1_slaves[] = { + &omap44xx_l4_wkup__timer1, +}; + +static struct omap_hwmod omap44xx_timer1_hwmod = { + .name = "timer1", + .class = &omap44xx_timer_1ms_hwmod_class, + .mpu_irqs = omap44xx_timer1_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap44xx_timer1_irqs), + .main_clk = "timer1_fck", + .prcm = { + .omap4 = { + .clkctrl_reg = OMAP4430_CM_WKUP_TIMER1_CLKCTRL, + }, + }, + .slaves = omap44xx_timer1_slaves, + .slaves_cnt = ARRAY_SIZE(omap44xx_timer1_slaves), + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430), +}; + +/* timer2 */ +static struct omap_hwmod omap44xx_timer2_hwmod; +static struct omap_hwmod_irq_info omap44xx_timer2_irqs[] = { + { .irq = 38 + OMAP44XX_IRQ_GIC_START }, +}; + +static struct omap_hwmod_addr_space omap44xx_timer2_addrs[] = { + { + .pa_start = 0x48032000, + .pa_end = 0x4803207f, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_per -> timer2 */ +static struct omap_hwmod_ocp_if omap44xx_l4_per__timer2 = { + .master = &omap44xx_l4_per_hwmod, + .slave = &omap44xx_timer2_hwmod, + .clk = "l4_div_ck", + .addr = omap44xx_timer2_addrs, + .addr_cnt = ARRAY_SIZE(omap44xx_timer2_addrs), + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* timer2 slave ports */ +static struct omap_hwmod_ocp_if *omap44xx_timer2_slaves[] = { + &omap44xx_l4_per__timer2, +}; + +static struct omap_hwmod omap44xx_timer2_hwmod = { + .name = "timer2", + .class = &omap44xx_timer_1ms_hwmod_class, + .mpu_irqs = omap44xx_timer2_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap44xx_timer2_irqs), + .main_clk = "timer2_fck", + .prcm = { + .omap4 = { + .clkctrl_reg = OMAP4430_CM_L4PER_DMTIMER2_CLKCTRL, + }, + }, + .slaves = omap44xx_timer2_slaves, + .slaves_cnt = ARRAY_SIZE(omap44xx_timer2_slaves), + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430), +}; + +/* timer3 */ +static struct omap_hwmod omap44xx_timer3_hwmod; +static struct omap_hwmod_irq_info omap44xx_timer3_irqs[] = { + { .irq = 39 + OMAP44XX_IRQ_GIC_START }, +}; + +static struct omap_hwmod_addr_space omap44xx_timer3_addrs[] = { + { + .pa_start = 0x48034000, + .pa_end = 0x4803407f, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_per -> timer3 */ +static struct omap_hwmod_ocp_if omap44xx_l4_per__timer3 = { + .master = &omap44xx_l4_per_hwmod, + .slave = &omap44xx_timer3_hwmod, + .clk = "l4_div_ck", + .addr = omap44xx_timer3_addrs, + .addr_cnt = ARRAY_SIZE(omap44xx_timer3_addrs), + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* timer3 slave ports */ +static struct omap_hwmod_ocp_if *omap44xx_timer3_slaves[] = { + &omap44xx_l4_per__timer3, +}; + +static struct omap_hwmod omap44xx_timer3_hwmod = { + .name = "timer3", + .class = &omap44xx_timer_hwmod_class, + .mpu_irqs = omap44xx_timer3_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap44xx_timer3_irqs), + .main_clk = "timer3_fck", + .prcm = { + .omap4 = { + .clkctrl_reg = OMAP4430_CM_L4PER_DMTIMER3_CLKCTRL, + }, + }, + .slaves = omap44xx_timer3_slaves, + .slaves_cnt = ARRAY_SIZE(omap44xx_timer3_slaves), + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430), +}; + +/* timer4 */ +static struct omap_hwmod omap44xx_timer4_hwmod; +static struct omap_hwmod_irq_info omap44xx_timer4_irqs[] = { + { .irq = 40 + OMAP44XX_IRQ_GIC_START }, +}; + +static struct omap_hwmod_addr_space omap44xx_timer4_addrs[] = { + { + .pa_start = 0x48036000, + .pa_end = 0x4803607f, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_per -> timer4 */ +static struct omap_hwmod_ocp_if omap44xx_l4_per__timer4 = { + .master = &omap44xx_l4_per_hwmod, + .slave = &omap44xx_timer4_hwmod, + .clk = "l4_div_ck", + .addr = omap44xx_timer4_addrs, + .addr_cnt = ARRAY_SIZE(omap44xx_timer4_addrs), + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* timer4 slave ports */ +static struct omap_hwmod_ocp_if *omap44xx_timer4_slaves[] = { + &omap44xx_l4_per__timer4, +}; + +static struct omap_hwmod omap44xx_timer4_hwmod = { + .name = "timer4", + .class = &omap44xx_timer_hwmod_class, + .mpu_irqs = omap44xx_timer4_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap44xx_timer4_irqs), + .main_clk = "timer4_fck", + .prcm = { + .omap4 = { + .clkctrl_reg = OMAP4430_CM_L4PER_DMTIMER4_CLKCTRL, + }, + }, + .slaves = omap44xx_timer4_slaves, + .slaves_cnt = ARRAY_SIZE(omap44xx_timer4_slaves), + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430), +}; + +/* timer5 */ +static struct omap_hwmod omap44xx_timer5_hwmod; +static struct omap_hwmod_irq_info omap44xx_timer5_irqs[] = { + { .irq = 41 + OMAP44XX_IRQ_GIC_START }, +}; + +static struct omap_hwmod_addr_space omap44xx_timer5_addrs[] = { + { + .pa_start = 0x40138000, + .pa_end = 0x4013807f, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_abe -> timer5 */ +static struct omap_hwmod_ocp_if omap44xx_l4_abe__timer5 = { + .master = &omap44xx_l4_abe_hwmod, + .slave = &omap44xx_timer5_hwmod, + .clk = "ocp_abe_iclk", + .addr = omap44xx_timer5_addrs, + .addr_cnt = ARRAY_SIZE(omap44xx_timer5_addrs), + .user = OCP_USER_MPU, +}; + +static struct omap_hwmod_addr_space omap44xx_timer5_dma_addrs[] = { + { + .pa_start = 0x49038000, + .pa_end = 0x4903807f, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_abe -> timer5 (dma) */ +static struct omap_hwmod_ocp_if omap44xx_l4_abe__timer5_dma = { + .master = &omap44xx_l4_abe_hwmod, + .slave = &omap44xx_timer5_hwmod, + .clk = "ocp_abe_iclk", + .addr = omap44xx_timer5_dma_addrs, + .addr_cnt = ARRAY_SIZE(omap44xx_timer5_dma_addrs), + .user = OCP_USER_SDMA, +}; + +/* timer5 slave ports */ +static struct omap_hwmod_ocp_if *omap44xx_timer5_slaves[] = { + &omap44xx_l4_abe__timer5, + &omap44xx_l4_abe__timer5_dma, +}; + +static struct omap_hwmod omap44xx_timer5_hwmod = { + .name = "timer5", + .class = &omap44xx_timer_hwmod_class, + .mpu_irqs = omap44xx_timer5_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap44xx_timer5_irqs), + .main_clk = "timer5_fck", + .prcm = { + .omap4 = { + .clkctrl_reg = OMAP4430_CM1_ABE_TIMER5_CLKCTRL, + }, + }, + .slaves = omap44xx_timer5_slaves, + .slaves_cnt = ARRAY_SIZE(omap44xx_timer5_slaves), + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430), +}; + +/* timer6 */ +static struct omap_hwmod omap44xx_timer6_hwmod; +static struct omap_hwmod_irq_info omap44xx_timer6_irqs[] = { + { .irq = 42 + OMAP44XX_IRQ_GIC_START }, +}; + +static struct omap_hwmod_addr_space omap44xx_timer6_addrs[] = { + { + .pa_start = 0x4013a000, + .pa_end = 0x4013a07f, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_abe -> timer6 */ +static struct omap_hwmod_ocp_if omap44xx_l4_abe__timer6 = { + .master = &omap44xx_l4_abe_hwmod, + .slave = &omap44xx_timer6_hwmod, + .clk = "ocp_abe_iclk", + .addr = omap44xx_timer6_addrs, + .addr_cnt = ARRAY_SIZE(omap44xx_timer6_addrs), + .user = OCP_USER_MPU, +}; + +static struct omap_hwmod_addr_space omap44xx_timer6_dma_addrs[] = { + { + .pa_start = 0x4903a000, + .pa_end = 0x4903a07f, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_abe -> timer6 (dma) */ +static struct omap_hwmod_ocp_if omap44xx_l4_abe__timer6_dma = { + .master = &omap44xx_l4_abe_hwmod, + .slave = &omap44xx_timer6_hwmod, + .clk = "ocp_abe_iclk", + .addr = omap44xx_timer6_dma_addrs, + .addr_cnt = ARRAY_SIZE(omap44xx_timer6_dma_addrs), + .user = OCP_USER_SDMA, +}; + +/* timer6 slave ports */ +static struct omap_hwmod_ocp_if *omap44xx_timer6_slaves[] = { + &omap44xx_l4_abe__timer6, + &omap44xx_l4_abe__timer6_dma, +}; + +static struct omap_hwmod omap44xx_timer6_hwmod = { + .name = "timer6", + .class = &omap44xx_timer_hwmod_class, + .mpu_irqs = omap44xx_timer6_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap44xx_timer6_irqs), + .main_clk = "timer6_fck", + .prcm = { + .omap4 = { + .clkctrl_reg = OMAP4430_CM1_ABE_TIMER6_CLKCTRL, + }, + }, + .slaves = omap44xx_timer6_slaves, + .slaves_cnt = ARRAY_SIZE(omap44xx_timer6_slaves), + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430), +}; + +/* timer7 */ +static struct omap_hwmod omap44xx_timer7_hwmod; +static struct omap_hwmod_irq_info omap44xx_timer7_irqs[] = { + { .irq = 43 + OMAP44XX_IRQ_GIC_START }, +}; + +static struct omap_hwmod_addr_space omap44xx_timer7_addrs[] = { + { + .pa_start = 0x4013c000, + .pa_end = 0x4013c07f, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_abe -> timer7 */ +static struct omap_hwmod_ocp_if omap44xx_l4_abe__timer7 = { + .master = &omap44xx_l4_abe_hwmod, + .slave = &omap44xx_timer7_hwmod, + .clk = "ocp_abe_iclk", + .addr = omap44xx_timer7_addrs, + .addr_cnt = ARRAY_SIZE(omap44xx_timer7_addrs), + .user = OCP_USER_MPU, +}; + +static struct omap_hwmod_addr_space omap44xx_timer7_dma_addrs[] = { + { + .pa_start = 0x4903c000, + .pa_end = 0x4903c07f, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_abe -> timer7 (dma) */ +static struct omap_hwmod_ocp_if omap44xx_l4_abe__timer7_dma = { + .master = &omap44xx_l4_abe_hwmod, + .slave = &omap44xx_timer7_hwmod, + .clk = "ocp_abe_iclk", + .addr = omap44xx_timer7_dma_addrs, + .addr_cnt = ARRAY_SIZE(omap44xx_timer7_dma_addrs), + .user = OCP_USER_SDMA, +}; + +/* timer7 slave ports */ +static struct omap_hwmod_ocp_if *omap44xx_timer7_slaves[] = { + &omap44xx_l4_abe__timer7, + &omap44xx_l4_abe__timer7_dma, +}; + +static struct omap_hwmod omap44xx_timer7_hwmod = { + .name = "timer7", + .class = &omap44xx_timer_hwmod_class, + .mpu_irqs = omap44xx_timer7_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap44xx_timer7_irqs), + .main_clk = "timer7_fck", + .prcm = { + .omap4 = { + .clkctrl_reg = OMAP4430_CM1_ABE_TIMER7_CLKCTRL, + }, + }, + .slaves = omap44xx_timer7_slaves, + .slaves_cnt = ARRAY_SIZE(omap44xx_timer7_slaves), + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430), +}; + +/* timer8 */ +static struct omap_hwmod omap44xx_timer8_hwmod; +static struct omap_hwmod_irq_info omap44xx_timer8_irqs[] = { + { .irq = 44 + OMAP44XX_IRQ_GIC_START }, +}; + +static struct omap_hwmod_addr_space omap44xx_timer8_addrs[] = { + { + .pa_start = 0x4013e000, + .pa_end = 0x4013e07f, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_abe -> timer8 */ +static struct omap_hwmod_ocp_if omap44xx_l4_abe__timer8 = { + .master = &omap44xx_l4_abe_hwmod, + .slave = &omap44xx_timer8_hwmod, + .clk = "ocp_abe_iclk", + .addr = omap44xx_timer8_addrs, + .addr_cnt = ARRAY_SIZE(omap44xx_timer8_addrs), + .user = OCP_USER_MPU, +}; + +static struct omap_hwmod_addr_space omap44xx_timer8_dma_addrs[] = { + { + .pa_start = 0x4903e000, + .pa_end = 0x4903e07f, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_abe -> timer8 (dma) */ +static struct omap_hwmod_ocp_if omap44xx_l4_abe__timer8_dma = { + .master = &omap44xx_l4_abe_hwmod, + .slave = &omap44xx_timer8_hwmod, + .clk = "ocp_abe_iclk", + .addr = omap44xx_timer8_dma_addrs, + .addr_cnt = ARRAY_SIZE(omap44xx_timer8_dma_addrs), + .user = OCP_USER_SDMA, +}; + +/* timer8 slave ports */ +static struct omap_hwmod_ocp_if *omap44xx_timer8_slaves[] = { + &omap44xx_l4_abe__timer8, + &omap44xx_l4_abe__timer8_dma, +}; + +static struct omap_hwmod omap44xx_timer8_hwmod = { + .name = "timer8", + .class = &omap44xx_timer_hwmod_class, + .mpu_irqs = omap44xx_timer8_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap44xx_timer8_irqs), + .main_clk = "timer8_fck", + .prcm = { + .omap4 = { + .clkctrl_reg = OMAP4430_CM1_ABE_TIMER8_CLKCTRL, + }, + }, + .slaves = omap44xx_timer8_slaves, + .slaves_cnt = ARRAY_SIZE(omap44xx_timer8_slaves), + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430), +}; + +/* timer9 */ +static struct omap_hwmod omap44xx_timer9_hwmod; +static struct omap_hwmod_irq_info omap44xx_timer9_irqs[] = { + { .irq = 45 + OMAP44XX_IRQ_GIC_START }, +}; + +static struct omap_hwmod_addr_space omap44xx_timer9_addrs[] = { + { + .pa_start = 0x4803e000, + .pa_end = 0x4803e07f, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_per -> timer9 */ +static struct omap_hwmod_ocp_if omap44xx_l4_per__timer9 = { + .master = &omap44xx_l4_per_hwmod, + .slave = &omap44xx_timer9_hwmod, + .clk = "l4_div_ck", + .addr = omap44xx_timer9_addrs, + .addr_cnt = ARRAY_SIZE(omap44xx_timer9_addrs), + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* timer9 slave ports */ +static struct omap_hwmod_ocp_if *omap44xx_timer9_slaves[] = { + &omap44xx_l4_per__timer9, +}; + +static struct omap_hwmod omap44xx_timer9_hwmod = { + .name = "timer9", + .class = &omap44xx_timer_hwmod_class, + .mpu_irqs = omap44xx_timer9_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap44xx_timer9_irqs), + .main_clk = "timer9_fck", + .prcm = { + .omap4 = { + .clkctrl_reg = OMAP4430_CM_L4PER_DMTIMER9_CLKCTRL, + }, + }, + .slaves = omap44xx_timer9_slaves, + .slaves_cnt = ARRAY_SIZE(omap44xx_timer9_slaves), + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430), +}; + +/* timer10 */ +static struct omap_hwmod omap44xx_timer10_hwmod; +static struct omap_hwmod_irq_info omap44xx_timer10_irqs[] = { + { .irq = 46 + OMAP44XX_IRQ_GIC_START }, +}; + +static struct omap_hwmod_addr_space omap44xx_timer10_addrs[] = { + { + .pa_start = 0x48086000, + .pa_end = 0x4808607f, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_per -> timer10 */ +static struct omap_hwmod_ocp_if omap44xx_l4_per__timer10 = { + .master = &omap44xx_l4_per_hwmod, + .slave = &omap44xx_timer10_hwmod, + .clk = "l4_div_ck", + .addr = omap44xx_timer10_addrs, + .addr_cnt = ARRAY_SIZE(omap44xx_timer10_addrs), + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* timer10 slave ports */ +static struct omap_hwmod_ocp_if *omap44xx_timer10_slaves[] = { + &omap44xx_l4_per__timer10, +}; + +static struct omap_hwmod omap44xx_timer10_hwmod = { + .name = "timer10", + .class = &omap44xx_timer_1ms_hwmod_class, + .mpu_irqs = omap44xx_timer10_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap44xx_timer10_irqs), + .main_clk = "timer10_fck", + .prcm = { + .omap4 = { + .clkctrl_reg = OMAP4430_CM_L4PER_DMTIMER10_CLKCTRL, + }, + }, + .slaves = omap44xx_timer10_slaves, + .slaves_cnt = ARRAY_SIZE(omap44xx_timer10_slaves), + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430), +}; + +/* timer11 */ +static struct omap_hwmod omap44xx_timer11_hwmod; +static struct omap_hwmod_irq_info omap44xx_timer11_irqs[] = { + { .irq = 47 + OMAP44XX_IRQ_GIC_START }, +}; + +static struct omap_hwmod_addr_space omap44xx_timer11_addrs[] = { + { + .pa_start = 0x48088000, + .pa_end = 0x4808807f, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_per -> timer11 */ +static struct omap_hwmod_ocp_if omap44xx_l4_per__timer11 = { + .master = &omap44xx_l4_per_hwmod, + .slave = &omap44xx_timer11_hwmod, + .clk = "l4_div_ck", + .addr = omap44xx_timer11_addrs, + .addr_cnt = ARRAY_SIZE(omap44xx_timer11_addrs), + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* timer11 slave ports */ +static struct omap_hwmod_ocp_if *omap44xx_timer11_slaves[] = { + &omap44xx_l4_per__timer11, +}; + +static struct omap_hwmod omap44xx_timer11_hwmod = { + .name = "timer11", + .class = &omap44xx_timer_hwmod_class, + .mpu_irqs = omap44xx_timer11_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap44xx_timer11_irqs), + .main_clk = "timer11_fck", + .prcm = { + .omap4 = { + .clkctrl_reg = OMAP4430_CM_L4PER_DMTIMER11_CLKCTRL, + }, + }, + .slaves = omap44xx_timer11_slaves, + .slaves_cnt = ARRAY_SIZE(omap44xx_timer11_slaves), + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430), +}; + +/* * 'uart' class * universal asynchronous receiver/transmitter (uart) */ @@ -1870,6 +4814,88 @@ static struct omap_hwmod omap44xx_uart4_hwmod = { }; /* + * 'usb_otg_hs' class + * high-speed on-the-go universal serial bus (usb_otg_hs) controller + */ + +static struct omap_hwmod_class_sysconfig omap44xx_usb_otg_hs_sysc = { + .rev_offs = 0x0400, + .sysc_offs = 0x0404, + .syss_offs = 0x0408, + .sysc_flags = (SYSC_HAS_AUTOIDLE | SYSC_HAS_ENAWAKEUP | + SYSC_HAS_MIDLEMODE | SYSC_HAS_SIDLEMODE | + SYSC_HAS_SOFTRESET | SYSS_HAS_RESET_STATUS), + .idlemodes = (SIDLE_FORCE | SIDLE_NO | SIDLE_SMART | + SIDLE_SMART_WKUP | MSTANDBY_FORCE | MSTANDBY_NO | + MSTANDBY_SMART), + .sysc_fields = &omap_hwmod_sysc_type1, +}; + +static struct omap_hwmod_class omap44xx_usb_otg_hs_hwmod_class = { + .name = "usb_otg_hs", + .sysc = &omap44xx_usb_otg_hs_sysc, +}; + +/* usb_otg_hs */ +static struct omap_hwmod_irq_info omap44xx_usb_otg_hs_irqs[] = { + { .name = "mc", .irq = 92 + OMAP44XX_IRQ_GIC_START }, + { .name = "dma", .irq = 93 + OMAP44XX_IRQ_GIC_START }, +}; + +/* usb_otg_hs master ports */ +static struct omap_hwmod_ocp_if *omap44xx_usb_otg_hs_masters[] = { + &omap44xx_usb_otg_hs__l3_main_2, +}; + +static struct omap_hwmod_addr_space omap44xx_usb_otg_hs_addrs[] = { + { + .pa_start = 0x4a0ab000, + .pa_end = 0x4a0ab003, + .flags = ADDR_TYPE_RT + }, +}; + +/* l4_cfg -> usb_otg_hs */ +static struct omap_hwmod_ocp_if omap44xx_l4_cfg__usb_otg_hs = { + .master = &omap44xx_l4_cfg_hwmod, + .slave = &omap44xx_usb_otg_hs_hwmod, + .clk = "l4_div_ck", + .addr = omap44xx_usb_otg_hs_addrs, + .addr_cnt = ARRAY_SIZE(omap44xx_usb_otg_hs_addrs), + .user = OCP_USER_MPU | OCP_USER_SDMA, +}; + +/* usb_otg_hs slave ports */ +static struct omap_hwmod_ocp_if *omap44xx_usb_otg_hs_slaves[] = { + &omap44xx_l4_cfg__usb_otg_hs, +}; + +static struct omap_hwmod_opt_clk usb_otg_hs_opt_clks[] = { + { .role = "xclk", .clk = "usb_otg_hs_xclk" }, +}; + +static struct omap_hwmod omap44xx_usb_otg_hs_hwmod = { + .name = "usb_otg_hs", + .class = &omap44xx_usb_otg_hs_hwmod_class, + .flags = HWMOD_SWSUP_SIDLE | HWMOD_SWSUP_MSTANDBY, + .mpu_irqs = omap44xx_usb_otg_hs_irqs, + .mpu_irqs_cnt = ARRAY_SIZE(omap44xx_usb_otg_hs_irqs), + .main_clk = "usb_otg_hs_ick", + .prcm = { + .omap4 = { + .clkctrl_reg = OMAP4430_CM_L3INIT_USB_OTG_CLKCTRL, + }, + }, + .opt_clks = usb_otg_hs_opt_clks, + .opt_clks_cnt = ARRAY_SIZE(usb_otg_hs_opt_clks), + .slaves = omap44xx_usb_otg_hs_slaves, + .slaves_cnt = ARRAY_SIZE(omap44xx_usb_otg_hs_slaves), + .masters = omap44xx_usb_otg_hs_masters, + .masters_cnt = ARRAY_SIZE(omap44xx_usb_otg_hs_masters), + .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430), +}; + +/* * 'wd_timer' class * 32-bit watchdog upward counter that generates a pulse on the reset pin on * overflow condition @@ -2024,13 +5050,34 @@ static __initdata struct omap_hwmod *omap44xx_hwmods[] = { /* mpu_bus class */ &omap44xx_mpu_private_hwmod, + /* aess class */ +/* &omap44xx_aess_hwmod, */ + + /* bandgap class */ + &omap44xx_bandgap_hwmod, + + /* counter class */ +/* &omap44xx_counter_32k_hwmod, */ + /* dma class */ &omap44xx_dma_system_hwmod, + /* dmic class */ + &omap44xx_dmic_hwmod, + /* dsp class */ &omap44xx_dsp_hwmod, &omap44xx_dsp_c0_hwmod, + /* dss class */ + &omap44xx_dss_hwmod, + &omap44xx_dss_dispc_hwmod, + &omap44xx_dss_dsi1_hwmod, + &omap44xx_dss_dsi2_hwmod, + &omap44xx_dss_hdmi_hwmod, + &omap44xx_dss_rfbi_hwmod, + &omap44xx_dss_venc_hwmod, + /* gpio class */ &omap44xx_gpio1_hwmod, &omap44xx_gpio2_hwmod, @@ -2039,17 +5086,56 @@ static __initdata struct omap_hwmod *omap44xx_hwmods[] = { &omap44xx_gpio5_hwmod, &omap44xx_gpio6_hwmod, + /* hsi class */ +/* &omap44xx_hsi_hwmod, */ + /* i2c class */ &omap44xx_i2c1_hwmod, &omap44xx_i2c2_hwmod, &omap44xx_i2c3_hwmod, &omap44xx_i2c4_hwmod, + /* ipu class */ + &omap44xx_ipu_hwmod, + &omap44xx_ipu_c0_hwmod, + &omap44xx_ipu_c1_hwmod, + + /* iss class */ +/* &omap44xx_iss_hwmod, */ + /* iva class */ &omap44xx_iva_hwmod, &omap44xx_iva_seq0_hwmod, &omap44xx_iva_seq1_hwmod, + /* kbd class */ +/* &omap44xx_kbd_hwmod, */ + + /* mailbox class */ + &omap44xx_mailbox_hwmod, + + /* mcbsp class */ + &omap44xx_mcbsp1_hwmod, + &omap44xx_mcbsp2_hwmod, + &omap44xx_mcbsp3_hwmod, + &omap44xx_mcbsp4_hwmod, + + /* mcpdm class */ +/* &omap44xx_mcpdm_hwmod, */ + + /* mcspi class */ + &omap44xx_mcspi1_hwmod, + &omap44xx_mcspi2_hwmod, + &omap44xx_mcspi3_hwmod, + &omap44xx_mcspi4_hwmod, + + /* mmc class */ + &omap44xx_mmc1_hwmod, + &omap44xx_mmc2_hwmod, + &omap44xx_mmc3_hwmod, + &omap44xx_mmc4_hwmod, + &omap44xx_mmc5_hwmod, + /* mpu class */ &omap44xx_mpu_hwmod, @@ -2058,12 +5144,31 @@ static __initdata struct omap_hwmod *omap44xx_hwmods[] = { &omap44xx_smartreflex_iva_hwmod, &omap44xx_smartreflex_mpu_hwmod, + /* spinlock class */ + &omap44xx_spinlock_hwmod, + + /* timer class */ + &omap44xx_timer1_hwmod, + &omap44xx_timer2_hwmod, + &omap44xx_timer3_hwmod, + &omap44xx_timer4_hwmod, + &omap44xx_timer5_hwmod, + &omap44xx_timer6_hwmod, + &omap44xx_timer7_hwmod, + &omap44xx_timer8_hwmod, + &omap44xx_timer9_hwmod, + &omap44xx_timer10_hwmod, + &omap44xx_timer11_hwmod, + /* uart class */ &omap44xx_uart1_hwmod, &omap44xx_uart2_hwmod, &omap44xx_uart3_hwmod, &omap44xx_uart4_hwmod, + /* usb_otg_hs class */ + &omap44xx_usb_otg_hs_hwmod, + /* wd_timer class */ &omap44xx_wd_timer2_hwmod, &omap44xx_wd_timer3_hwmod, @@ -2073,6 +5178,6 @@ static __initdata struct omap_hwmod *omap44xx_hwmods[] = { int __init omap44xx_hwmod_init(void) { - return omap_hwmod_init(omap44xx_hwmods); + return omap_hwmod_register(omap44xx_hwmods); } diff --git a/arch/arm/mach-omap2/omap_l3_noc.c b/arch/arm/mach-omap2/omap_l3_noc.c new file mode 100644 index 00000000000..82632c24076 --- /dev/null +++ b/arch/arm/mach-omap2/omap_l3_noc.c @@ -0,0 +1,253 @@ +/* + * OMAP4XXX L3 Interconnect error handling driver + * + * Copyright (C) 2011 Texas Corporation + * Santosh Shilimkar <santosh.shilimkar@ti.com> + * Sricharan <r.sricharan@ti.com> + * + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program; if not, write to the Free Software + * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 + * USA + */ +#include <linux/init.h> +#include <linux/io.h> +#include <linux/platform_device.h> +#include <linux/interrupt.h> +#include <linux/kernel.h> +#include <linux/slab.h> + +#include "omap_l3_noc.h" + +/* + * Interrupt Handler for L3 error detection. + * 1) Identify the L3 clockdomain partition to which the error belongs to. + * 2) Identify the slave where the error information is logged + * 3) Print the logged information. + * 4) Add dump stack to provide kernel trace. + * + * Two Types of errors : + * 1) Custom errors in L3 : + * Target like DMM/FW/EMIF generates SRESP=ERR error + * 2) Standard L3 error: + * - Unsupported CMD. + * L3 tries to access target while it is idle + * - OCP disconnect. + * - Address hole error: + * If DSS/ISS/FDIF/USBHOSTFS access a target where they + * do not have connectivity, the error is logged in + * their default target which is DMM2. + * + * On High Secure devices, firewall errors are possible and those + * can be trapped as well. But the trapping is implemented as part + * secure software and hence need not be implemented here. + */ +static irqreturn_t l3_interrupt_handler(int irq, void *_l3) +{ + + struct omap4_l3 *l3 = _l3; + int inttype, i, j; + int err_src = 0; + u32 std_err_main_addr, std_err_main, err_reg; + u32 base, slave_addr, clear; + char *source_name; + + /* Get the Type of interrupt */ + if (irq == l3->app_irq) + inttype = L3_APPLICATION_ERROR; + else + inttype = L3_DEBUG_ERROR; + + for (i = 0; i < L3_MODULES; i++) { + /* + * Read the regerr register of the clock domain + * to determine the source + */ + base = (u32)l3->l3_base[i]; + err_reg = readl(base + l3_flagmux[i] + (inttype << 3)); + + /* Get the corresponding error and analyse */ + if (err_reg) { + /* Identify the source from control status register */ + for (j = 0; !(err_reg & (1 << j)); j++) + ; + + err_src = j; + /* Read the stderrlog_main_source from clk domain */ + std_err_main_addr = base + (*(l3_targ[i] + err_src)); + std_err_main = readl(std_err_main_addr); + + switch ((std_err_main & CUSTOM_ERROR)) { + case STANDARD_ERROR: + source_name = + l3_targ_stderrlog_main_name[i][err_src]; + + slave_addr = std_err_main_addr + + L3_SLAVE_ADDRESS_OFFSET; + WARN(true, "L3 standard error: SOURCE:%s at address 0x%x\n", + source_name, readl(slave_addr)); + /* clear the std error log*/ + clear = std_err_main | CLEAR_STDERR_LOG; + writel(clear, std_err_main_addr); + break; + + case CUSTOM_ERROR: + source_name = + l3_targ_stderrlog_main_name[i][err_src]; + + WARN(true, "CUSTOM SRESP error with SOURCE:%s\n", + source_name); + /* clear the std error log*/ + clear = std_err_main | CLEAR_STDERR_LOG; + writel(clear, std_err_main_addr); + break; + + default: + /* Nothing to be handled here as of now */ + break; + } + /* Error found so break the for loop */ + break; + } + } + return IRQ_HANDLED; +} + +static int __init omap4_l3_probe(struct platform_device *pdev) +{ + static struct omap4_l3 *l3; + struct resource *res; + int ret; + int irq; + + l3 = kzalloc(sizeof(*l3), GFP_KERNEL); + if (!l3) + ret = -ENOMEM; + + platform_set_drvdata(pdev, l3); + res = platform_get_resource(pdev, IORESOURCE_MEM, 0); + if (!res) { + dev_err(&pdev->dev, "couldn't find resource 0\n"); + ret = -ENODEV; + goto err1; + } + + l3->l3_base[0] = ioremap(res->start, resource_size(res)); + if (!(l3->l3_base[0])) { + dev_err(&pdev->dev, "ioremap failed\n"); + ret = -ENOMEM; + goto err2; + } + + res = platform_get_resource(pdev, IORESOURCE_MEM, 1); + if (!res) { + dev_err(&pdev->dev, "couldn't find resource 1\n"); + ret = -ENODEV; + goto err3; + } + + l3->l3_base[1] = ioremap(res->start, resource_size(res)); + if (!(l3->l3_base[1])) { + dev_err(&pdev->dev, "ioremap failed\n"); + ret = -ENOMEM; + goto err4; + } + + res = platform_get_resource(pdev, IORESOURCE_MEM, 2); + if (!res) { + dev_err(&pdev->dev, "couldn't find resource 2\n"); + ret = -ENODEV; + goto err5; + } + + l3->l3_base[2] = ioremap(res->start, resource_size(res)); + if (!(l3->l3_base[2])) { + dev_err(&pdev->dev, "ioremap failed\n"); + ret = -ENOMEM; + goto err6; + } + + /* + * Setup interrupt Handlers + */ + irq = platform_get_irq(pdev, 0); + ret = request_irq(irq, + l3_interrupt_handler, + IRQF_DISABLED, "l3-dbg-irq", l3); + if (ret) { + pr_crit("L3: request_irq failed to register for 0x%x\n", + OMAP44XX_IRQ_L3_DBG); + goto err7; + } + l3->debug_irq = irq; + + irq = platform_get_irq(pdev, 1); + ret = request_irq(irq, + l3_interrupt_handler, + IRQF_DISABLED, "l3-app-irq", l3); + if (ret) { + pr_crit("L3: request_irq failed to register for 0x%x\n", + OMAP44XX_IRQ_L3_APP); + goto err8; + } + l3->app_irq = irq; + + goto err0; +err8: +err7: + iounmap(l3->l3_base[2]); +err6: +err5: + iounmap(l3->l3_base[1]); +err4: +err3: + iounmap(l3->l3_base[0]); +err2: +err1: + kfree(l3); +err0: + return ret; +} + +static int __exit omap4_l3_remove(struct platform_device *pdev) +{ + struct omap4_l3 *l3 = platform_get_drvdata(pdev); + + free_irq(l3->app_irq, l3); + free_irq(l3->debug_irq, l3); + iounmap(l3->l3_base[0]); + iounmap(l3->l3_base[1]); + iounmap(l3->l3_base[2]); + kfree(l3); + + return 0; +} + +static struct platform_driver omap4_l3_driver = { + .remove = __exit_p(omap4_l3_remove), + .driver = { + .name = "omap_l3_noc", + }, +}; + +static int __init omap4_l3_init(void) +{ + return platform_driver_probe(&omap4_l3_driver, omap4_l3_probe); +} +postcore_initcall_sync(omap4_l3_init); + +static void __exit omap4_l3_exit(void) +{ + platform_driver_unregister(&omap4_l3_driver); +} +module_exit(omap4_l3_exit); diff --git a/arch/arm/mach-omap2/omap_l3_noc.h b/arch/arm/mach-omap2/omap_l3_noc.h new file mode 100644 index 00000000000..359b83348ae --- /dev/null +++ b/arch/arm/mach-omap2/omap_l3_noc.h @@ -0,0 +1,132 @@ + /* + * OMAP4XXX L3 Interconnect error handling driver header + * + * Copyright (C) 2011 Texas Corporation + * Santosh Shilimkar <santosh.shilimkar@ti.com> + * sricharan <r.sricharan@ti.com> + * + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program; if not, write to the Free Software + * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 + * USA + */ +#ifndef __ARCH_ARM_MACH_OMAP2_L3_INTERCONNECT_3XXX_H +#define __ARCH_ARM_MACH_OMAP2_L3_INTERCONNECT_3XXX_H + +/* + * L3 register offsets + */ +#define L3_MODULES 3 +#define CLEAR_STDERR_LOG (1 << 31) +#define CUSTOM_ERROR 0x2 +#define STANDARD_ERROR 0x0 +#define INBAND_ERROR 0x0 +#define EMIF_KERRLOG_OFFSET 0x10 +#define L3_SLAVE_ADDRESS_OFFSET 0x14 +#define LOGICAL_ADDR_ERRORLOG 0x4 +#define L3_APPLICATION_ERROR 0x0 +#define L3_DEBUG_ERROR 0x1 + +u32 l3_flagmux[L3_MODULES] = { + 0x50C, + 0x100C, + 0X020C +}; + +/* + * L3 Target standard Error register offsets + */ +u32 l3_targ_stderrlog_main_clk1[] = { + 0x148, /* DMM1 */ + 0x248, /* DMM2 */ + 0x348, /* ABE */ + 0x448, /* L4CFG */ + 0x648 /* CLK2 PWR DISC */ +}; + +u32 l3_targ_stderrlog_main_clk2[] = { + 0x548, /* CORTEX M3 */ + 0x348, /* DSS */ + 0x148, /* GPMC */ + 0x448, /* ISS */ + 0x748, /* IVAHD */ + 0xD48, /* missing in TRM corresponds to AES1*/ + 0x948, /* L4 PER0*/ + 0x248, /* OCMRAM */ + 0x148, /* missing in TRM corresponds to GPMC sERROR*/ + 0x648, /* SGX */ + 0x848, /* SL2 */ + 0x1648, /* C2C */ + 0x1148, /* missing in TRM corresponds PWR DISC CLK1*/ + 0xF48, /* missing in TRM corrsponds to SHA1*/ + 0xE48, /* missing in TRM corresponds to AES2*/ + 0xC48, /* L4 PER3 */ + 0xA48, /* L4 PER1*/ + 0xB48 /* L4 PER2*/ +}; + +u32 l3_targ_stderrlog_main_clk3[] = { + 0x0148 /* EMUSS */ +}; + +char *l3_targ_stderrlog_main_name[L3_MODULES][18] = { + { + "DMM1", + "DMM2", + "ABE", + "L4CFG", + "CLK2 PWR DISC", + }, + { + "CORTEX M3" , + "DSS ", + "GPMC ", + "ISS ", + "IVAHD ", + "AES1", + "L4 PER0", + "OCMRAM ", + "GPMC sERROR", + "SGX ", + "SL2 ", + "C2C ", + "PWR DISC CLK1", + "SHA1", + "AES2", + "L4 PER3", + "L4 PER1", + "L4 PER2", + }, + { + "EMUSS", + }, +}; + +u32 *l3_targ[L3_MODULES] = { + l3_targ_stderrlog_main_clk1, + l3_targ_stderrlog_main_clk2, + l3_targ_stderrlog_main_clk3, +}; + +struct omap4_l3 { + struct device *dev; + struct clk *ick; + + /* memory base */ + void __iomem *l3_base[4]; + + int debug_irq; + int app_irq; +}; + +#endif diff --git a/arch/arm/mach-omap2/omap_l3_smx.c b/arch/arm/mach-omap2/omap_l3_smx.c new file mode 100644 index 00000000000..265bff3acb9 --- /dev/null +++ b/arch/arm/mach-omap2/omap_l3_smx.c @@ -0,0 +1,314 @@ + /* + * OMAP3XXX L3 Interconnect Driver + * + * Copyright (C) 2011 Texas Corporation + * Felipe Balbi <balbi@ti.com> + * Santosh Shilimkar <santosh.shilimkar@ti.com> + * Sricharan <r.sricharan@ti.com> + * + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program; if not, write to the Free Software + * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 + * USA + */ + +#include <linux/kernel.h> +#include <linux/slab.h> +#include <linux/platform_device.h> +#include <linux/interrupt.h> +#include <linux/io.h> +#include "omap_l3_smx.h" + +static inline u64 omap3_l3_readll(void __iomem *base, u16 reg) +{ + return __raw_readll(base + reg); +} + +static inline void omap3_l3_writell(void __iomem *base, u16 reg, u64 value) +{ + __raw_writell(value, base + reg); +} + +static inline enum omap3_l3_code omap3_l3_decode_error_code(u64 error) +{ + return (error & 0x0f000000) >> L3_ERROR_LOG_CODE; +} + +static inline u32 omap3_l3_decode_addr(u64 error_addr) +{ + return error_addr & 0xffffffff; +} + +static inline unsigned omap3_l3_decode_cmd(u64 error) +{ + return (error & 0x07) >> L3_ERROR_LOG_CMD; +} + +static inline enum omap3_l3_initiator_id omap3_l3_decode_initid(u64 error) +{ + return (error & 0xff00) >> L3_ERROR_LOG_INITID; +} + +static inline unsigned omap3_l3_decode_req_info(u64 error) +{ + return (error >> 32) & 0xffff; +} + +static char *omap3_l3_code_string(u8 code) +{ + switch (code) { + case OMAP_L3_CODE_NOERROR: + return "No Error"; + case OMAP_L3_CODE_UNSUP_CMD: + return "Unsupported Command"; + case OMAP_L3_CODE_ADDR_HOLE: + return "Address Hole"; + case OMAP_L3_CODE_PROTECT_VIOLATION: + return "Protection Violation"; + case OMAP_L3_CODE_IN_BAND_ERR: + return "In-band Error"; + case OMAP_L3_CODE_REQ_TOUT_NOT_ACCEPT: + return "Request Timeout Not Accepted"; + case OMAP_L3_CODE_REQ_TOUT_NO_RESP: + return "Request Timeout, no response"; + default: + return "UNKNOWN error"; + } +} + +static char *omap3_l3_initiator_string(u8 initid) +{ + switch (initid) { + case OMAP_L3_LCD: + return "LCD"; + case OMAP_L3_SAD2D: + return "SAD2D"; + case OMAP_L3_IA_MPU_SS_1: + case OMAP_L3_IA_MPU_SS_2: + case OMAP_L3_IA_MPU_SS_3: + case OMAP_L3_IA_MPU_SS_4: + case OMAP_L3_IA_MPU_SS_5: + return "MPU"; + case OMAP_L3_IA_IVA_SS_1: + case OMAP_L3_IA_IVA_SS_2: + case OMAP_L3_IA_IVA_SS_3: + return "IVA_SS"; + case OMAP_L3_IA_IVA_SS_DMA_1: + case OMAP_L3_IA_IVA_SS_DMA_2: + case OMAP_L3_IA_IVA_SS_DMA_3: + case OMAP_L3_IA_IVA_SS_DMA_4: + case OMAP_L3_IA_IVA_SS_DMA_5: + case OMAP_L3_IA_IVA_SS_DMA_6: + return "IVA_SS_DMA"; + case OMAP_L3_IA_SGX: + return "SGX"; + case OMAP_L3_IA_CAM_1: + case OMAP_L3_IA_CAM_2: + case OMAP_L3_IA_CAM_3: + return "CAM"; + case OMAP_L3_IA_DAP: + return "DAP"; + case OMAP_L3_SDMA_WR_1: + case OMAP_L3_SDMA_WR_2: + return "SDMA_WR"; + case OMAP_L3_SDMA_RD_1: + case OMAP_L3_SDMA_RD_2: + case OMAP_L3_SDMA_RD_3: + case OMAP_L3_SDMA_RD_4: + return "SDMA_RD"; + case OMAP_L3_USBOTG: + return "USB_OTG"; + case OMAP_L3_USBHOST: + return "USB_HOST"; + default: + return "UNKNOWN Initiator"; + } +} + +/** + * omap3_l3_block_irq - handles a register block's irq + * @l3: struct omap3_l3 * + * @base: register block base address + * @error: L3_ERROR_LOG register of our block + * + * Called in hard-irq context. Caller should take care of locking + * + * OMAP36xx TRM gives, on page 2001, Figure 9-10, the Typical Error + * Analysis Sequence, we are following that sequence here, please + * refer to that Figure for more information on the subject. + */ +static irqreturn_t omap3_l3_block_irq(struct omap3_l3 *l3, + u64 error, int error_addr) +{ + u8 code = omap3_l3_decode_error_code(error); + u8 initid = omap3_l3_decode_initid(error); + u8 multi = error & L3_ERROR_LOG_MULTI; + u32 address = omap3_l3_decode_addr(error_addr); + + WARN(true, "%s Error seen by %s %s at address %x\n", + omap3_l3_code_string(code), + omap3_l3_initiator_string(initid), + multi ? "Multiple Errors" : "", + address); + + return IRQ_HANDLED; +} + +static irqreturn_t omap3_l3_app_irq(int irq, void *_l3) +{ + struct omap3_l3 *l3 = _l3; + + u64 status, clear; + u64 error; + u64 error_addr; + u64 err_source = 0; + void __iomem *base; + int int_type; + + irqreturn_t ret = IRQ_NONE; + + if (irq == l3->app_irq) + int_type = L3_APPLICATION_ERROR; + else + int_type = L3_DEBUG_ERROR; + + if (!int_type) { + status = omap3_l3_readll(l3->rt, L3_SI_FLAG_STATUS_0); + /* + * if we have a timeout error, there's nothing we can + * do besides rebooting the board. So let's BUG on any + * of such errors and handle the others. timeout error + * is severe and not expected to occur. + */ + BUG_ON(status & L3_STATUS_0_TIMEOUT_MASK); + } else { + status = omap3_l3_readll(l3->rt, L3_SI_FLAG_STATUS_1); + /* No timeout error for debug sources */ + } + + base = ((l3->rt) + (*(omap3_l3_bases[int_type] + err_source))); + + /* identify the error source */ + for (err_source = 0; !(status & (1 << err_source)); err_source++) + ; + error = omap3_l3_readll(base, L3_ERROR_LOG); + + if (error) { + error_addr = omap3_l3_readll(base, L3_ERROR_LOG_ADDR); + + ret |= omap3_l3_block_irq(l3, error, error_addr); + } + + /* Clear the status register */ + clear = ((L3_AGENT_STATUS_CLEAR_IA << int_type) | + (L3_AGENT_STATUS_CLEAR_TA)); + + omap3_l3_writell(base, L3_AGENT_STATUS, clear); + + /* clear the error log register */ + omap3_l3_writell(base, L3_ERROR_LOG, error); + + return ret; +} + +static int __init omap3_l3_probe(struct platform_device *pdev) +{ + struct omap3_l3 *l3; + struct resource *res; + int ret; + int irq; + + l3 = kzalloc(sizeof(*l3), GFP_KERNEL); + if (!l3) { + ret = -ENOMEM; + goto err0; + } + + platform_set_drvdata(pdev, l3); + + res = platform_get_resource(pdev, IORESOURCE_MEM, 0); + if (!res) { + dev_err(&pdev->dev, "couldn't find resource\n"); + ret = -ENODEV; + goto err1; + } + l3->rt = ioremap(res->start, resource_size(res)); + if (!(l3->rt)) { + dev_err(&pdev->dev, "ioremap failed\n"); + ret = -ENOMEM; + goto err2; + } + + irq = platform_get_irq(pdev, 0); + ret = request_irq(irq, omap3_l3_app_irq, + IRQF_DISABLED | IRQF_TRIGGER_RISING, + "l3-debug-irq", l3); + if (ret) { + dev_err(&pdev->dev, "couldn't request debug irq\n"); + goto err3; + } + l3->debug_irq = irq; + + irq = platform_get_irq(pdev, 1); + ret = request_irq(irq, omap3_l3_app_irq, + IRQF_DISABLED | IRQF_TRIGGER_RISING, + "l3-app-irq", l3); + + if (ret) { + dev_err(&pdev->dev, "couldn't request app irq\n"); + goto err4; + } + + l3->app_irq = irq; + goto err0; + +err4: +err3: + iounmap(l3->rt); +err2: +err1: + kfree(l3); +err0: + return ret; +} + +static int __exit omap3_l3_remove(struct platform_device *pdev) +{ + struct omap3_l3 *l3 = platform_get_drvdata(pdev); + + free_irq(l3->app_irq, l3); + free_irq(l3->debug_irq, l3); + iounmap(l3->rt); + kfree(l3); + + return 0; +} + +static struct platform_driver omap3_l3_driver = { + .remove = __exit_p(omap3_l3_remove), + .driver = { + .name = "omap_l3_smx", + }, +}; + +static int __init omap3_l3_init(void) +{ + return platform_driver_probe(&omap3_l3_driver, omap3_l3_probe); +} +postcore_initcall_sync(omap3_l3_init); + +static void __exit omap3_l3_exit(void) +{ + platform_driver_unregister(&omap3_l3_driver); +} +module_exit(omap3_l3_exit); diff --git a/arch/arm/mach-omap2/omap_l3_smx.h b/arch/arm/mach-omap2/omap_l3_smx.h new file mode 100644 index 00000000000..ba2ed9a850c --- /dev/null +++ b/arch/arm/mach-omap2/omap_l3_smx.h @@ -0,0 +1,338 @@ + /* + * OMAP3XXX L3 Interconnect Driver header + * + * Copyright (C) 2011 Texas Corporation + * Felipe Balbi <balbi@ti.com> + * Santosh Shilimkar <santosh.shilimkar@ti.com> + * sricharan <r.sricharan@ti.com> + * + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program; if not, write to the Free Software + * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 + * USA + */ +#ifndef __ARCH_ARM_MACH_OMAP2_L3_INTERCONNECT_3XXX_H +#define __ARCH_ARM_MACH_OMAP2_L3_INTERCONNECT_3XXX_H + +/* Register definitions. All 64-bit wide */ +#define L3_COMPONENT 0x000 +#define L3_CORE 0x018 +#define L3_AGENT_CONTROL 0x020 +#define L3_AGENT_STATUS 0x028 +#define L3_ERROR_LOG 0x058 + +#define L3_ERROR_LOG_MULTI (1 << 31) +#define L3_ERROR_LOG_SECONDARY (1 << 30) + +#define L3_ERROR_LOG_ADDR 0x060 + +/* Register definitions for Sideband Interconnect */ +#define L3_SI_CONTROL 0x020 +#define L3_SI_FLAG_STATUS_0 0x510 + +const u64 shift = 1; + +#define L3_STATUS_0_MPUIA_BRST (shift << 0) +#define L3_STATUS_0_MPUIA_RSP (shift << 1) +#define L3_STATUS_0_MPUIA_INBAND (shift << 2) +#define L3_STATUS_0_IVAIA_BRST (shift << 6) +#define L3_STATUS_0_IVAIA_RSP (shift << 7) +#define L3_STATUS_0_IVAIA_INBAND (shift << 8) +#define L3_STATUS_0_SGXIA_BRST (shift << 9) +#define L3_STATUS_0_SGXIA_RSP (shift << 10) +#define L3_STATUS_0_SGXIA_MERROR (shift << 11) +#define L3_STATUS_0_CAMIA_BRST (shift << 12) +#define L3_STATUS_0_CAMIA_RSP (shift << 13) +#define L3_STATUS_0_CAMIA_INBAND (shift << 14) +#define L3_STATUS_0_DISPIA_BRST (shift << 15) +#define L3_STATUS_0_DISPIA_RSP (shift << 16) +#define L3_STATUS_0_DMARDIA_BRST (shift << 18) +#define L3_STATUS_0_DMARDIA_RSP (shift << 19) +#define L3_STATUS_0_DMAWRIA_BRST (shift << 21) +#define L3_STATUS_0_DMAWRIA_RSP (shift << 22) +#define L3_STATUS_0_USBOTGIA_BRST (shift << 24) +#define L3_STATUS_0_USBOTGIA_RSP (shift << 25) +#define L3_STATUS_0_USBOTGIA_INBAND (shift << 26) +#define L3_STATUS_0_USBHOSTIA_BRST (shift << 27) +#define L3_STATUS_0_USBHOSTIA_INBAND (shift << 28) +#define L3_STATUS_0_SMSTA_REQ (shift << 48) +#define L3_STATUS_0_GPMCTA_REQ (shift << 49) +#define L3_STATUS_0_OCMRAMTA_REQ (shift << 50) +#define L3_STATUS_0_OCMROMTA_REQ (shift << 51) +#define L3_STATUS_0_IVATA_REQ (shift << 54) +#define L3_STATUS_0_SGXTA_REQ (shift << 55) +#define L3_STATUS_0_SGXTA_SERROR (shift << 56) +#define L3_STATUS_0_GPMCTA_SERROR (shift << 57) +#define L3_STATUS_0_L4CORETA_REQ (shift << 58) +#define L3_STATUS_0_L4PERTA_REQ (shift << 59) +#define L3_STATUS_0_L4EMUTA_REQ (shift << 60) +#define L3_STATUS_0_MAD2DTA_REQ (shift << 61) + +#define L3_STATUS_0_TIMEOUT_MASK (L3_STATUS_0_MPUIA_BRST \ + | L3_STATUS_0_MPUIA_RSP \ + | L3_STATUS_0_IVAIA_BRST \ + | L3_STATUS_0_IVAIA_RSP \ + | L3_STATUS_0_SGXIA_BRST \ + | L3_STATUS_0_SGXIA_RSP \ + | L3_STATUS_0_CAMIA_BRST \ + | L3_STATUS_0_CAMIA_RSP \ + | L3_STATUS_0_DISPIA_BRST \ + | L3_STATUS_0_DISPIA_RSP \ + | L3_STATUS_0_DMARDIA_BRST \ + | L3_STATUS_0_DMARDIA_RSP \ + | L3_STATUS_0_DMAWRIA_BRST \ + | L3_STATUS_0_DMAWRIA_RSP \ + | L3_STATUS_0_USBOTGIA_BRST \ + | L3_STATUS_0_USBOTGIA_RSP \ + | L3_STATUS_0_USBHOSTIA_BRST \ + | L3_STATUS_0_SMSTA_REQ \ + | L3_STATUS_0_GPMCTA_REQ \ + | L3_STATUS_0_OCMRAMTA_REQ \ + | L3_STATUS_0_OCMROMTA_REQ \ + | L3_STATUS_0_IVATA_REQ \ + | L3_STATUS_0_SGXTA_REQ \ + | L3_STATUS_0_L4CORETA_REQ \ + | L3_STATUS_0_L4PERTA_REQ \ + | L3_STATUS_0_L4EMUTA_REQ \ + | L3_STATUS_0_MAD2DTA_REQ) + +#define L3_SI_FLAG_STATUS_1 0x530 + +#define L3_STATUS_1_MPU_DATAIA (1 << 0) +#define L3_STATUS_1_DAPIA0 (1 << 3) +#define L3_STATUS_1_DAPIA1 (1 << 4) +#define L3_STATUS_1_IVAIA (1 << 6) + +#define L3_PM_ERROR_LOG 0x020 +#define L3_PM_CONTROL 0x028 +#define L3_PM_ERROR_CLEAR_SINGLE 0x030 +#define L3_PM_ERROR_CLEAR_MULTI 0x038 +#define L3_PM_REQ_INFO_PERMISSION(n) (0x048 + (0x020 * n)) +#define L3_PM_READ_PERMISSION(n) (0x050 + (0x020 * n)) +#define L3_PM_WRITE_PERMISSION(n) (0x058 + (0x020 * n)) +#define L3_PM_ADDR_MATCH(n) (0x060 + (0x020 * n)) + +/* L3 error log bit fields. Common for IA and TA */ +#define L3_ERROR_LOG_CODE 24 +#define L3_ERROR_LOG_INITID 8 +#define L3_ERROR_LOG_CMD 0 + +/* L3 agent status bit fields. */ +#define L3_AGENT_STATUS_CLEAR_IA 0x10000000 +#define L3_AGENT_STATUS_CLEAR_TA 0x01000000 + +#define OMAP34xx_IRQ_L3_APP 10 +#define L3_APPLICATION_ERROR 0x0 +#define L3_DEBUG_ERROR 0x1 + +enum omap3_l3_initiator_id { + /* LCD has 1 ID */ + OMAP_L3_LCD = 29, + /* SAD2D has 1 ID */ + OMAP_L3_SAD2D = 28, + /* MPU has 5 IDs */ + OMAP_L3_IA_MPU_SS_1 = 27, + OMAP_L3_IA_MPU_SS_2 = 26, + OMAP_L3_IA_MPU_SS_3 = 25, + OMAP_L3_IA_MPU_SS_4 = 24, + OMAP_L3_IA_MPU_SS_5 = 23, + /* IVA2.2 SS has 3 IDs*/ + OMAP_L3_IA_IVA_SS_1 = 22, + OMAP_L3_IA_IVA_SS_2 = 21, + OMAP_L3_IA_IVA_SS_3 = 20, + /* IVA 2.2 SS DMA has 6 IDS */ + OMAP_L3_IA_IVA_SS_DMA_1 = 19, + OMAP_L3_IA_IVA_SS_DMA_2 = 18, + OMAP_L3_IA_IVA_SS_DMA_3 = 17, + OMAP_L3_IA_IVA_SS_DMA_4 = 16, + OMAP_L3_IA_IVA_SS_DMA_5 = 15, + OMAP_L3_IA_IVA_SS_DMA_6 = 14, + /* SGX has 1 ID */ + OMAP_L3_IA_SGX = 13, + /* CAM has 3 ID */ + OMAP_L3_IA_CAM_1 = 12, + OMAP_L3_IA_CAM_2 = 11, + OMAP_L3_IA_CAM_3 = 10, + /* DAP has 1 ID */ + OMAP_L3_IA_DAP = 9, + /* SDMA WR has 2 IDs */ + OMAP_L3_SDMA_WR_1 = 8, + OMAP_L3_SDMA_WR_2 = 7, + /* SDMA RD has 4 IDs */ + OMAP_L3_SDMA_RD_1 = 6, + OMAP_L3_SDMA_RD_2 = 5, + OMAP_L3_SDMA_RD_3 = 4, + OMAP_L3_SDMA_RD_4 = 3, + /* HSUSB OTG has 1 ID */ + OMAP_L3_USBOTG = 2, + /* HSUSB HOST has 1 ID */ + OMAP_L3_USBHOST = 1, +}; + +enum omap3_l3_code { + OMAP_L3_CODE_NOERROR = 0, + OMAP_L3_CODE_UNSUP_CMD = 1, + OMAP_L3_CODE_ADDR_HOLE = 2, + OMAP_L3_CODE_PROTECT_VIOLATION = 3, + OMAP_L3_CODE_IN_BAND_ERR = 4, + /* codes 5 and 6 are reserved */ + OMAP_L3_CODE_REQ_TOUT_NOT_ACCEPT = 7, + OMAP_L3_CODE_REQ_TOUT_NO_RESP = 8, + /* codes 9 - 15 are also reserved */ +}; + +struct omap3_l3 { + struct device *dev; + struct clk *ick; + + /* memory base*/ + void __iomem *rt; + + int debug_irq; + int app_irq; + + /* true when and inband functional error occurs */ + unsigned inband:1; +}; + +/* offsets for l3 agents in order with the Flag status register */ +unsigned int __iomem omap3_l3_app_bases[] = { + /* MPU IA */ + 0x1400, + 0x1400, + 0x1400, + /* RESERVED */ + 0, + 0, + 0, + /* IVA 2.2 IA */ + 0x1800, + 0x1800, + 0x1800, + /* SGX IA */ + 0x1c00, + 0x1c00, + /* RESERVED */ + 0, + /* CAMERA IA */ + 0x5800, + 0x5800, + 0x5800, + /* DISPLAY IA */ + 0x5400, + 0x5400, + /* RESERVED */ + 0, + /*SDMA RD IA */ + 0x4c00, + 0x4c00, + /* RESERVED */ + 0, + /* SDMA WR IA */ + 0x5000, + 0x5000, + /* RESERVED */ + 0, + /* USB OTG IA */ + 0x4400, + 0x4400, + 0x4400, + /* USB HOST IA */ + 0x4000, + 0x4000, + /* RESERVED */ + 0, + 0, + 0, + 0, + /* SAD2D IA */ + 0x3000, + 0x3000, + 0x3000, + /* RESERVED */ + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + /* SMA TA */ + 0x2000, + /* GPMC TA */ + 0x2400, + /* OCM RAM TA */ + 0x2800, + /* OCM ROM TA */ + 0x2C00, + /* L4 CORE TA */ + 0x6800, + /* L4 PER TA */ + 0x6c00, + /* IVA 2.2 TA */ + 0x6000, + /* SGX TA */ + 0x6400, + /* L4 EMU TA */ + 0x7000, + /* GPMC TA */ + 0x2400, + /* L4 CORE TA */ + 0x6800, + /* L4 PER TA */ + 0x6c00, + /* L4 EMU TA */ + 0x7000, + /* MAD2D TA */ + 0x3400, + /* RESERVED */ + 0, + 0, +}; + +unsigned int __iomem omap3_l3_debug_bases[] = { + /* MPU DATA IA */ + 0x1400, + /* RESERVED */ + 0, + 0, + /* DAP IA */ + 0x5c00, + 0x5c00, + /* RESERVED */ + 0, + /* IVA 2.2 IA */ + 0x1800, + /* REST RESERVED */ +}; + +u32 *omap3_l3_bases[] = { + omap3_l3_app_bases, + omap3_l3_debug_bases, +}; + +/* + * REVISIT define __raw_readll/__raw_writell here, but move them to + * <asm/io.h> at some point + */ +#define __raw_writell(v, a) (__chk_io_ptr(a), \ + *(volatile u64 __force *)(a) = (v)) +#define __raw_readll(a) (__chk_io_ptr(a), \ + *(volatile u64 __force *)(a)) + +#endif diff --git a/arch/arm/mach-omap2/omap_opp_data.h b/arch/arm/mach-omap2/omap_opp_data.h index 46ac27dd6c8..c784c12f98a 100644 --- a/arch/arm/mach-omap2/omap_opp_data.h +++ b/arch/arm/mach-omap2/omap_opp_data.h @@ -21,6 +21,8 @@ #include <plat/omap_hwmod.h> +#include "voltage.h" + /* * *BIG FAT WARNING*: * USE the following ONLY in opp data initialization common to an SoC. @@ -65,8 +67,30 @@ struct omap_opp_def { .u_volt = _uv, \ } +/* + * Initialization wrapper used to define SmartReflex process data + * XXX Is this needed? Just use C99 initializers in data files? + */ +#define VOLT_DATA_DEFINE(_v_nom, _efuse_offs, _errminlimit, _errgain) \ +{ \ + .volt_nominal = _v_nom, \ + .sr_efuse_offs = _efuse_offs, \ + .sr_errminlimit = _errminlimit, \ + .vp_errgain = _errgain \ +} + /* Use this to initialize the default table */ extern int __init omap_init_opp_table(struct omap_opp_def *opp_def, u32 opp_def_size); + +extern struct omap_volt_data omap34xx_vddmpu_volt_data[]; +extern struct omap_volt_data omap34xx_vddcore_volt_data[]; +extern struct omap_volt_data omap36xx_vddmpu_volt_data[]; +extern struct omap_volt_data omap36xx_vddcore_volt_data[]; + +extern struct omap_volt_data omap44xx_vdd_mpu_volt_data[]; +extern struct omap_volt_data omap44xx_vdd_iva_volt_data[]; +extern struct omap_volt_data omap44xx_vdd_core_volt_data[]; + #endif /* __ARCH_ARM_MACH_OMAP2_OMAP_OPP_DATA_H */ diff --git a/arch/arm/mach-omap2/omap_phy_internal.c b/arch/arm/mach-omap2/omap_phy_internal.c index ebe33df708b..e2e605fe913 100644 --- a/arch/arm/mach-omap2/omap_phy_internal.c +++ b/arch/arm/mach-omap2/omap_phy_internal.c @@ -29,6 +29,7 @@ #include <linux/usb.h> #include <plat/usb.h> +#include "control.h" /* OMAP control module register for UTMI PHY */ #define CONTROL_DEV_CONF 0x300 @@ -162,3 +163,95 @@ int omap4430_phy_exit(struct device *dev) return 0; } + +void am35x_musb_reset(void) +{ + u32 regval; + + /* Reset the musb interface */ + regval = omap_ctrl_readl(AM35XX_CONTROL_IP_SW_RESET); + + regval |= AM35XX_USBOTGSS_SW_RST; + omap_ctrl_writel(regval, AM35XX_CONTROL_IP_SW_RESET); + + regval &= ~AM35XX_USBOTGSS_SW_RST; + omap_ctrl_writel(regval, AM35XX_CONTROL_IP_SW_RESET); + + regval = omap_ctrl_readl(AM35XX_CONTROL_IP_SW_RESET); +} + +void am35x_musb_phy_power(u8 on) +{ + unsigned long timeout = jiffies + msecs_to_jiffies(100); + u32 devconf2; + + if (on) { + /* + * Start the on-chip PHY and its PLL. + */ + devconf2 = omap_ctrl_readl(AM35XX_CONTROL_DEVCONF2); + + devconf2 &= ~(CONF2_RESET | CONF2_PHYPWRDN | CONF2_OTGPWRDN); + devconf2 |= CONF2_PHY_PLLON; + + omap_ctrl_writel(devconf2, AM35XX_CONTROL_DEVCONF2); + + pr_info(KERN_INFO "Waiting for PHY clock good...\n"); + while (!(omap_ctrl_readl(AM35XX_CONTROL_DEVCONF2) + & CONF2_PHYCLKGD)) { + cpu_relax(); + + if (time_after(jiffies, timeout)) { + pr_err(KERN_ERR "musb PHY clock good timed out\n"); + break; + } + } + } else { + /* + * Power down the on-chip PHY. + */ + devconf2 = omap_ctrl_readl(AM35XX_CONTROL_DEVCONF2); + + devconf2 &= ~CONF2_PHY_PLLON; + devconf2 |= CONF2_PHYPWRDN | CONF2_OTGPWRDN; + omap_ctrl_writel(devconf2, AM35XX_CONTROL_DEVCONF2); + } +} + +void am35x_musb_clear_irq(void) +{ + u32 regval; + + regval = omap_ctrl_readl(AM35XX_CONTROL_LVL_INTR_CLEAR); + regval |= AM35XX_USBOTGSS_INT_CLR; + omap_ctrl_writel(regval, AM35XX_CONTROL_LVL_INTR_CLEAR); + regval = omap_ctrl_readl(AM35XX_CONTROL_LVL_INTR_CLEAR); +} + +void am35x_musb_set_mode(u8 musb_mode) +{ + u32 devconf2 = omap_ctrl_readl(AM35XX_CONTROL_DEVCONF2); + + devconf2 &= ~CONF2_OTGMODE; + switch (musb_mode) { +#ifdef CONFIG_USB_MUSB_HDRC_HCD + case MUSB_HOST: /* Force VBUS valid, ID = 0 */ + devconf2 |= CONF2_FORCE_HOST; + break; +#endif +#ifdef CONFIG_USB_GADGET_MUSB_HDRC + case MUSB_PERIPHERAL: /* Force VBUS valid, ID = 1 */ + devconf2 |= CONF2_FORCE_DEVICE; + break; +#endif +#ifdef CONFIG_USB_MUSB_OTG + case MUSB_OTG: /* Don't override the VBUS/ID comparators */ + devconf2 |= CONF2_NO_OVERRIDE; + break; +#endif + default: + pr_info(KERN_INFO "Unsupported mode %u\n", musb_mode); + } + + omap_ctrl_writel(devconf2, AM35XX_CONTROL_DEVCONF2); +} diff --git a/arch/arm/mach-omap2/omap_twl.c b/arch/arm/mach-omap2/omap_twl.c index 00e1d2b5368..0a8e74e3e81 100644 --- a/arch/arm/mach-omap2/omap_twl.c +++ b/arch/arm/mach-omap2/omap_twl.c @@ -18,7 +18,7 @@ #include <linux/kernel.h> #include <linux/i2c/twl.h> -#include <plat/voltage.h> +#include "voltage.h" #include "pm.h" @@ -59,8 +59,15 @@ static bool is_offset_valid; static u8 smps_offset; +/* + * Flag to ensure Smartreflex bit in TWL + * being cleared in board file is not overwritten. + */ +static bool __initdata twl_sr_enable_autoinit; +#define TWL4030_DCDC_GLOBAL_CFG 0x06 #define REG_SMPS_OFFSET 0xE0 +#define SMARTREFLEX_ENABLE BIT(3) static unsigned long twl4030_vsel_to_uv(const u8 vsel) { @@ -269,6 +276,18 @@ int __init omap3_twl_init(void) omap3_core_volt_info.vp_vddmax = OMAP3630_VP2_VLIMITTO_VDDMAX; } + /* + * The smartreflex bit on twl4030 specifies if the setting of voltage + * is done over the I2C_SR path. Since this setting is independent of + * the actual usage of smartreflex AVS module, we enable TWL SR bit + * by default irrespective of whether smartreflex AVS module is enabled + * on the OMAP side or not. This is because without this bit enabled, + * the voltage scaling through vp forceupdate/bypass mechanism of + * voltage scaling will not function on TWL over I2C_SR. + */ + if (!twl_sr_enable_autoinit) + omap3_twl_set_sr_bit(true); + voltdm = omap_voltage_domain_lookup("mpu"); omap_voltage_register_pmic(voltdm, &omap3_mpu_volt_info); @@ -277,3 +296,44 @@ int __init omap3_twl_init(void) return 0; } + +/** + * omap3_twl_set_sr_bit() - Set/Clear SR bit on TWL + * @enable: enable SR mode in twl or not + * + * If 'enable' is true, enables Smartreflex bit on TWL 4030 to make sure + * voltage scaling through OMAP SR works. Else, the smartreflex bit + * on twl4030 is cleared as there are platforms which use OMAP3 and T2 but + * use Synchronized Scaling Hardware Strategy (ENABLE_VMODE=1) and Direct + * Strategy Software Scaling Mode (ENABLE_VMODE=0), for setting the voltages, + * in those scenarios this bit is to be cleared (enable = false). + * + * Returns 0 on sucess, error is returned if I2C read/write fails. + */ +int __init omap3_twl_set_sr_bit(bool enable) +{ + u8 temp; + int ret; + if (twl_sr_enable_autoinit) + pr_warning("%s: unexpected multiple calls\n", __func__); + + ret = twl_i2c_read_u8(TWL4030_MODULE_PM_RECEIVER, &temp, + TWL4030_DCDC_GLOBAL_CFG); + if (ret) + goto err; + + if (enable) + temp |= SMARTREFLEX_ENABLE; + else + temp &= ~SMARTREFLEX_ENABLE; + + ret = twl_i2c_write_u8(TWL4030_MODULE_PM_RECEIVER, temp, + TWL4030_DCDC_GLOBAL_CFG); + if (!ret) { + twl_sr_enable_autoinit = true; + return 0; + } +err: + pr_err("%s: Error access to TWL4030 (%d)\n", __func__, ret); + return ret; +} diff --git a/arch/arm/mach-omap2/opp2xxx.h b/arch/arm/mach-omap2/opp2xxx.h index 38b73055050..8affc66a92c 100644 --- a/arch/arm/mach-omap2/opp2xxx.h +++ b/arch/arm/mach-omap2/opp2xxx.h @@ -418,7 +418,7 @@ struct prcm_config { extern const struct prcm_config omap2420_rate_table[]; -#ifdef CONFIG_ARCH_OMAP2430 +#ifdef CONFIG_SOC_OMAP2430 extern const struct prcm_config omap2430_rate_table[]; #else #define omap2430_rate_table NULL diff --git a/arch/arm/mach-omap2/opp3xxx_data.c b/arch/arm/mach-omap2/opp3xxx_data.c index 0486fce8a92..d95f3f945d4 100644 --- a/arch/arm/mach-omap2/opp3xxx_data.c +++ b/arch/arm/mach-omap2/opp3xxx_data.c @@ -4,8 +4,9 @@ * Copyright (C) 2009-2010 Texas Instruments Incorporated - http://www.ti.com/ * Nishanth Menon * Kevin Hilman - * Copyright (C) 2010 Nokia Corporation. + * Copyright (C) 2010-2011 Nokia Corporation. * Eduardo Valentin + * Paul Walmsley * * This program is free software; you can redistribute it and/or modify * it under the terms of the GNU General Public License version 2 as @@ -20,19 +21,83 @@ #include <plat/cpu.h> +#include "control.h" #include "omap_opp_data.h" +#include "pm.h" + +/* 34xx */ + +/* VDD1 */ + +#define OMAP3430_VDD_MPU_OPP1_UV 975000 +#define OMAP3430_VDD_MPU_OPP2_UV 1075000 +#define OMAP3430_VDD_MPU_OPP3_UV 1200000 +#define OMAP3430_VDD_MPU_OPP4_UV 1270000 +#define OMAP3430_VDD_MPU_OPP5_UV 1350000 + +struct omap_volt_data omap34xx_vddmpu_volt_data[] = { + VOLT_DATA_DEFINE(OMAP3430_VDD_MPU_OPP1_UV, OMAP343X_CONTROL_FUSE_OPP1_VDD1, 0xf4, 0x0c), + VOLT_DATA_DEFINE(OMAP3430_VDD_MPU_OPP2_UV, OMAP343X_CONTROL_FUSE_OPP2_VDD1, 0xf4, 0x0c), + VOLT_DATA_DEFINE(OMAP3430_VDD_MPU_OPP3_UV, OMAP343X_CONTROL_FUSE_OPP3_VDD1, 0xf9, 0x18), + VOLT_DATA_DEFINE(OMAP3430_VDD_MPU_OPP4_UV, OMAP343X_CONTROL_FUSE_OPP4_VDD1, 0xf9, 0x18), + VOLT_DATA_DEFINE(OMAP3430_VDD_MPU_OPP5_UV, OMAP343X_CONTROL_FUSE_OPP5_VDD1, 0xf9, 0x18), + VOLT_DATA_DEFINE(0, 0, 0, 0), +}; + +/* VDD2 */ + +#define OMAP3430_VDD_CORE_OPP1_UV 975000 +#define OMAP3430_VDD_CORE_OPP2_UV 1050000 +#define OMAP3430_VDD_CORE_OPP3_UV 1150000 + +struct omap_volt_data omap34xx_vddcore_volt_data[] = { + VOLT_DATA_DEFINE(OMAP3430_VDD_CORE_OPP1_UV, OMAP343X_CONTROL_FUSE_OPP1_VDD2, 0xf4, 0x0c), + VOLT_DATA_DEFINE(OMAP3430_VDD_CORE_OPP2_UV, OMAP343X_CONTROL_FUSE_OPP2_VDD2, 0xf4, 0x0c), + VOLT_DATA_DEFINE(OMAP3430_VDD_CORE_OPP3_UV, OMAP343X_CONTROL_FUSE_OPP3_VDD2, 0xf9, 0x18), + VOLT_DATA_DEFINE(0, 0, 0, 0), +}; + +/* 36xx */ + +/* VDD1 */ + +#define OMAP3630_VDD_MPU_OPP50_UV 1012500 +#define OMAP3630_VDD_MPU_OPP100_UV 1200000 +#define OMAP3630_VDD_MPU_OPP120_UV 1325000 +#define OMAP3630_VDD_MPU_OPP1G_UV 1375000 + +struct omap_volt_data omap36xx_vddmpu_volt_data[] = { + VOLT_DATA_DEFINE(OMAP3630_VDD_MPU_OPP50_UV, OMAP3630_CONTROL_FUSE_OPP50_VDD1, 0xf4, 0x0c), + VOLT_DATA_DEFINE(OMAP3630_VDD_MPU_OPP100_UV, OMAP3630_CONTROL_FUSE_OPP100_VDD1, 0xf9, 0x16), + VOLT_DATA_DEFINE(OMAP3630_VDD_MPU_OPP120_UV, OMAP3630_CONTROL_FUSE_OPP120_VDD1, 0xfa, 0x23), + VOLT_DATA_DEFINE(OMAP3630_VDD_MPU_OPP1G_UV, OMAP3630_CONTROL_FUSE_OPP1G_VDD1, 0xfa, 0x27), + VOLT_DATA_DEFINE(0, 0, 0, 0), +}; + +/* VDD2 */ + +#define OMAP3630_VDD_CORE_OPP50_UV 1000000 +#define OMAP3630_VDD_CORE_OPP100_UV 1200000 + +struct omap_volt_data omap36xx_vddcore_volt_data[] = { + VOLT_DATA_DEFINE(OMAP3630_VDD_CORE_OPP50_UV, OMAP3630_CONTROL_FUSE_OPP50_VDD2, 0xf4, 0x0c), + VOLT_DATA_DEFINE(OMAP3630_VDD_CORE_OPP100_UV, OMAP3630_CONTROL_FUSE_OPP100_VDD2, 0xf9, 0x16), + VOLT_DATA_DEFINE(0, 0, 0, 0), +}; + +/* OPP data */ static struct omap_opp_def __initdata omap34xx_opp_def_list[] = { /* MPU OPP1 */ - OPP_INITIALIZER("mpu", true, 125000000, 975000), + OPP_INITIALIZER("mpu", true, 125000000, OMAP3430_VDD_MPU_OPP1_UV), /* MPU OPP2 */ - OPP_INITIALIZER("mpu", true, 250000000, 1075000), + OPP_INITIALIZER("mpu", true, 250000000, OMAP3430_VDD_MPU_OPP2_UV), /* MPU OPP3 */ - OPP_INITIALIZER("mpu", true, 500000000, 1200000), + OPP_INITIALIZER("mpu", true, 500000000, OMAP3430_VDD_MPU_OPP3_UV), /* MPU OPP4 */ - OPP_INITIALIZER("mpu", true, 550000000, 1270000), + OPP_INITIALIZER("mpu", true, 550000000, OMAP3430_VDD_MPU_OPP4_UV), /* MPU OPP5 */ - OPP_INITIALIZER("mpu", true, 600000000, 1350000), + OPP_INITIALIZER("mpu", true, 600000000, OMAP3430_VDD_MPU_OPP5_UV), /* * L3 OPP1 - 41.5 MHz is disabled because: The voltage for that OPP is @@ -42,53 +107,53 @@ static struct omap_opp_def __initdata omap34xx_opp_def_list[] = { * impact that frequency will do to the MPU and the whole system in * general. */ - OPP_INITIALIZER("l3_main", false, 41500000, 975000), + OPP_INITIALIZER("l3_main", false, 41500000, OMAP3430_VDD_CORE_OPP1_UV), /* L3 OPP2 */ - OPP_INITIALIZER("l3_main", true, 83000000, 1050000), + OPP_INITIALIZER("l3_main", true, 83000000, OMAP3430_VDD_CORE_OPP2_UV), /* L3 OPP3 */ - OPP_INITIALIZER("l3_main", true, 166000000, 1150000), + OPP_INITIALIZER("l3_main", true, 166000000, OMAP3430_VDD_CORE_OPP3_UV), /* DSP OPP1 */ - OPP_INITIALIZER("iva", true, 90000000, 975000), + OPP_INITIALIZER("iva", true, 90000000, OMAP3430_VDD_MPU_OPP1_UV), /* DSP OPP2 */ - OPP_INITIALIZER("iva", true, 180000000, 1075000), + OPP_INITIALIZER("iva", true, 180000000, OMAP3430_VDD_MPU_OPP2_UV), /* DSP OPP3 */ - OPP_INITIALIZER("iva", true, 360000000, 1200000), + OPP_INITIALIZER("iva", true, 360000000, OMAP3430_VDD_MPU_OPP3_UV), /* DSP OPP4 */ - OPP_INITIALIZER("iva", true, 400000000, 1270000), + OPP_INITIALIZER("iva", true, 400000000, OMAP3430_VDD_MPU_OPP4_UV), /* DSP OPP5 */ - OPP_INITIALIZER("iva", true, 430000000, 1350000), + OPP_INITIALIZER("iva", true, 430000000, OMAP3430_VDD_MPU_OPP5_UV), }; static struct omap_opp_def __initdata omap36xx_opp_def_list[] = { /* MPU OPP1 - OPP50 */ - OPP_INITIALIZER("mpu", true, 300000000, 1012500), + OPP_INITIALIZER("mpu", true, 300000000, OMAP3630_VDD_MPU_OPP50_UV), /* MPU OPP2 - OPP100 */ - OPP_INITIALIZER("mpu", true, 600000000, 1200000), + OPP_INITIALIZER("mpu", true, 600000000, OMAP3630_VDD_MPU_OPP100_UV), /* MPU OPP3 - OPP-Turbo */ - OPP_INITIALIZER("mpu", false, 800000000, 1325000), + OPP_INITIALIZER("mpu", false, 800000000, OMAP3630_VDD_MPU_OPP120_UV), /* MPU OPP4 - OPP-SB */ - OPP_INITIALIZER("mpu", false, 1000000000, 1375000), + OPP_INITIALIZER("mpu", false, 1000000000, OMAP3630_VDD_MPU_OPP1G_UV), /* L3 OPP1 - OPP50 */ - OPP_INITIALIZER("l3_main", true, 100000000, 1000000), + OPP_INITIALIZER("l3_main", true, 100000000, OMAP3630_VDD_CORE_OPP50_UV), /* L3 OPP2 - OPP100, OPP-Turbo, OPP-SB */ - OPP_INITIALIZER("l3_main", true, 200000000, 1200000), + OPP_INITIALIZER("l3_main", true, 200000000, OMAP3630_VDD_CORE_OPP100_UV), /* DSP OPP1 - OPP50 */ - OPP_INITIALIZER("iva", true, 260000000, 1012500), + OPP_INITIALIZER("iva", true, 260000000, OMAP3630_VDD_MPU_OPP50_UV), /* DSP OPP2 - OPP100 */ - OPP_INITIALIZER("iva", true, 520000000, 1200000), + OPP_INITIALIZER("iva", true, 520000000, OMAP3630_VDD_MPU_OPP100_UV), /* DSP OPP3 - OPP-Turbo */ - OPP_INITIALIZER("iva", false, 660000000, 1325000), + OPP_INITIALIZER("iva", false, 660000000, OMAP3630_VDD_MPU_OPP120_UV), /* DSP OPP4 - OPP-SB */ - OPP_INITIALIZER("iva", false, 800000000, 1375000), + OPP_INITIALIZER("iva", false, 800000000, OMAP3630_VDD_MPU_OPP1G_UV), }; /** * omap3_opp_init() - initialize omap3 opp table */ -static int __init omap3_opp_init(void) +int __init omap3_opp_init(void) { int r = -ENODEV; diff --git a/arch/arm/mach-omap2/opp4xxx_data.c b/arch/arm/mach-omap2/opp4xxx_data.c index a11fa566d8e..2293ba27101 100644 --- a/arch/arm/mach-omap2/opp4xxx_data.c +++ b/arch/arm/mach-omap2/opp4xxx_data.c @@ -5,8 +5,9 @@ * Nishanth Menon * Kevin Hilman * Thara Gopinath - * Copyright (C) 2010 Nokia Corporation. + * Copyright (C) 2010-2011 Nokia Corporation. * Eduardo Valentin + * Paul Walmsley * * This program is free software; you can redistribute it and/or modify * it under the terms of the GNU General Public License version 2 as @@ -21,28 +22,75 @@ #include <plat/cpu.h> +#include "control.h" #include "omap_opp_data.h" +#include "pm.h" + +/* + * Structures containing OMAP4430 voltage supported and various + * voltage dependent data for each VDD. + */ + +#define OMAP4430_VDD_MPU_OPP50_UV 1025000 +#define OMAP4430_VDD_MPU_OPP100_UV 1200000 +#define OMAP4430_VDD_MPU_OPPTURBO_UV 1313000 +#define OMAP4430_VDD_MPU_OPPNITRO_UV 1375000 + +struct omap_volt_data omap44xx_vdd_mpu_volt_data[] = { + VOLT_DATA_DEFINE(OMAP4430_VDD_MPU_OPP50_UV, OMAP44XX_CONTROL_FUSE_MPU_OPP50, 0xf4, 0x0c), + VOLT_DATA_DEFINE(OMAP4430_VDD_MPU_OPP100_UV, OMAP44XX_CONTROL_FUSE_MPU_OPP100, 0xf9, 0x16), + VOLT_DATA_DEFINE(OMAP4430_VDD_MPU_OPPTURBO_UV, OMAP44XX_CONTROL_FUSE_MPU_OPPTURBO, 0xfa, 0x23), + VOLT_DATA_DEFINE(OMAP4430_VDD_MPU_OPPNITRO_UV, OMAP44XX_CONTROL_FUSE_MPU_OPPNITRO, 0xfa, 0x27), + VOLT_DATA_DEFINE(0, 0, 0, 0), +}; + +#define OMAP4430_VDD_IVA_OPP50_UV 1013000 +#define OMAP4430_VDD_IVA_OPP100_UV 1188000 +#define OMAP4430_VDD_IVA_OPPTURBO_UV 1300000 + +struct omap_volt_data omap44xx_vdd_iva_volt_data[] = { + VOLT_DATA_DEFINE(OMAP4430_VDD_IVA_OPP50_UV, OMAP44XX_CONTROL_FUSE_IVA_OPP50, 0xf4, 0x0c), + VOLT_DATA_DEFINE(OMAP4430_VDD_IVA_OPP100_UV, OMAP44XX_CONTROL_FUSE_IVA_OPP100, 0xf9, 0x16), + VOLT_DATA_DEFINE(OMAP4430_VDD_IVA_OPPTURBO_UV, OMAP44XX_CONTROL_FUSE_IVA_OPPTURBO, 0xfa, 0x23), + VOLT_DATA_DEFINE(0, 0, 0, 0), +}; + +#define OMAP4430_VDD_CORE_OPP50_UV 1025000 +#define OMAP4430_VDD_CORE_OPP100_UV 1200000 + +struct omap_volt_data omap44xx_vdd_core_volt_data[] = { + VOLT_DATA_DEFINE(OMAP4430_VDD_CORE_OPP50_UV, OMAP44XX_CONTROL_FUSE_CORE_OPP50, 0xf4, 0x0c), + VOLT_DATA_DEFINE(OMAP4430_VDD_CORE_OPP100_UV, OMAP44XX_CONTROL_FUSE_CORE_OPP100, 0xf9, 0x16), + VOLT_DATA_DEFINE(0, 0, 0, 0), +}; + static struct omap_opp_def __initdata omap44xx_opp_def_list[] = { /* MPU OPP1 - OPP50 */ - OPP_INITIALIZER("mpu", true, 300000000, 1100000), + OPP_INITIALIZER("mpu", true, 300000000, OMAP4430_VDD_MPU_OPP50_UV), /* MPU OPP2 - OPP100 */ - OPP_INITIALIZER("mpu", true, 600000000, 1200000), + OPP_INITIALIZER("mpu", true, 600000000, OMAP4430_VDD_MPU_OPP100_UV), /* MPU OPP3 - OPP-Turbo */ - OPP_INITIALIZER("mpu", false, 800000000, 1260000), + OPP_INITIALIZER("mpu", true, 800000000, OMAP4430_VDD_MPU_OPPTURBO_UV), /* MPU OPP4 - OPP-SB */ - OPP_INITIALIZER("mpu", false, 1008000000, 1350000), + OPP_INITIALIZER("mpu", true, 1008000000, OMAP4430_VDD_MPU_OPPNITRO_UV), /* L3 OPP1 - OPP50 */ - OPP_INITIALIZER("l3_main_1", true, 100000000, 930000), + OPP_INITIALIZER("l3_main_1", true, 100000000, OMAP4430_VDD_CORE_OPP50_UV), /* L3 OPP2 - OPP100, OPP-Turbo, OPP-SB */ - OPP_INITIALIZER("l3_main_1", true, 200000000, 1100000), - /* TODO: add IVA, DSP, aess, fdif, gpu */ + OPP_INITIALIZER("l3_main_1", true, 200000000, OMAP4430_VDD_CORE_OPP100_UV), + /* IVA OPP1 - OPP50 */ + OPP_INITIALIZER("iva", true, 133000000, OMAP4430_VDD_IVA_OPP50_UV), + /* IVA OPP2 - OPP100 */ + OPP_INITIALIZER("iva", true, 266100000, OMAP4430_VDD_IVA_OPP100_UV), + /* IVA OPP3 - OPP-Turbo */ + OPP_INITIALIZER("iva", false, 332000000, OMAP4430_VDD_IVA_OPPTURBO_UV), + /* TODO: add DSP, aess, fdif, gpu */ }; /** * omap4_opp_init() - initialize omap4 opp table */ -static int __init omap4_opp_init(void) +int __init omap4_opp_init(void) { int r = -ENODEV; diff --git a/arch/arm/mach-omap2/pm.c b/arch/arm/mach-omap2/pm.c index d5a102c7198..30af3351c2d 100644 --- a/arch/arm/mach-omap2/pm.c +++ b/arch/arm/mach-omap2/pm.c @@ -18,8 +18,8 @@ #include <plat/omap-pm.h> #include <plat/omap_device.h> #include <plat/common.h> -#include <plat/voltage.h> +#include "voltage.h" #include "powerdomain.h" #include "clockdomain.h" #include "pm.h" @@ -83,7 +83,9 @@ static int _init_omap_device(char *name, struct device **new_dev) static void omap2_init_processor_devices(void) { _init_omap_device("mpu", &mpu_dev); - _init_omap_device("iva", &iva_dev); + if (omap3_has_iva()) + _init_omap_device("iva", &iva_dev); + if (cpu_is_omap44xx()) { _init_omap_device("l3_main_1", &l3_dev); _init_omap_device("dsp", &dsp_dev); @@ -124,7 +126,7 @@ int omap_set_pwrdm_state(struct powerdomain *pwrdm, u32 state) (pwrdm->flags & PWRDM_HAS_LOWPOWERSTATECHANGE)) { sleep_switch = LOWPOWERSTATE_SWITCH; } else { - omap2_clkdm_wakeup(pwrdm->pwrdm_clkdms[0]); + clkdm_wakeup(pwrdm->pwrdm_clkdms[0]); pwrdm_wait_transition(pwrdm); sleep_switch = FORCEWAKEUP_SWITCH; } @@ -140,9 +142,9 @@ int omap_set_pwrdm_state(struct powerdomain *pwrdm, u32 state) switch (sleep_switch) { case FORCEWAKEUP_SWITCH: if (pwrdm->pwrdm_clkdms[0]->flags & CLKDM_CAN_ENABLE_AUTO) - omap2_clkdm_allow_idle(pwrdm->pwrdm_clkdms[0]); + clkdm_allow_idle(pwrdm->pwrdm_clkdms[0]); else - omap2_clkdm_sleep(pwrdm->pwrdm_clkdms[0]); + clkdm_sleep(pwrdm->pwrdm_clkdms[0]); break; case LOWPOWERSTATE_SWITCH: pwrdm_set_lowpwrstchange(pwrdm); diff --git a/arch/arm/mach-omap2/pm.h b/arch/arm/mach-omap2/pm.h index 39580e6060e..797bfd12b64 100644 --- a/arch/arm/mach-omap2/pm.h +++ b/arch/arm/mach-omap2/pm.h @@ -127,6 +127,7 @@ static inline void omap_enable_smartreflex_on_init(void) {} #ifdef CONFIG_TWL4030_CORE extern int omap3_twl_init(void); extern int omap4_twl_init(void); +extern int omap3_twl_set_sr_bit(bool enable); #else static inline int omap3_twl_init(void) { diff --git a/arch/arm/mach-omap2/pm24xx.c b/arch/arm/mach-omap2/pm24xx.c index 97feb3ab6a6..df3ded6fe19 100644 --- a/arch/arm/mach-omap2/pm24xx.c +++ b/arch/arm/mach-omap2/pm24xx.c @@ -363,14 +363,11 @@ static const struct platform_suspend_ops __initdata omap_pm_ops; /* XXX This function should be shareable between OMAP2xxx and OMAP3 */ static int __init clkdms_setup(struct clockdomain *clkdm, void *unused) { - clkdm_clear_all_wkdeps(clkdm); - clkdm_clear_all_sleepdeps(clkdm); - if (clkdm->flags & CLKDM_CAN_ENABLE_AUTO) - omap2_clkdm_allow_idle(clkdm); + clkdm_allow_idle(clkdm); else if (clkdm->flags & CLKDM_CAN_FORCE_SLEEP && atomic_read(&clkdm->usecount) == 0) - omap2_clkdm_sleep(clkdm); + clkdm_sleep(clkdm); return 0; } @@ -379,7 +376,10 @@ static void __init prcm_setup_regs(void) int i, num_mem_banks; struct powerdomain *pwrdm; - /* Enable autoidle */ + /* + * Enable autoidle + * XXX This should be handled by hwmod code or PRCM init code + */ omap2_prm_write_mod_reg(OMAP24XX_AUTOIDLE_MASK, OCP_MOD, OMAP2_PRCM_SYSCONFIG_OFFSET); @@ -405,83 +405,16 @@ static void __init prcm_setup_regs(void) pwrdm = clkdm_get_pwrdm(dsp_clkdm); pwrdm_set_next_pwrst(pwrdm, PWRDM_POWER_OFF); - omap2_clkdm_sleep(dsp_clkdm); + clkdm_sleep(dsp_clkdm); pwrdm = clkdm_get_pwrdm(gfx_clkdm); pwrdm_set_next_pwrst(pwrdm, PWRDM_POWER_OFF); - omap2_clkdm_sleep(gfx_clkdm); + clkdm_sleep(gfx_clkdm); - /* - * Clear clockdomain wakeup dependencies and enable - * hardware-supervised idle for all clkdms - */ + /* Enable hardware-supervised idle for all clkdms */ clkdm_for_each(clkdms_setup, NULL); clkdm_add_wkdep(mpu_clkdm, wkup_clkdm); - /* Enable clock autoidle for all domains */ - omap2_cm_write_mod_reg(OMAP24XX_AUTO_CAM_MASK | - OMAP24XX_AUTO_MAILBOXES_MASK | - OMAP24XX_AUTO_WDT4_MASK | - OMAP2420_AUTO_WDT3_MASK | - OMAP24XX_AUTO_MSPRO_MASK | - OMAP2420_AUTO_MMC_MASK | - OMAP24XX_AUTO_FAC_MASK | - OMAP2420_AUTO_EAC_MASK | - OMAP24XX_AUTO_HDQ_MASK | - OMAP24XX_AUTO_UART2_MASK | - OMAP24XX_AUTO_UART1_MASK | - OMAP24XX_AUTO_I2C2_MASK | - OMAP24XX_AUTO_I2C1_MASK | - OMAP24XX_AUTO_MCSPI2_MASK | - OMAP24XX_AUTO_MCSPI1_MASK | - OMAP24XX_AUTO_MCBSP2_MASK | - OMAP24XX_AUTO_MCBSP1_MASK | - OMAP24XX_AUTO_GPT12_MASK | - OMAP24XX_AUTO_GPT11_MASK | - OMAP24XX_AUTO_GPT10_MASK | - OMAP24XX_AUTO_GPT9_MASK | - OMAP24XX_AUTO_GPT8_MASK | - OMAP24XX_AUTO_GPT7_MASK | - OMAP24XX_AUTO_GPT6_MASK | - OMAP24XX_AUTO_GPT5_MASK | - OMAP24XX_AUTO_GPT4_MASK | - OMAP24XX_AUTO_GPT3_MASK | - OMAP24XX_AUTO_GPT2_MASK | - OMAP2420_AUTO_VLYNQ_MASK | - OMAP24XX_AUTO_DSS_MASK, - CORE_MOD, CM_AUTOIDLE1); - omap2_cm_write_mod_reg(OMAP24XX_AUTO_UART3_MASK | - OMAP24XX_AUTO_SSI_MASK | - OMAP24XX_AUTO_USB_MASK, - CORE_MOD, CM_AUTOIDLE2); - omap2_cm_write_mod_reg(OMAP24XX_AUTO_SDRC_MASK | - OMAP24XX_AUTO_GPMC_MASK | - OMAP24XX_AUTO_SDMA_MASK, - CORE_MOD, CM_AUTOIDLE3); - omap2_cm_write_mod_reg(OMAP24XX_AUTO_PKA_MASK | - OMAP24XX_AUTO_AES_MASK | - OMAP24XX_AUTO_RNG_MASK | - OMAP24XX_AUTO_SHA_MASK | - OMAP24XX_AUTO_DES_MASK, - CORE_MOD, OMAP24XX_CM_AUTOIDLE4); - - omap2_cm_write_mod_reg(OMAP2420_AUTO_DSP_IPI_MASK, OMAP24XX_DSP_MOD, - CM_AUTOIDLE); - - /* Put DPLL and both APLLs into autoidle mode */ - omap2_cm_write_mod_reg((0x03 << OMAP24XX_AUTO_DPLL_SHIFT) | - (0x03 << OMAP24XX_AUTO_96M_SHIFT) | - (0x03 << OMAP24XX_AUTO_54M_SHIFT), - PLL_MOD, CM_AUTOIDLE); - - omap2_cm_write_mod_reg(OMAP24XX_AUTO_OMAPCTRL_MASK | - OMAP24XX_AUTO_WDT1_MASK | - OMAP24XX_AUTO_MPU_WDT_MASK | - OMAP24XX_AUTO_GPIOS_MASK | - OMAP24XX_AUTO_32KSYNC_MASK | - OMAP24XX_AUTO_GPT1_MASK, - WKUP_MOD, CM_AUTOIDLE); - /* REVISIT: Configure number of 32 kHz clock cycles for sys_clk * stabilisation */ omap2_prm_write_mod_reg(15 << OMAP_SETUP_TIME_SHIFT, OMAP24XX_GR_MOD, diff --git a/arch/arm/mach-omap2/pm34xx.c b/arch/arm/mach-omap2/pm34xx.c index 2f864e4b085..0c5e3a46a3a 100644 --- a/arch/arm/mach-omap2/pm34xx.c +++ b/arch/arm/mach-omap2/pm34xx.c @@ -29,6 +29,7 @@ #include <linux/delay.h> #include <linux/slab.h> #include <linux/console.h> +#include <trace/events/power.h> #include <plat/sram.h> #include "clockdomain.h" @@ -311,11 +312,6 @@ static irqreturn_t prcm_interrupt_handler (int irq, void *dev_id) return IRQ_HANDLED; } -static void restore_control_register(u32 val) -{ - __asm__ __volatile__ ("mcr p15, 0, %0, c1, c0, 0" : : "r" (val)); -} - /* Function to restore the table entry that was modified for enabling MMU */ static void restore_table_entry(void) { @@ -337,7 +333,7 @@ static void restore_table_entry(void) control_reg_value = __raw_readl(scratchpad_address + OMAP343X_CONTROL_REG_VALUE_OFFSET); /* This will enable caches and prediction */ - restore_control_register(control_reg_value); + set_cr(control_reg_value); } void omap_sram_idle(void) @@ -496,7 +492,7 @@ console_still_active: pwrdm_post_transition(); - omap2_clkdm_allow_idle(mpu_pwrdm->pwrdm_clkdms[0]); + clkdm_allow_idle(mpu_pwrdm->pwrdm_clkdms[0]); } int omap3_can_sleep(void) @@ -519,8 +515,14 @@ static void omap3_pm_idle(void) if (omap_irq_pending() || need_resched()) goto out; + trace_power_start(POWER_CSTATE, 1, smp_processor_id()); + trace_cpu_idle(1, smp_processor_id()); + omap_sram_idle(); + trace_power_end(smp_processor_id()); + trace_cpu_idle(PWR_EVENT_EXIT, smp_processor_id()); + out: local_fiq_enable(); local_irq_enable(); @@ -688,149 +690,15 @@ static void __init omap3_d2d_idle(void) static void __init prcm_setup_regs(void) { - u32 omap3630_auto_uart4_mask = cpu_is_omap3630() ? - OMAP3630_AUTO_UART4_MASK : 0; u32 omap3630_en_uart4_mask = cpu_is_omap3630() ? OMAP3630_EN_UART4_MASK : 0; u32 omap3630_grpsel_uart4_mask = cpu_is_omap3630() ? OMAP3630_GRPSEL_UART4_MASK : 0; - - /* XXX Reset all wkdeps. This should be done when initializing - * powerdomains */ - omap2_prm_write_mod_reg(0, OMAP3430_IVA2_MOD, PM_WKDEP); - omap2_prm_write_mod_reg(0, MPU_MOD, PM_WKDEP); - omap2_prm_write_mod_reg(0, OMAP3430_DSS_MOD, PM_WKDEP); - omap2_prm_write_mod_reg(0, OMAP3430_NEON_MOD, PM_WKDEP); - omap2_prm_write_mod_reg(0, OMAP3430_CAM_MOD, PM_WKDEP); - omap2_prm_write_mod_reg(0, OMAP3430_PER_MOD, PM_WKDEP); - if (omap_rev() > OMAP3430_REV_ES1_0) { - omap2_prm_write_mod_reg(0, OMAP3430ES2_SGX_MOD, PM_WKDEP); - omap2_prm_write_mod_reg(0, OMAP3430ES2_USBHOST_MOD, PM_WKDEP); - } else - omap2_prm_write_mod_reg(0, GFX_MOD, PM_WKDEP); - - /* - * Enable interface clock autoidle for all modules. - * Note that in the long run this should be done by clockfw - */ - omap2_cm_write_mod_reg( - OMAP3430_AUTO_MODEM_MASK | - OMAP3430ES2_AUTO_MMC3_MASK | - OMAP3430ES2_AUTO_ICR_MASK | - OMAP3430_AUTO_AES2_MASK | - OMAP3430_AUTO_SHA12_MASK | - OMAP3430_AUTO_DES2_MASK | - OMAP3430_AUTO_MMC2_MASK | - OMAP3430_AUTO_MMC1_MASK | - OMAP3430_AUTO_MSPRO_MASK | - OMAP3430_AUTO_HDQ_MASK | - OMAP3430_AUTO_MCSPI4_MASK | - OMAP3430_AUTO_MCSPI3_MASK | - OMAP3430_AUTO_MCSPI2_MASK | - OMAP3430_AUTO_MCSPI1_MASK | - OMAP3430_AUTO_I2C3_MASK | - OMAP3430_AUTO_I2C2_MASK | - OMAP3430_AUTO_I2C1_MASK | - OMAP3430_AUTO_UART2_MASK | - OMAP3430_AUTO_UART1_MASK | - OMAP3430_AUTO_GPT11_MASK | - OMAP3430_AUTO_GPT10_MASK | - OMAP3430_AUTO_MCBSP5_MASK | - OMAP3430_AUTO_MCBSP1_MASK | - OMAP3430ES1_AUTO_FAC_MASK | /* This is es1 only */ - OMAP3430_AUTO_MAILBOXES_MASK | - OMAP3430_AUTO_OMAPCTRL_MASK | - OMAP3430ES1_AUTO_FSHOSTUSB_MASK | - OMAP3430_AUTO_HSOTGUSB_MASK | - OMAP3430_AUTO_SAD2D_MASK | - OMAP3430_AUTO_SSI_MASK, - CORE_MOD, CM_AUTOIDLE1); - - omap2_cm_write_mod_reg( - OMAP3430_AUTO_PKA_MASK | - OMAP3430_AUTO_AES1_MASK | - OMAP3430_AUTO_RNG_MASK | - OMAP3430_AUTO_SHA11_MASK | - OMAP3430_AUTO_DES1_MASK, - CORE_MOD, CM_AUTOIDLE2); - - if (omap_rev() > OMAP3430_REV_ES1_0) { - omap2_cm_write_mod_reg( - OMAP3430_AUTO_MAD2D_MASK | - OMAP3430ES2_AUTO_USBTLL_MASK, - CORE_MOD, CM_AUTOIDLE3); - } - - omap2_cm_write_mod_reg( - OMAP3430_AUTO_WDT2_MASK | - OMAP3430_AUTO_WDT1_MASK | - OMAP3430_AUTO_GPIO1_MASK | - OMAP3430_AUTO_32KSYNC_MASK | - OMAP3430_AUTO_GPT12_MASK | - OMAP3430_AUTO_GPT1_MASK, - WKUP_MOD, CM_AUTOIDLE); - - omap2_cm_write_mod_reg( - OMAP3430_AUTO_DSS_MASK, - OMAP3430_DSS_MOD, - CM_AUTOIDLE); - - omap2_cm_write_mod_reg( - OMAP3430_AUTO_CAM_MASK, - OMAP3430_CAM_MOD, - CM_AUTOIDLE); - - omap2_cm_write_mod_reg( - omap3630_auto_uart4_mask | - OMAP3430_AUTO_GPIO6_MASK | - OMAP3430_AUTO_GPIO5_MASK | - OMAP3430_AUTO_GPIO4_MASK | - OMAP3430_AUTO_GPIO3_MASK | - OMAP3430_AUTO_GPIO2_MASK | - OMAP3430_AUTO_WDT3_MASK | - OMAP3430_AUTO_UART3_MASK | - OMAP3430_AUTO_GPT9_MASK | - OMAP3430_AUTO_GPT8_MASK | - OMAP3430_AUTO_GPT7_MASK | - OMAP3430_AUTO_GPT6_MASK | - OMAP3430_AUTO_GPT5_MASK | - OMAP3430_AUTO_GPT4_MASK | - OMAP3430_AUTO_GPT3_MASK | - OMAP3430_AUTO_GPT2_MASK | - OMAP3430_AUTO_MCBSP4_MASK | - OMAP3430_AUTO_MCBSP3_MASK | - OMAP3430_AUTO_MCBSP2_MASK, - OMAP3430_PER_MOD, - CM_AUTOIDLE); - - if (omap_rev() > OMAP3430_REV_ES1_0) { - omap2_cm_write_mod_reg( - OMAP3430ES2_AUTO_USBHOST_MASK, - OMAP3430ES2_USBHOST_MOD, - CM_AUTOIDLE); - } - + /* XXX This should be handled by hwmod code or SCM init code */ omap_ctrl_writel(OMAP3430_AUTOIDLE_MASK, OMAP2_CONTROL_SYSCONFIG); /* - * Set all plls to autoidle. This is needed until autoidle is - * enabled by clockfw - */ - omap2_cm_write_mod_reg(1 << OMAP3430_AUTO_IVA2_DPLL_SHIFT, - OMAP3430_IVA2_MOD, CM_AUTOIDLE2); - omap2_cm_write_mod_reg(1 << OMAP3430_AUTO_MPU_DPLL_SHIFT, - MPU_MOD, - CM_AUTOIDLE2); - omap2_cm_write_mod_reg((1 << OMAP3430_AUTO_PERIPH_DPLL_SHIFT) | - (1 << OMAP3430_AUTO_CORE_DPLL_SHIFT), - PLL_MOD, - CM_AUTOIDLE); - omap2_cm_write_mod_reg(1 << OMAP3430ES2_AUTO_PERIPH2_DPLL_SHIFT, - PLL_MOD, - CM_AUTOIDLE2); - - /* * Enable control of expternal oscillator through * sys_clkreq. In the long run clock framework should * take care of this. @@ -928,8 +796,7 @@ void omap3_pm_off_mode_enable(int enable) pwrst->pwrdm == core_pwrdm && state == PWRDM_POWER_OFF) { pwrst->next_state = PWRDM_POWER_RET; - WARN_ONCE(1, - "%s: Core OFF disabled due to errata i583\n", + pr_warn("%s: Core OFF disabled due to errata i583\n", __func__); } else { pwrst->next_state = state; @@ -990,10 +857,10 @@ static int __init pwrdms_setup(struct powerdomain *pwrdm, void *unused) static int __init clkdms_setup(struct clockdomain *clkdm, void *unused) { if (clkdm->flags & CLKDM_CAN_ENABLE_AUTO) - omap2_clkdm_allow_idle(clkdm); + clkdm_allow_idle(clkdm); else if (clkdm->flags & CLKDM_CAN_FORCE_SLEEP && atomic_read(&clkdm->usecount) == 0) - omap2_clkdm_sleep(clkdm); + clkdm_sleep(clkdm); return 0; } diff --git a/arch/arm/mach-omap2/powerdomain.c b/arch/arm/mach-omap2/powerdomain.c index eaed0df1669..49c6513e90d 100644 --- a/arch/arm/mach-omap2/powerdomain.c +++ b/arch/arm/mach-omap2/powerdomain.c @@ -2,7 +2,7 @@ * OMAP powerdomain control * * Copyright (C) 2007-2008 Texas Instruments, Inc. - * Copyright (C) 2007-2009 Nokia Corporation + * Copyright (C) 2007-2011 Nokia Corporation * * Written by Paul Walmsley * Added OMAP4 specific support by Abhijit Pagare <abhijitpagare@ti.com> @@ -19,12 +19,15 @@ #include <linux/list.h> #include <linux/errno.h> #include <linux/string.h> +#include <trace/events/power.h> + #include "cm2xxx_3xxx.h" #include "prcm44xx.h" #include "cm44xx.h" #include "prm2xxx_3xxx.h" #include "prm44xx.h" +#include <asm/cpu.h> #include <plat/cpu.h> #include "powerdomain.h" #include "clockdomain.h" @@ -32,6 +35,8 @@ #include "pm.h" +#define PWRDM_TRACE_STATES_FLAG (1<<31) + enum { PWRDM_STATE_NOW = 0, PWRDM_STATE_PREV, @@ -130,8 +135,7 @@ static void _update_logic_membank_counters(struct powerdomain *pwrdm) static int _pwrdm_state_switch(struct powerdomain *pwrdm, int flag) { - int prev; - int state; + int prev, state, trace_state = 0; if (pwrdm == NULL) return -EINVAL; @@ -148,6 +152,17 @@ static int _pwrdm_state_switch(struct powerdomain *pwrdm, int flag) pwrdm->state_counter[prev]++; if (prev == PWRDM_POWER_RET) _update_logic_membank_counters(pwrdm); + /* + * If the power domain did not hit the desired state, + * generate a trace event with both the desired and hit states + */ + if (state != prev) { + trace_state = (PWRDM_TRACE_STATES_FLAG | + ((state & OMAP_POWERSTATE_MASK) << 8) | + ((prev & OMAP_POWERSTATE_MASK) << 0)); + trace_power_domain_target(pwrdm->name, trace_state, + smp_processor_id()); + } break; default: return -EINVAL; @@ -406,8 +421,13 @@ int pwrdm_set_next_pwrst(struct powerdomain *pwrdm, u8 pwrst) pr_debug("powerdomain: setting next powerstate for %s to %0x\n", pwrdm->name, pwrst); - if (arch_pwrdm && arch_pwrdm->pwrdm_set_next_pwrst) + if (arch_pwrdm && arch_pwrdm->pwrdm_set_next_pwrst) { + /* Trace the pwrdm desired target state */ + trace_power_domain_target(pwrdm->name, pwrst, + smp_processor_id()); + /* Program the pwrdm desired target state */ ret = arch_pwrdm->pwrdm_set_next_pwrst(pwrdm, pwrst); + } return ret; } @@ -938,3 +958,44 @@ u32 pwrdm_get_context_loss_count(struct powerdomain *pwrdm) return count; } + +/** + * pwrdm_can_ever_lose_context - can this powerdomain ever lose context? + * @pwrdm: struct powerdomain * + * + * Given a struct powerdomain * @pwrdm, returns 1 if the powerdomain + * can lose either memory or logic context or if @pwrdm is invalid, or + * returns 0 otherwise. This function is not concerned with how the + * powerdomain registers are programmed (i.e., to go off or not); it's + * concerned with whether it's ever possible for this powerdomain to + * go off while some other part of the chip is active. This function + * assumes that every powerdomain can go to either ON or INACTIVE. + */ +bool pwrdm_can_ever_lose_context(struct powerdomain *pwrdm) +{ + int i; + + if (IS_ERR_OR_NULL(pwrdm)) { + pr_debug("powerdomain: %s: invalid powerdomain pointer\n", + __func__); + return 1; + } + + if (pwrdm->pwrsts & PWRSTS_OFF) + return 1; + + if (pwrdm->pwrsts & PWRSTS_RET) { + if (pwrdm->pwrsts_logic_ret & PWRSTS_OFF) + return 1; + + for (i = 0; i < pwrdm->banks; i++) + if (pwrdm->pwrsts_mem_ret[i] & PWRSTS_OFF) + return 1; + } + + for (i = 0; i < pwrdm->banks; i++) + if (pwrdm->pwrsts_mem_on[i] & PWRSTS_OFF) + return 1; + + return 0; +} diff --git a/arch/arm/mach-omap2/powerdomain.h b/arch/arm/mach-omap2/powerdomain.h index c66431edfeb..027f40bd235 100644 --- a/arch/arm/mach-omap2/powerdomain.h +++ b/arch/arm/mach-omap2/powerdomain.h @@ -2,7 +2,7 @@ * OMAP2/3/4 powerdomain control * * Copyright (C) 2007-2008, 2010 Texas Instruments, Inc. - * Copyright (C) 2007-2010 Nokia Corporation + * Copyright (C) 2007-2011 Nokia Corporation * * Paul Walmsley * @@ -34,17 +34,14 @@ /* Powerdomain allowable state bitfields */ #define PWRSTS_ON (1 << PWRDM_POWER_ON) +#define PWRSTS_INACTIVE (1 << PWRDM_POWER_INACTIVE) +#define PWRSTS_RET (1 << PWRDM_POWER_RET) #define PWRSTS_OFF (1 << PWRDM_POWER_OFF) -#define PWRSTS_OFF_ON ((1 << PWRDM_POWER_OFF) | \ - (1 << PWRDM_POWER_ON)) -#define PWRSTS_OFF_RET ((1 << PWRDM_POWER_OFF) | \ - (1 << PWRDM_POWER_RET)) - -#define PWRSTS_RET_ON ((1 << PWRDM_POWER_RET) | \ - (1 << PWRDM_POWER_ON)) - -#define PWRSTS_OFF_RET_ON (PWRSTS_OFF_RET | (1 << PWRDM_POWER_ON)) +#define PWRSTS_OFF_ON (PWRSTS_OFF | PWRSTS_ON) +#define PWRSTS_OFF_RET (PWRSTS_OFF | PWRSTS_RET) +#define PWRSTS_RET_ON (PWRSTS_RET | PWRSTS_ON) +#define PWRSTS_OFF_RET_ON (PWRSTS_OFF_RET | PWRSTS_ON) /* Powerdomain flags */ @@ -165,7 +162,6 @@ struct pwrdm_ops { int (*pwrdm_wait_transition)(struct powerdomain *pwrdm); }; -void pwrdm_fw_init(void); void pwrdm_init(struct powerdomain **pwrdm_list, struct pwrdm_ops *custom_funcs); struct powerdomain *pwrdm_lookup(const char *name); @@ -212,6 +208,7 @@ int pwrdm_pre_transition(void); int pwrdm_post_transition(void); int pwrdm_set_lowpwrstchange(struct powerdomain *pwrdm); u32 pwrdm_get_context_loss_count(struct powerdomain *pwrdm); +bool pwrdm_can_ever_lose_context(struct powerdomain *pwrdm); extern void omap2xxx_powerdomains_init(void); extern void omap3xxx_powerdomains_init(void); diff --git a/arch/arm/mach-omap2/powerdomains2xxx_3xxx_data.c b/arch/arm/mach-omap2/powerdomains2xxx_3xxx_data.c index 5b4dd971320..4210c339976 100644 --- a/arch/arm/mach-omap2/powerdomains2xxx_3xxx_data.c +++ b/arch/arm/mach-omap2/powerdomains2xxx_3xxx_data.c @@ -2,7 +2,7 @@ * OMAP2/3 common powerdomain definitions * * Copyright (C) 2007-2008 Texas Instruments, Inc. - * Copyright (C) 2007-2010 Nokia Corporation + * Copyright (C) 2007-2011 Nokia Corporation * * Paul Walmsley, Jouni Högander * @@ -62,13 +62,13 @@ struct powerdomain gfx_omap2_pwrdm = { .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP24XX | CHIP_IS_OMAP3430ES1), .pwrsts = PWRSTS_OFF_RET_ON, - .pwrsts_logic_ret = PWRDM_POWER_RET, + .pwrsts_logic_ret = PWRSTS_RET, .banks = 1, .pwrsts_mem_ret = { - [0] = PWRDM_POWER_RET, /* MEMRETSTATE */ + [0] = PWRSTS_RET, /* MEMRETSTATE */ }, .pwrsts_mem_on = { - [0] = PWRDM_POWER_ON, /* MEMONSTATE */ + [0] = PWRSTS_ON, /* MEMONSTATE */ }, }; @@ -76,4 +76,5 @@ struct powerdomain wkup_omap2_pwrdm = { .name = "wkup_pwrdm", .prcm_offs = WKUP_MOD, .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP24XX | CHIP_IS_OMAP3430), + .pwrsts = PWRSTS_ON, }; diff --git a/arch/arm/mach-omap2/powerdomains2xxx_data.c b/arch/arm/mach-omap2/powerdomains2xxx_data.c index 9b1a3350057..cc389fb2005 100644 --- a/arch/arm/mach-omap2/powerdomains2xxx_data.c +++ b/arch/arm/mach-omap2/powerdomains2xxx_data.c @@ -2,7 +2,7 @@ * OMAP2XXX powerdomain definitions * * Copyright (C) 2007-2008 Texas Instruments, Inc. - * Copyright (C) 2007-2010 Nokia Corporation + * Copyright (C) 2007-2011 Nokia Corporation * * Paul Walmsley, Jouni Högander * @@ -30,13 +30,13 @@ static struct powerdomain dsp_pwrdm = { .prcm_offs = OMAP24XX_DSP_MOD, .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP24XX), .pwrsts = PWRSTS_OFF_RET_ON, - .pwrsts_logic_ret = PWRDM_POWER_RET, + .pwrsts_logic_ret = PWRSTS_RET, .banks = 1, .pwrsts_mem_ret = { - [0] = PWRDM_POWER_RET, + [0] = PWRSTS_RET, }, .pwrsts_mem_on = { - [0] = PWRDM_POWER_ON, + [0] = PWRSTS_ON, }, }; @@ -48,10 +48,10 @@ static struct powerdomain mpu_24xx_pwrdm = { .pwrsts_logic_ret = PWRSTS_OFF_RET, .banks = 1, .pwrsts_mem_ret = { - [0] = PWRDM_POWER_RET, + [0] = PWRSTS_RET, }, .pwrsts_mem_on = { - [0] = PWRDM_POWER_ON, + [0] = PWRSTS_ON, }, }; @@ -78,7 +78,7 @@ static struct powerdomain core_24xx_pwrdm = { * 2430-specific powerdomains */ -#ifdef CONFIG_ARCH_OMAP2430 +#ifdef CONFIG_SOC_OMAP2430 /* XXX 2430 KILLDOMAINWKUP bit? No current users apparently */ @@ -87,17 +87,17 @@ static struct powerdomain mdm_pwrdm = { .prcm_offs = OMAP2430_MDM_MOD, .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP2430), .pwrsts = PWRSTS_OFF_RET_ON, - .pwrsts_logic_ret = PWRDM_POWER_RET, + .pwrsts_logic_ret = PWRSTS_RET, .banks = 1, .pwrsts_mem_ret = { - [0] = PWRDM_POWER_RET, /* MEMRETSTATE */ + [0] = PWRSTS_RET, /* MEMRETSTATE */ }, .pwrsts_mem_on = { - [0] = PWRDM_POWER_ON, /* MEMONSTATE */ + [0] = PWRSTS_ON, /* MEMONSTATE */ }, }; -#endif /* CONFIG_ARCH_OMAP2430 */ +#endif /* CONFIG_SOC_OMAP2430 */ /* As powerdomains are added or removed above, this list must also be changed */ static struct powerdomain *powerdomains_omap2xxx[] __initdata = { @@ -111,7 +111,7 @@ static struct powerdomain *powerdomains_omap2xxx[] __initdata = { &core_24xx_pwrdm, #endif -#ifdef CONFIG_ARCH_OMAP2430 +#ifdef CONFIG_SOC_OMAP2430 &mdm_pwrdm, #endif NULL diff --git a/arch/arm/mach-omap2/powerdomains3xxx_data.c b/arch/arm/mach-omap2/powerdomains3xxx_data.c index e1bec562625..9c9c113788b 100644 --- a/arch/arm/mach-omap2/powerdomains3xxx_data.c +++ b/arch/arm/mach-omap2/powerdomains3xxx_data.c @@ -2,7 +2,7 @@ * OMAP3 powerdomain definitions * * Copyright (C) 2007-2008 Texas Instruments, Inc. - * Copyright (C) 2007-2010 Nokia Corporation + * Copyright (C) 2007-2011 Nokia Corporation * * Paul Walmsley, Jouni Högander * @@ -47,10 +47,10 @@ static struct powerdomain iva2_pwrdm = { [3] = PWRSTS_OFF_RET, }, .pwrsts_mem_on = { - [0] = PWRDM_POWER_ON, - [1] = PWRDM_POWER_ON, + [0] = PWRSTS_ON, + [1] = PWRSTS_ON, [2] = PWRSTS_OFF_ON, - [3] = PWRDM_POWER_ON, + [3] = PWRSTS_ON, }, }; @@ -128,13 +128,13 @@ static struct powerdomain dss_pwrdm = { .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP3430), .prcm_offs = OMAP3430_DSS_MOD, .pwrsts = PWRSTS_OFF_RET_ON, - .pwrsts_logic_ret = PWRDM_POWER_RET, + .pwrsts_logic_ret = PWRSTS_RET, .banks = 1, .pwrsts_mem_ret = { - [0] = PWRDM_POWER_RET, /* MEMRETSTATE */ + [0] = PWRSTS_RET, /* MEMRETSTATE */ }, .pwrsts_mem_on = { - [0] = PWRDM_POWER_ON, /* MEMONSTATE */ + [0] = PWRSTS_ON, /* MEMONSTATE */ }, }; @@ -149,13 +149,13 @@ static struct powerdomain sgx_pwrdm = { .omap_chip = OMAP_CHIP_INIT(CHIP_GE_OMAP3430ES2), /* XXX This is accurate for 3430 SGX, but what about GFX? */ .pwrsts = PWRSTS_OFF_ON, - .pwrsts_logic_ret = PWRDM_POWER_RET, + .pwrsts_logic_ret = PWRSTS_RET, .banks = 1, .pwrsts_mem_ret = { - [0] = PWRDM_POWER_RET, /* MEMRETSTATE */ + [0] = PWRSTS_RET, /* MEMRETSTATE */ }, .pwrsts_mem_on = { - [0] = PWRDM_POWER_ON, /* MEMONSTATE */ + [0] = PWRSTS_ON, /* MEMONSTATE */ }, }; @@ -164,13 +164,13 @@ static struct powerdomain cam_pwrdm = { .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP3430), .prcm_offs = OMAP3430_CAM_MOD, .pwrsts = PWRSTS_OFF_RET_ON, - .pwrsts_logic_ret = PWRDM_POWER_RET, + .pwrsts_logic_ret = PWRSTS_RET, .banks = 1, .pwrsts_mem_ret = { - [0] = PWRDM_POWER_RET, /* MEMRETSTATE */ + [0] = PWRSTS_RET, /* MEMRETSTATE */ }, .pwrsts_mem_on = { - [0] = PWRDM_POWER_ON, /* MEMONSTATE */ + [0] = PWRSTS_ON, /* MEMONSTATE */ }, }; @@ -182,10 +182,10 @@ static struct powerdomain per_pwrdm = { .pwrsts_logic_ret = PWRSTS_OFF_RET, .banks = 1, .pwrsts_mem_ret = { - [0] = PWRDM_POWER_RET, /* MEMRETSTATE */ + [0] = PWRSTS_RET, /* MEMRETSTATE */ }, .pwrsts_mem_on = { - [0] = PWRDM_POWER_ON, /* MEMONSTATE */ + [0] = PWRSTS_ON, /* MEMONSTATE */ }, }; @@ -200,7 +200,7 @@ static struct powerdomain neon_pwrdm = { .prcm_offs = OMAP3430_NEON_MOD, .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP3430), .pwrsts = PWRSTS_OFF_RET_ON, - .pwrsts_logic_ret = PWRDM_POWER_RET, + .pwrsts_logic_ret = PWRSTS_RET, }; static struct powerdomain usbhost_pwrdm = { @@ -208,7 +208,7 @@ static struct powerdomain usbhost_pwrdm = { .prcm_offs = OMAP3430ES2_USBHOST_MOD, .omap_chip = OMAP_CHIP_INIT(CHIP_GE_OMAP3430ES2), .pwrsts = PWRSTS_OFF_RET_ON, - .pwrsts_logic_ret = PWRDM_POWER_RET, + .pwrsts_logic_ret = PWRSTS_RET, /* * REVISIT: Enabling usb host save and restore mechanism seems to * leave the usb host domain permanently in ACTIVE mode after @@ -218,10 +218,10 @@ static struct powerdomain usbhost_pwrdm = { /*.flags = PWRDM_HAS_HDWR_SAR,*/ /* for USBHOST ctrlr only */ .banks = 1, .pwrsts_mem_ret = { - [0] = PWRDM_POWER_RET, /* MEMRETSTATE */ + [0] = PWRSTS_RET, /* MEMRETSTATE */ }, .pwrsts_mem_on = { - [0] = PWRDM_POWER_ON, /* MEMONSTATE */ + [0] = PWRSTS_ON, /* MEMONSTATE */ }, }; diff --git a/arch/arm/mach-omap2/powerdomains44xx_data.c b/arch/arm/mach-omap2/powerdomains44xx_data.c index 26d7641076d..c4222c7036a 100644 --- a/arch/arm/mach-omap2/powerdomains44xx_data.c +++ b/arch/arm/mach-omap2/powerdomains44xx_data.c @@ -2,7 +2,7 @@ * OMAP4 Power domains framework * * Copyright (C) 2009-2010 Texas Instruments, Inc. - * Copyright (C) 2009-2010 Nokia Corporation + * Copyright (C) 2009-2011 Nokia Corporation * * Abhijit Pagare (abhijitpagare@ti.com) * Benoit Cousson (b-cousson@ti.com) @@ -40,18 +40,18 @@ static struct powerdomain core_44xx_pwrdm = { .pwrsts_logic_ret = PWRSTS_OFF_RET, .banks = 5, .pwrsts_mem_ret = { - [0] = PWRDM_POWER_OFF, /* core_nret_bank */ + [0] = PWRSTS_OFF, /* core_nret_bank */ [1] = PWRSTS_OFF_RET, /* core_ocmram */ - [2] = PWRDM_POWER_RET, /* core_other_bank */ + [2] = PWRSTS_RET, /* core_other_bank */ [3] = PWRSTS_OFF_RET, /* ducati_l2ram */ [4] = PWRSTS_OFF_RET, /* ducati_unicache */ }, .pwrsts_mem_on = { - [0] = PWRDM_POWER_ON, /* core_nret_bank */ + [0] = PWRSTS_ON, /* core_nret_bank */ [1] = PWRSTS_OFF_RET, /* core_ocmram */ - [2] = PWRDM_POWER_ON, /* core_other_bank */ - [3] = PWRDM_POWER_ON, /* ducati_l2ram */ - [4] = PWRDM_POWER_ON, /* ducati_unicache */ + [2] = PWRSTS_ON, /* core_other_bank */ + [3] = PWRSTS_ON, /* ducati_l2ram */ + [4] = PWRSTS_ON, /* ducati_unicache */ }, .flags = PWRDM_HAS_LOWPOWERSTATECHANGE, }; @@ -65,10 +65,10 @@ static struct powerdomain gfx_44xx_pwrdm = { .pwrsts = PWRSTS_OFF_ON, .banks = 1, .pwrsts_mem_ret = { - [0] = PWRDM_POWER_OFF, /* gfx_mem */ + [0] = PWRSTS_OFF, /* gfx_mem */ }, .pwrsts_mem_on = { - [0] = PWRDM_POWER_ON, /* gfx_mem */ + [0] = PWRSTS_ON, /* gfx_mem */ }, .flags = PWRDM_HAS_LOWPOWERSTATECHANGE, }; @@ -80,15 +80,15 @@ static struct powerdomain abe_44xx_pwrdm = { .prcm_partition = OMAP4430_PRM_PARTITION, .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430), .pwrsts = PWRSTS_OFF_RET_ON, - .pwrsts_logic_ret = PWRDM_POWER_OFF, + .pwrsts_logic_ret = PWRSTS_OFF, .banks = 2, .pwrsts_mem_ret = { - [0] = PWRDM_POWER_RET, /* aessmem */ - [1] = PWRDM_POWER_OFF, /* periphmem */ + [0] = PWRSTS_RET, /* aessmem */ + [1] = PWRSTS_OFF, /* periphmem */ }, .pwrsts_mem_on = { - [0] = PWRDM_POWER_ON, /* aessmem */ - [1] = PWRDM_POWER_ON, /* periphmem */ + [0] = PWRSTS_ON, /* aessmem */ + [1] = PWRSTS_ON, /* periphmem */ }, .flags = PWRDM_HAS_LOWPOWERSTATECHANGE, }; @@ -103,10 +103,10 @@ static struct powerdomain dss_44xx_pwrdm = { .pwrsts_logic_ret = PWRSTS_OFF, .banks = 1, .pwrsts_mem_ret = { - [0] = PWRDM_POWER_OFF, /* dss_mem */ + [0] = PWRSTS_OFF, /* dss_mem */ }, .pwrsts_mem_on = { - [0] = PWRDM_POWER_ON, /* dss_mem */ + [0] = PWRSTS_ON, /* dss_mem */ }, .flags = PWRDM_HAS_LOWPOWERSTATECHANGE, }; @@ -121,14 +121,14 @@ static struct powerdomain tesla_44xx_pwrdm = { .pwrsts_logic_ret = PWRSTS_OFF_RET, .banks = 3, .pwrsts_mem_ret = { - [0] = PWRDM_POWER_RET, /* tesla_edma */ + [0] = PWRSTS_RET, /* tesla_edma */ [1] = PWRSTS_OFF_RET, /* tesla_l1 */ [2] = PWRSTS_OFF_RET, /* tesla_l2 */ }, .pwrsts_mem_on = { - [0] = PWRDM_POWER_ON, /* tesla_edma */ - [1] = PWRDM_POWER_ON, /* tesla_l1 */ - [2] = PWRDM_POWER_ON, /* tesla_l2 */ + [0] = PWRSTS_ON, /* tesla_edma */ + [1] = PWRSTS_ON, /* tesla_l1 */ + [2] = PWRSTS_ON, /* tesla_l2 */ }, .flags = PWRDM_HAS_LOWPOWERSTATECHANGE, }; @@ -142,10 +142,10 @@ static struct powerdomain wkup_44xx_pwrdm = { .pwrsts = PWRSTS_ON, .banks = 1, .pwrsts_mem_ret = { - [0] = PWRDM_POWER_OFF, /* wkup_bank */ + [0] = PWRSTS_OFF, /* wkup_bank */ }, .pwrsts_mem_on = { - [0] = PWRDM_POWER_ON, /* wkup_bank */ + [0] = PWRSTS_ON, /* wkup_bank */ }, }; @@ -162,7 +162,7 @@ static struct powerdomain cpu0_44xx_pwrdm = { [0] = PWRSTS_OFF_RET, /* cpu0_l1 */ }, .pwrsts_mem_on = { - [0] = PWRDM_POWER_ON, /* cpu0_l1 */ + [0] = PWRSTS_ON, /* cpu0_l1 */ }, }; @@ -179,7 +179,7 @@ static struct powerdomain cpu1_44xx_pwrdm = { [0] = PWRSTS_OFF_RET, /* cpu1_l1 */ }, .pwrsts_mem_on = { - [0] = PWRDM_POWER_ON, /* cpu1_l1 */ + [0] = PWRSTS_ON, /* cpu1_l1 */ }, }; @@ -192,10 +192,10 @@ static struct powerdomain emu_44xx_pwrdm = { .pwrsts = PWRSTS_OFF_ON, .banks = 1, .pwrsts_mem_ret = { - [0] = PWRDM_POWER_OFF, /* emu_bank */ + [0] = PWRSTS_OFF, /* emu_bank */ }, .pwrsts_mem_on = { - [0] = PWRDM_POWER_ON, /* emu_bank */ + [0] = PWRSTS_ON, /* emu_bank */ }, }; @@ -211,12 +211,12 @@ static struct powerdomain mpu_44xx_pwrdm = { .pwrsts_mem_ret = { [0] = PWRSTS_OFF_RET, /* mpu_l1 */ [1] = PWRSTS_OFF_RET, /* mpu_l2 */ - [2] = PWRDM_POWER_RET, /* mpu_ram */ + [2] = PWRSTS_RET, /* mpu_ram */ }, .pwrsts_mem_on = { - [0] = PWRDM_POWER_ON, /* mpu_l1 */ - [1] = PWRDM_POWER_ON, /* mpu_l2 */ - [2] = PWRDM_POWER_ON, /* mpu_ram */ + [0] = PWRSTS_ON, /* mpu_l1 */ + [1] = PWRSTS_ON, /* mpu_l2 */ + [2] = PWRSTS_ON, /* mpu_ram */ }, }; @@ -227,19 +227,19 @@ static struct powerdomain ivahd_44xx_pwrdm = { .prcm_partition = OMAP4430_PRM_PARTITION, .omap_chip = OMAP_CHIP_INIT(CHIP_IS_OMAP4430), .pwrsts = PWRSTS_OFF_RET_ON, - .pwrsts_logic_ret = PWRDM_POWER_OFF, + .pwrsts_logic_ret = PWRSTS_OFF, .banks = 4, .pwrsts_mem_ret = { - [0] = PWRDM_POWER_OFF, /* hwa_mem */ + [0] = PWRSTS_OFF, /* hwa_mem */ [1] = PWRSTS_OFF_RET, /* sl2_mem */ [2] = PWRSTS_OFF_RET, /* tcm1_mem */ [3] = PWRSTS_OFF_RET, /* tcm2_mem */ }, .pwrsts_mem_on = { - [0] = PWRDM_POWER_ON, /* hwa_mem */ - [1] = PWRDM_POWER_ON, /* sl2_mem */ - [2] = PWRDM_POWER_ON, /* tcm1_mem */ - [3] = PWRDM_POWER_ON, /* tcm2_mem */ + [0] = PWRSTS_ON, /* hwa_mem */ + [1] = PWRSTS_ON, /* sl2_mem */ + [2] = PWRSTS_ON, /* tcm1_mem */ + [3] = PWRSTS_ON, /* tcm2_mem */ }, .flags = PWRDM_HAS_LOWPOWERSTATECHANGE, }; @@ -253,10 +253,10 @@ static struct powerdomain cam_44xx_pwrdm = { .pwrsts = PWRSTS_OFF_ON, .banks = 1, .pwrsts_mem_ret = { - [0] = PWRDM_POWER_OFF, /* cam_mem */ + [0] = PWRSTS_OFF, /* cam_mem */ }, .pwrsts_mem_on = { - [0] = PWRDM_POWER_ON, /* cam_mem */ + [0] = PWRSTS_ON, /* cam_mem */ }, .flags = PWRDM_HAS_LOWPOWERSTATECHANGE, }; @@ -271,10 +271,10 @@ static struct powerdomain l3init_44xx_pwrdm = { .pwrsts_logic_ret = PWRSTS_OFF_RET, .banks = 1, .pwrsts_mem_ret = { - [0] = PWRDM_POWER_OFF, /* l3init_bank1 */ + [0] = PWRSTS_OFF, /* l3init_bank1 */ }, .pwrsts_mem_on = { - [0] = PWRDM_POWER_ON, /* l3init_bank1 */ + [0] = PWRSTS_ON, /* l3init_bank1 */ }, .flags = PWRDM_HAS_LOWPOWERSTATECHANGE, }; @@ -289,12 +289,12 @@ static struct powerdomain l4per_44xx_pwrdm = { .pwrsts_logic_ret = PWRSTS_OFF_RET, .banks = 2, .pwrsts_mem_ret = { - [0] = PWRDM_POWER_OFF, /* nonretained_bank */ - [1] = PWRDM_POWER_RET, /* retained_bank */ + [0] = PWRSTS_OFF, /* nonretained_bank */ + [1] = PWRSTS_RET, /* retained_bank */ }, .pwrsts_mem_on = { - [0] = PWRDM_POWER_ON, /* nonretained_bank */ - [1] = PWRDM_POWER_ON, /* retained_bank */ + [0] = PWRSTS_ON, /* nonretained_bank */ + [1] = PWRSTS_ON, /* retained_bank */ }, .flags = PWRDM_HAS_LOWPOWERSTATECHANGE, }; diff --git a/arch/arm/mach-omap2/prcm-common.h b/arch/arm/mach-omap2/prcm-common.h index 87486f55978..0363dcb0ef9 100644 --- a/arch/arm/mach-omap2/prcm-common.h +++ b/arch/arm/mach-omap2/prcm-common.h @@ -121,6 +121,10 @@ #define OMAP24XX_ST_MCSPI2_MASK (1 << 18) #define OMAP24XX_ST_MCSPI1_SHIFT 17 #define OMAP24XX_ST_MCSPI1_MASK (1 << 17) +#define OMAP24XX_ST_MCBSP2_SHIFT 16 +#define OMAP24XX_ST_MCBSP2_MASK (1 << 16) +#define OMAP24XX_ST_MCBSP1_SHIFT 15 +#define OMAP24XX_ST_MCBSP1_MASK (1 << 15) #define OMAP24XX_ST_GPT12_SHIFT 14 #define OMAP24XX_ST_GPT12_MASK (1 << 14) #define OMAP24XX_ST_GPT11_SHIFT 13 @@ -191,6 +195,8 @@ #define OMAP3430_AUTOIDLE_MASK (1 << 0) /* CM_FCLKEN1_CORE, CM_ICLKEN1_CORE, PM_WKEN1_CORE shared bits */ +#define OMAP3430_EN_MMC3_MASK (1 << 30) +#define OMAP3430_EN_MMC3_SHIFT 30 #define OMAP3430_EN_MMC2_MASK (1 << 25) #define OMAP3430_EN_MMC2_SHIFT 25 #define OMAP3430_EN_MMC1_MASK (1 << 24) @@ -231,6 +237,8 @@ #define OMAP3430_EN_HSOTGUSB_SHIFT 4 /* PM_WKST1_CORE, CM_IDLEST1_CORE shared bits */ +#define OMAP3430_ST_MMC3_SHIFT 30 +#define OMAP3430_ST_MMC3_MASK (1 << 30) #define OMAP3430_ST_MMC2_SHIFT 25 #define OMAP3430_ST_MMC2_MASK (1 << 25) #define OMAP3430_ST_MMC1_SHIFT 24 diff --git a/arch/arm/mach-omap2/prcm.c b/arch/arm/mach-omap2/prcm.c index 679bcd28576..6be14389e4f 100644 --- a/arch/arm/mach-omap2/prcm.c +++ b/arch/arm/mach-omap2/prcm.c @@ -24,6 +24,7 @@ #include <linux/io.h> #include <linux/delay.h> +#include <mach/system.h> #include <plat/common.h> #include <plat/prcm.h> #include <plat/irqs.h> @@ -57,7 +58,7 @@ u32 omap_prcm_get_reset_sources(void) EXPORT_SYMBOL(omap_prcm_get_reset_sources); /* Resets clock rates and reboots the system. Only called from system.h */ -void omap_prcm_arch_reset(char mode, const char *cmd) +static void omap_prcm_arch_reset(char mode, const char *cmd) { s16 prcm_offs = 0; @@ -108,6 +109,8 @@ void omap_prcm_arch_reset(char mode, const char *cmd) omap2_prm_read_mod_reg(prcm_offs, OMAP2_RM_RSTCTRL); /* OCP barrier */ } +void (*arch_reset)(char, const char *) = omap_prcm_arch_reset; + /** * omap2_cm_wait_idlest - wait for IDLEST bit to indicate module readiness * @reg: physical address of module IDLEST register diff --git a/arch/arm/mach-omap2/prcm_mpu44xx.h b/arch/arm/mach-omap2/prcm_mpu44xx.h index 3300ff6e3cf..d22d1b43bcc 100644 --- a/arch/arm/mach-omap2/prcm_mpu44xx.h +++ b/arch/arm/mach-omap2/prcm_mpu44xx.h @@ -38,8 +38,8 @@ #define OMAP4430_PRCM_MPU_CPU1_INST 0x0800 /* PRCM_MPU clockdomain register offsets (from instance start) */ -#define OMAP4430_PRCM_MPU_CPU0_MPU_CDOFFS 0x0018 -#define OMAP4430_PRCM_MPU_CPU1_MPU_CDOFFS 0x0018 +#define OMAP4430_PRCM_MPU_CPU0_CPU0_CDOFFS 0x0018 +#define OMAP4430_PRCM_MPU_CPU1_CPU1_CDOFFS 0x0018 /* diff --git a/arch/arm/mach-omap2/prm2xxx_3xxx.c b/arch/arm/mach-omap2/prm2xxx_3xxx.c index ec0362574b5..051213fbc34 100644 --- a/arch/arm/mach-omap2/prm2xxx_3xxx.c +++ b/arch/arm/mach-omap2/prm2xxx_3xxx.c @@ -118,7 +118,8 @@ int omap2_prm_assert_hardreset(s16 prm_mod, u8 shift) /** * omap2_prm_deassert_hardreset - deassert a submodule hardreset line and wait * @prm_mod: PRM submodule base (e.g. CORE_MOD) - * @shift: register bit shift corresponding to the reset line to deassert + * @rst_shift: register bit shift corresponding to the reset line to deassert + * @st_shift: register bit shift for the status of the deasserted submodule * * Some IPs like dsp or iva contain processors that require an HW * reset line to be asserted / deasserted in order to fully enable the @@ -129,27 +130,28 @@ int omap2_prm_assert_hardreset(s16 prm_mod, u8 shift) * -EINVAL upon an argument error, -EEXIST if the submodule was already out * of reset, or -EBUSY if the submodule did not exit reset promptly. */ -int omap2_prm_deassert_hardreset(s16 prm_mod, u8 shift) +int omap2_prm_deassert_hardreset(s16 prm_mod, u8 rst_shift, u8 st_shift) { - u32 mask; + u32 rst, st; int c; if (!(cpu_is_omap24xx() || cpu_is_omap34xx())) return -EINVAL; - mask = 1 << shift; + rst = 1 << rst_shift; + st = 1 << st_shift; /* Check the current status to avoid de-asserting the line twice */ - if (omap2_prm_read_mod_bits_shift(prm_mod, OMAP2_RM_RSTCTRL, mask) == 0) + if (omap2_prm_read_mod_bits_shift(prm_mod, OMAP2_RM_RSTCTRL, rst) == 0) return -EEXIST; /* Clear the reset status by writing 1 to the status bit */ - omap2_prm_rmw_mod_reg_bits(0xffffffff, mask, prm_mod, OMAP2_RM_RSTST); + omap2_prm_rmw_mod_reg_bits(0xffffffff, st, prm_mod, OMAP2_RM_RSTST); /* de-assert the reset control line */ - omap2_prm_rmw_mod_reg_bits(mask, 0, prm_mod, OMAP2_RM_RSTCTRL); + omap2_prm_rmw_mod_reg_bits(rst, 0, prm_mod, OMAP2_RM_RSTCTRL); /* wait the status to be set */ omap_test_timeout(omap2_prm_read_mod_bits_shift(prm_mod, OMAP2_RM_RSTST, - mask), + st), MAX_MODULE_HARDRESET_WAIT, c); return (c == MAX_MODULE_HARDRESET_WAIT) ? -EBUSY : 0; diff --git a/arch/arm/mach-omap2/prm2xxx_3xxx.h b/arch/arm/mach-omap2/prm2xxx_3xxx.h index 49654c8d18f..a1fc62a39db 100644 --- a/arch/arm/mach-omap2/prm2xxx_3xxx.h +++ b/arch/arm/mach-omap2/prm2xxx_3xxx.h @@ -282,7 +282,8 @@ static inline int omap2_prm_assert_hardreset(s16 prm_mod, u8 shift) "not suppose to be used on omap4\n"); return 0; } -static inline int omap2_prm_deassert_hardreset(s16 prm_mod, u8 shift) +static inline int omap2_prm_deassert_hardreset(s16 prm_mod, u8 rst_shift, + u8 st_shift) { WARN(1, "prm: omap2xxx/omap3xxx specific function and " "not suppose to be used on omap4\n"); @@ -300,7 +301,7 @@ extern u32 omap2_prm_read_mod_bits_shift(s16 domain, s16 idx, u32 mask); /* These omap2_ PRM functions apply to both OMAP2 and 3 */ extern int omap2_prm_is_hardreset_asserted(s16 prm_mod, u8 shift); extern int omap2_prm_assert_hardreset(s16 prm_mod, u8 shift); -extern int omap2_prm_deassert_hardreset(s16 prm_mod, u8 shift); +extern int omap2_prm_deassert_hardreset(s16 prm_mod, u8 rst_shift, u8 st_shift); #endif /* CONFIG_ARCH_OMAP4 */ #endif diff --git a/arch/arm/mach-omap2/serial.c b/arch/arm/mach-omap2/serial.c index 32e91a9c8b6..1ac361b7b8c 100644 --- a/arch/arm/mach-omap2/serial.c +++ b/arch/arm/mach-omap2/serial.c @@ -486,7 +486,7 @@ static void omap_uart_idle_init(struct omap_uart_state *uart) mod_timer(&uart->timer, jiffies + uart->timeout); omap_uart_smart_idle_enable(uart, 0); - if (cpu_is_omap34xx()) { + if (cpu_is_omap34xx() && !cpu_is_ti816x()) { u32 mod = (uart->num > 1) ? OMAP3430_PER_MOD : CORE_MOD; u32 wk_mask = 0; u32 padconf = 0; @@ -655,7 +655,7 @@ static void serial_out_override(struct uart_port *up, int offset, int value) } #endif -void __init omap_serial_early_init(void) +static int __init omap_serial_early_init(void) { int i = 0; @@ -672,7 +672,7 @@ void __init omap_serial_early_init(void) uart = kzalloc(sizeof(struct omap_uart_state), GFP_KERNEL); if (WARN_ON(!uart)) - return; + return -ENODEV; uart->oh = oh; uart->num = i++; @@ -680,7 +680,7 @@ void __init omap_serial_early_init(void) num_uarts++; /* - * NOTE: omap_hwmod_init() has not yet been called, + * NOTE: omap_hwmod_setup*() has not yet been called, * so no hwmod functions will work yet. */ @@ -691,7 +691,10 @@ void __init omap_serial_early_init(void) */ uart->oh->flags |= HWMOD_INIT_NO_IDLE | HWMOD_INIT_NO_RESET; } while (1); + + return 0; } +core_initcall(omap_serial_early_init); /** * omap_serial_init_port() - initialize single serial port @@ -759,13 +762,13 @@ void __init omap_serial_init_port(struct omap_board_data *bdata) p->private_data = uart; /* - * omap44xx: Never read empty UART fifo + * 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()) + 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) @@ -847,7 +850,7 @@ void __init omap_serial_init_port(struct omap_board_data *bdata) } /* Enable the MDR1 errata for OMAP3 */ - if (cpu_is_omap34xx()) + if (cpu_is_omap34xx() && !cpu_is_ti816x()) uart->errata |= UART_ERRATA_i202_MDR1_ACCESS; } diff --git a/arch/arm/mach-omap2/sleep34xx.S b/arch/arm/mach-omap2/sleep34xx.S index 951a0be66cf..63f10669571 100644 --- a/arch/arm/mach-omap2/sleep34xx.S +++ b/arch/arm/mach-omap2/sleep34xx.S @@ -64,6 +64,11 @@ #define SDRC_DLLA_STATUS_V OMAP34XX_SDRC_REGADDR(SDRC_DLLA_STATUS) #define SDRC_DLLA_CTRL_V OMAP34XX_SDRC_REGADDR(SDRC_DLLA_CTRL) +/* + * This file needs be built unconditionally as ARM to interoperate correctly + * with non-Thumb-2-capable firmware. + */ + .arm /* * API functions @@ -82,6 +87,8 @@ ENTRY(get_restore_pointer) stmfd sp!, {lr} @ save registers on stack adr r0, restore ldmfd sp!, {pc} @ restore regs and return +ENDPROC(get_restore_pointer) + .align ENTRY(get_restore_pointer_sz) .word . - get_restore_pointer @@ -91,6 +98,8 @@ ENTRY(get_omap3630_restore_pointer) stmfd sp!, {lr} @ save registers on stack adr r0, restore_3630 ldmfd sp!, {pc} @ restore regs and return +ENDPROC(get_omap3630_restore_pointer) + .align ENTRY(get_omap3630_restore_pointer_sz) .word . - get_omap3630_restore_pointer @@ -100,6 +109,8 @@ ENTRY(get_es3_restore_pointer) stmfd sp!, {lr} @ save registers on stack adr r0, restore_es3 ldmfd sp!, {pc} @ restore regs and return +ENDPROC(get_es3_restore_pointer) + .align ENTRY(get_es3_restore_pointer_sz) .word . - get_es3_restore_pointer @@ -113,8 +124,10 @@ ENTRY(enable_omap3630_toggle_l2_on_restore) stmfd sp!, {lr} @ save registers on stack /* Setup so that we will disable and enable l2 */ mov r1, #0x1 - str r1, l2dis_3630 + adrl r2, l2dis_3630 @ may be too distant for plain adr + str r1, [r2] ldmfd sp!, {pc} @ restore regs and return +ENDPROC(enable_omap3630_toggle_l2_on_restore) .text /* Function to call rom code to save secure ram context */ @@ -132,20 +145,22 @@ ENTRY(save_secure_ram_context) mov r1, #0 @ set task id for ROM code in r1 mov r2, #4 @ set some flags in r2, r6 mov r6, #0xff - mcr p15, 0, r0, c7, c10, 4 @ data write barrier - mcr p15, 0, r0, c7, c10, 5 @ data memory barrier - .word 0xE1600071 @ call SMI monitor (smi #1) + dsb @ data write barrier + dmb @ data memory barrier + smc #1 @ call SMI monitor (smi #1) nop nop nop nop ldmfd sp!, {r1-r12, pc} + .align sram_phy_addr_mask: .word SRAM_BASE_P high_mask: .word 0xffff api_params: .word 0x4, 0x0, 0x0, 0x1, 0x1 +ENDPROC(save_secure_ram_context) ENTRY(save_secure_ram_context_sz) .word . - save_secure_ram_context @@ -175,12 +190,12 @@ ENTRY(omap34xx_cpu_suspend) stmfd sp!, {r0-r12, lr} @ save registers on stack /* - * r0 contains restore pointer in sdram + * r0 contains CPU context save/restore pointer in sdram * r1 contains information about saving context: * 0 - No context lost * 1 - Only L1 and logic lost - * 2 - Only L2 lost - * 3 - Both L1 and L2 lost + * 2 - Only L2 lost (Even L1 is retained we clean it along with L2) + * 3 - Both L1 and L2 lost and logic lost */ /* Directly jump to WFI is the context save is not required */ @@ -201,89 +216,74 @@ save_context_wfi: beq clean_caches l1_logic_lost: - /* Store sp and spsr to SDRAM */ - mov r4, sp - mrs r5, spsr - mov r6, lr + mov r4, sp @ Store sp + mrs r5, spsr @ Store spsr + mov r6, lr @ Store lr stmia r8!, {r4-r6} - /* Save all ARM registers */ - /* Coprocessor access control register */ - mrc p15, 0, r6, c1, c0, 2 - stmia r8!, {r6} - /* TTBR0, TTBR1 and Translation table base control */ - mrc p15, 0, r4, c2, c0, 0 - mrc p15, 0, r5, c2, c0, 1 - mrc p15, 0, r6, c2, c0, 2 - stmia r8!, {r4-r6} - /* - * Domain access control register, data fault status register, - * and instruction fault status register - */ - mrc p15, 0, r4, c3, c0, 0 - mrc p15, 0, r5, c5, c0, 0 - mrc p15, 0, r6, c5, c0, 1 - stmia r8!, {r4-r6} - /* - * Data aux fault status register, instruction aux fault status, - * data fault address register and instruction fault address register - */ - mrc p15, 0, r4, c5, c1, 0 - mrc p15, 0, r5, c5, c1, 1 - mrc p15, 0, r6, c6, c0, 0 - mrc p15, 0, r7, c6, c0, 2 - stmia r8!, {r4-r7} - /* - * user r/w thread and process ID, user r/o thread and process ID, - * priv only thread and process ID, cache size selection - */ - mrc p15, 0, r4, c13, c0, 2 - mrc p15, 0, r5, c13, c0, 3 - mrc p15, 0, r6, c13, c0, 4 - mrc p15, 2, r7, c0, c0, 0 + + mrc p15, 0, r4, c1, c0, 2 @ Coprocessor access control register + mrc p15, 0, r5, c2, c0, 0 @ TTBR0 + mrc p15, 0, r6, c2, c0, 1 @ TTBR1 + mrc p15, 0, r7, c2, c0, 2 @ TTBCR stmia r8!, {r4-r7} - /* Data TLB lockdown, instruction TLB lockdown registers */ - mrc p15, 0, r5, c10, c0, 0 - mrc p15, 0, r6, c10, c0, 1 - stmia r8!, {r5-r6} - /* Secure or non secure vector base address, FCSE PID, Context PID*/ - mrc p15, 0, r4, c12, c0, 0 - mrc p15, 0, r5, c13, c0, 0 - mrc p15, 0, r6, c13, c0, 1 - stmia r8!, {r4-r6} - /* Primary remap, normal remap registers */ - mrc p15, 0, r4, c10, c2, 0 - mrc p15, 0, r5, c10, c2, 1 - stmia r8!,{r4-r5} - /* Store current cpsr*/ - mrs r2, cpsr - stmia r8!, {r2} + mrc p15, 0, r4, c3, c0, 0 @ Domain access Control Register + mrc p15, 0, r5, c10, c2, 0 @ PRRR + mrc p15, 0, r6, c10, c2, 1 @ NMRR + stmia r8!,{r4-r6} - mrc p15, 0, r4, c1, c0, 0 - /* save control register */ + mrc p15, 0, r4, c13, c0, 1 @ Context ID + mrc p15, 0, r5, c13, c0, 2 @ User r/w thread and process ID + mrc p15, 0, r6, c12, c0, 0 @ Secure or NS vector base address + mrs r7, cpsr @ Store current cpsr + stmia r8!, {r4-r7} + + mrc p15, 0, r4, c1, c0, 0 @ save control register stmia r8!, {r4} clean_caches: /* - * Clean Data or unified cache to POU - * How to invalidate only L1 cache???? - #FIX_ME# - * mcr p15, 0, r11, c7, c11, 1 - */ - cmp r1, #0x1 @ Check whether L2 inval is required - beq omap3_do_wfi - -clean_l2: - /* * jump out to kernel flush routine * - reuse that code is better * - it executes in a cached space so is faster than refetch per-block * - should be faster and will change with kernel * - 'might' have to copy address, load and jump to it + * Flush all data from the L1 data cache before disabling + * SCTLR.C bit. */ ldr r1, kernel_flush mov lr, pc bx r1 + /* + * Clear the SCTLR.C bit to prevent further data cache + * allocation. Clearing SCTLR.C would make all the data accesses + * strongly ordered and would not hit the cache. + */ + mrc p15, 0, r0, c1, c0, 0 + bic r0, r0, #(1 << 2) @ Disable the C bit + mcr p15, 0, r0, c1, c0, 0 + isb + + /* + * Invalidate L1 data cache. Even though only invalidate is + * necessary exported flush API is used here. Doing clean + * on already clean cache would be almost NOP. + */ + ldr r1, kernel_flush + blx r1 + /* + * The kernel doesn't interwork: v7_flush_dcache_all in particluar will + * always return in Thumb state when CONFIG_THUMB2_KERNEL is enabled. + * This sequence switches back to ARM. Note that .align may insert a + * nop: bx pc needs to be word-aligned in order to work. + */ + THUMB( .thumb ) + THUMB( .align ) + THUMB( bx pc ) + THUMB( nop ) + .arm + omap3_do_wfi: ldr r4, sdrc_power @ read the SDRC_POWER register ldr r5, [r4] @ read the contents of SDRC_POWER @@ -291,9 +291,8 @@ omap3_do_wfi: str r5, [r4] @ write back to SDRC_POWER register /* Data memory barrier and Data sync barrier */ - mov r1, #0 - mcr p15, 0, r1, c7, c10, 4 - mcr p15, 0, r1, c7, c10, 5 + dsb + dmb /* * =================================== @@ -319,6 +318,12 @@ omap3_do_wfi: nop bl wait_sdrc_ok + mrc p15, 0, r0, c1, c0, 0 + tst r0, #(1 << 2) @ Check C bit enabled? + orreq r0, r0, #(1 << 2) @ Enable the C bit if cleared + mcreq p15, 0, r0, c1, c0, 0 + isb + /* * =================================== * == Exit point from non-OFF modes == @@ -408,9 +413,9 @@ skipl2dis: mov r2, #4 @ set some flags in r2, r6 mov r6, #0xff adr r3, l2_inv_api_params @ r3 points to dummy parameters - mcr p15, 0, r0, c7, c10, 4 @ data write barrier - mcr p15, 0, r0, c7, c10, 5 @ data memory barrier - .word 0xE1600071 @ call SMI monitor (smi #1) + dsb @ data write barrier + dmb @ data memory barrier + smc #1 @ call SMI monitor (smi #1) /* Write to Aux control register to set some bits */ mov r0, #42 @ set service ID for PPA mov r12, r0 @ copy secure Service ID in r12 @@ -419,9 +424,9 @@ skipl2dis: mov r6, #0xff ldr r4, scratchpad_base ldr r3, [r4, #0xBC] @ r3 points to parameters - mcr p15, 0, r0, c7, c10, 4 @ data write barrier - mcr p15, 0, r0, c7, c10, 5 @ data memory barrier - .word 0xE1600071 @ call SMI monitor (smi #1) + dsb @ data write barrier + dmb @ data memory barrier + smc #1 @ call SMI monitor (smi #1) #ifdef CONFIG_OMAP3_L2_AUX_SECURE_SAVE_RESTORE /* Restore L2 aux control register */ @@ -434,29 +439,30 @@ skipl2dis: ldr r4, scratchpad_base ldr r3, [r4, #0xBC] adds r3, r3, #8 @ r3 points to parameters - mcr p15, 0, r0, c7, c10, 4 @ data write barrier - mcr p15, 0, r0, c7, c10, 5 @ data memory barrier - .word 0xE1600071 @ call SMI monitor (smi #1) + dsb @ data write barrier + dmb @ data memory barrier + smc #1 @ call SMI monitor (smi #1) #endif b logic_l1_restore + .align l2_inv_api_params: .word 0x1, 0x00 l2_inv_gp: /* Execute smi to invalidate L2 cache */ mov r12, #0x1 @ set up to invalidate L2 - .word 0xE1600070 @ Call SMI monitor (smieq) + smc #0 @ Call SMI monitor (smieq) /* Write to Aux control register to set some bits */ ldr r4, scratchpad_base ldr r3, [r4,#0xBC] ldr r0, [r3,#4] mov r12, #0x3 - .word 0xE1600070 @ Call SMI monitor (smieq) + smc #0 @ Call SMI monitor (smieq) ldr r4, scratchpad_base ldr r3, [r4,#0xBC] ldr r0, [r3,#12] mov r12, #0x2 - .word 0xE1600070 @ Call SMI monitor (smieq) + smc #0 @ Call SMI monitor (smieq) logic_l1_restore: ldr r1, l2dis_3630 cmp r1, #0x1 @ Test if L2 re-enable needed on 3630 @@ -475,68 +481,29 @@ skipl2reen: ldr r4, scratchpad_base ldr r3, [r4,#0xBC] adds r3, r3, #16 + ldmia r3!, {r4-r6} - mov sp, r4 - msr spsr_cxsf, r5 - mov lr, r6 - - ldmia r3!, {r4-r9} - /* Coprocessor access Control Register */ - mcr p15, 0, r4, c1, c0, 2 - - /* TTBR0 */ - MCR p15, 0, r5, c2, c0, 0 - /* TTBR1 */ - MCR p15, 0, r6, c2, c0, 1 - /* Translation table base control register */ - MCR p15, 0, r7, c2, c0, 2 - /* Domain access Control Register */ - MCR p15, 0, r8, c3, c0, 0 - /* Data fault status Register */ - MCR p15, 0, r9, c5, c0, 0 - - ldmia r3!,{r4-r8} - /* Instruction fault status Register */ - MCR p15, 0, r4, c5, c0, 1 - /* Data Auxiliary Fault Status Register */ - MCR p15, 0, r5, c5, c1, 0 - /* Instruction Auxiliary Fault Status Register*/ - MCR p15, 0, r6, c5, c1, 1 - /* Data Fault Address Register */ - MCR p15, 0, r7, c6, c0, 0 - /* Instruction Fault Address Register*/ - MCR p15, 0, r8, c6, c0, 2 - ldmia r3!,{r4-r7} + mov sp, r4 @ Restore sp + msr spsr_cxsf, r5 @ Restore spsr + mov lr, r6 @ Restore lr + + ldmia r3!, {r4-r7} + mcr p15, 0, r4, c1, c0, 2 @ Coprocessor access Control Register + mcr p15, 0, r5, c2, c0, 0 @ TTBR0 + mcr p15, 0, r6, c2, c0, 1 @ TTBR1 + mcr p15, 0, r7, c2, c0, 2 @ TTBCR - /* User r/w thread and process ID */ - MCR p15, 0, r4, c13, c0, 2 - /* User ro thread and process ID */ - MCR p15, 0, r5, c13, c0, 3 - /* Privileged only thread and process ID */ - MCR p15, 0, r6, c13, c0, 4 - /* Cache size selection */ - MCR p15, 2, r7, c0, c0, 0 - ldmia r3!,{r4-r8} - /* Data TLB lockdown registers */ - MCR p15, 0, r4, c10, c0, 0 - /* Instruction TLB lockdown registers */ - MCR p15, 0, r5, c10, c0, 1 - /* Secure or Nonsecure Vector Base Address */ - MCR p15, 0, r6, c12, c0, 0 - /* FCSE PID */ - MCR p15, 0, r7, c13, c0, 0 - /* Context PID */ - MCR p15, 0, r8, c13, c0, 1 - - ldmia r3!,{r4-r5} - /* Primary memory remap register */ - MCR p15, 0, r4, c10, c2, 0 - /* Normal memory remap register */ - MCR p15, 0, r5, c10, c2, 1 - - /* Restore cpsr */ - ldmia r3!,{r4} @ load CPSR from SDRAM - msr cpsr, r4 @ store cpsr + ldmia r3!,{r4-r6} + mcr p15, 0, r4, c3, c0, 0 @ Domain access Control Register + mcr p15, 0, r5, c10, c2, 0 @ PRRR + mcr p15, 0, r6, c10, c2, 1 @ NMRR + + + ldmia r3!,{r4-r7} + mcr p15, 0, r4, c13, c0, 1 @ Context ID + mcr p15, 0, r5, c13, c0, 2 @ User r/w thread and process ID + mrc p15, 0, r6, c12, c0, 0 @ Secure or NS vector base address + msr cpsr, r7 @ store cpsr /* Enabling MMU here */ mrc p15, 0, r7, c2, c0, 2 @ Read TTBRControl @@ -594,12 +561,17 @@ usettbr0: ldr r2, cache_pred_disable_mask and r4, r2 mcr p15, 0, r4, c1, c0, 0 + dsb + isb + ldr r0, =restoremmu_on + bx r0 /* * ============================== * == Exit point from OFF mode == * ============================== */ +restoremmu_on: ldmfd sp!, {r0-r12, pc} @ restore regs and return @@ -609,6 +581,7 @@ usettbr0: /* This function implements the erratum ID i443 WA, applies to 34xx >= ES3.0 */ .text + .align 3 ENTRY(es3_sdrc_fix) ldr r4, sdrc_syscfg @ get config addr ldr r5, [r4] @ get value @@ -636,6 +609,7 @@ ENTRY(es3_sdrc_fix) str r5, [r4] @ kick off refreshes bx lr + .align sdrc_syscfg: .word SDRC_SYSCONFIG_P sdrc_mr_0: @@ -650,6 +624,7 @@ sdrc_emr2_1: .word SDRC_EMR2_1_P sdrc_manual_1: .word SDRC_MANUAL_1_P +ENDPROC(es3_sdrc_fix) ENTRY(es3_sdrc_fix_sz) .word . - es3_sdrc_fix @@ -684,6 +659,12 @@ wait_sdrc_ready: bic r5, r5, #0x40 str r5, [r4] +/* + * PC-relative stores lead to undefined behaviour in Thumb-2: use a r7 as a + * base instead. + * Be careful not to clobber r7 when maintaing this code. + */ + is_dll_in_lock_mode: /* Is dll in lock mode? */ ldr r4, sdrc_dlla_ctrl @@ -691,10 +672,11 @@ is_dll_in_lock_mode: tst r5, #0x4 bxne lr @ Return if locked /* wait till dll locks */ + adr r7, kick_counter wait_dll_lock_timed: ldr r4, wait_dll_lock_counter add r4, r4, #1 - str r4, wait_dll_lock_counter + str r4, [r7, #wait_dll_lock_counter - kick_counter] ldr r4, sdrc_dlla_status /* Wait 20uS for lock */ mov r6, #8 @@ -720,9 +702,10 @@ kick_dll: dsb ldr r4, kick_counter add r4, r4, #1 - str r4, kick_counter + str r4, [r7] @ kick_counter b wait_dll_lock_timed + .align cm_idlest1_core: .word CM_IDLEST1_CORE_V cm_idlest_ckgen: @@ -765,6 +748,7 @@ kick_counter: .word 0 wait_dll_lock_counter: .word 0 +ENDPROC(omap34xx_cpu_suspend) ENTRY(omap34xx_cpu_suspend_sz) .word . - omap34xx_cpu_suspend diff --git a/arch/arm/mach-omap2/smartreflex-class3.c b/arch/arm/mach-omap2/smartreflex-class3.c index 60e70552b4c..f438cf4d847 100644 --- a/arch/arm/mach-omap2/smartreflex-class3.c +++ b/arch/arm/mach-omap2/smartreflex-class3.c @@ -11,7 +11,7 @@ * published by the Free Software Foundation. */ -#include <plat/smartreflex.h> +#include "smartreflex.h" static int sr_class3_enable(struct voltagedomain *voltdm) { diff --git a/arch/arm/mach-omap2/smartreflex.c b/arch/arm/mach-omap2/smartreflex.c index 1a777e34d0c..8f674c9442b 100644 --- a/arch/arm/mach-omap2/smartreflex.c +++ b/arch/arm/mach-omap2/smartreflex.c @@ -26,9 +26,9 @@ #include <linux/pm_runtime.h> #include <plat/common.h> -#include <plat/smartreflex.h> #include "pm.h" +#include "smartreflex.h" #define SMARTREFLEX_NAME_LEN 16 #define NVALUE_NAME_LEN 40 @@ -54,6 +54,7 @@ struct omap_sr { struct list_head node; struct omap_sr_nvalue_table *nvalue_table; struct voltagedomain *voltdm; + struct dentry *dbg_dir; }; /* sr_list contains all the instances of smartreflex module */ @@ -260,9 +261,11 @@ static int sr_late_init(struct omap_sr *sr_info) if (sr_class->class_type == SR_CLASS2 && sr_class->notify_flags && sr_info->irq) { - name = kzalloc(SMARTREFLEX_NAME_LEN + 1, GFP_KERNEL); - strcpy(name, "sr_"); - strcat(name, sr_info->voltdm->name); + name = kasprintf(GFP_KERNEL, "sr_%s", sr_info->voltdm->name); + if (name == NULL) { + ret = -ENOMEM; + goto error; + } ret = request_irq(sr_info->irq, sr_interrupt, 0, name, (void *)sr_info); if (ret) @@ -821,7 +824,7 @@ static int __init omap_sr_probe(struct platform_device *pdev) struct omap_sr *sr_info = kzalloc(sizeof(struct omap_sr), GFP_KERNEL); struct omap_sr_data *pdata = pdev->dev.platform_data; struct resource *mem, *irq; - struct dentry *vdd_dbg_dir, *dbg_dir, *nvalue_dir; + struct dentry *vdd_dbg_dir, *nvalue_dir; struct omap_volt_data *volt_data; int i, ret = 0; @@ -896,24 +899,24 @@ static int __init omap_sr_probe(struct platform_device *pdev) goto err_release_region; } - dbg_dir = debugfs_create_dir("smartreflex", vdd_dbg_dir); - if (IS_ERR(dbg_dir)) { + sr_info->dbg_dir = debugfs_create_dir("smartreflex", vdd_dbg_dir); + if (IS_ERR(sr_info->dbg_dir)) { dev_err(&pdev->dev, "%s: Unable to create debugfs directory\n", __func__); - ret = PTR_ERR(dbg_dir); + ret = PTR_ERR(sr_info->dbg_dir); goto err_release_region; } - (void) debugfs_create_file("autocomp", S_IRUGO | S_IWUSR, dbg_dir, - (void *)sr_info, &pm_sr_fops); - (void) debugfs_create_x32("errweight", S_IRUGO, dbg_dir, + (void) debugfs_create_file("autocomp", S_IRUGO | S_IWUSR, + sr_info->dbg_dir, (void *)sr_info, &pm_sr_fops); + (void) debugfs_create_x32("errweight", S_IRUGO, sr_info->dbg_dir, &sr_info->err_weight); - (void) debugfs_create_x32("errmaxlimit", S_IRUGO, dbg_dir, + (void) debugfs_create_x32("errmaxlimit", S_IRUGO, sr_info->dbg_dir, &sr_info->err_maxlimit); - (void) debugfs_create_x32("errminlimit", S_IRUGO, dbg_dir, + (void) debugfs_create_x32("errminlimit", S_IRUGO, sr_info->dbg_dir, &sr_info->err_minlimit); - nvalue_dir = debugfs_create_dir("nvalue", dbg_dir); + nvalue_dir = debugfs_create_dir("nvalue", sr_info->dbg_dir); if (IS_ERR(nvalue_dir)) { dev_err(&pdev->dev, "%s: Unable to create debugfs directory" "for n-values\n", __func__); @@ -970,6 +973,8 @@ static int __devexit omap_sr_remove(struct platform_device *pdev) if (sr_info->autocomp_active) sr_stop_vddautocomp(sr_info); + if (sr_info->dbg_dir) + debugfs_remove_recursive(sr_info->dbg_dir); list_del(&sr_info->node); iounmap(sr_info->base); diff --git a/arch/arm/plat-omap/include/plat/smartreflex.h b/arch/arm/mach-omap2/smartreflex.h index 6568c885f37..5f35b9e2555 100644 --- a/arch/arm/plat-omap/include/plat/smartreflex.h +++ b/arch/arm/mach-omap2/smartreflex.h @@ -21,7 +21,8 @@ #define __ASM_ARM_OMAP_SMARTREFLEX_H #include <linux/platform_device.h> -#include <plat/voltage.h> + +#include "voltage.h" /* * Different Smartreflex IPs version. The v1 is the 65nm version used in diff --git a/arch/arm/mach-omap2/sr_device.c b/arch/arm/mach-omap2/sr_device.c index b1e0af18a26..10d3c5ee801 100644 --- a/arch/arm/mach-omap2/sr_device.c +++ b/arch/arm/mach-omap2/sr_device.c @@ -23,9 +23,9 @@ #include <linux/io.h> #include <plat/omap_device.h> -#include <plat/smartreflex.h> -#include <plat/voltage.h> +#include "smartreflex.h" +#include "voltage.h" #include "control.h" #include "pm.h" diff --git a/arch/arm/mach-omap2/sram34xx.S b/arch/arm/mach-omap2/sram34xx.S index 25011ca2145..6f5849aaa7c 100644 --- a/arch/arm/mach-omap2/sram34xx.S +++ b/arch/arm/mach-omap2/sram34xx.S @@ -34,6 +34,12 @@ #include "sdrc.h" #include "cm2xxx_3xxx.h" +/* + * This file needs be built unconditionally as ARM to interoperate correctly + * with non-Thumb-2-capable firmware. + */ + .arm + .text /* r1 parameters */ @@ -117,24 +123,36 @@ ENTRY(omap3_sram_configure_core_dpll) @ pull the extra args off the stack @ and store them in SRAM + +/* + * PC-relative stores are deprecated in ARMv7 and lead to undefined behaviour + * in Thumb-2: use a r7 as a base instead. + * Be careful not to clobber r7 when maintaing this file. + */ + THUMB( adr r7, omap3_sram_configure_core_dpll ) + .macro strtext Rt:req, label:req + ARM( str \Rt, \label ) + THUMB( str \Rt, [r7, \label - omap3_sram_configure_core_dpll] ) + .endm + ldr r4, [sp, #52] - str r4, omap_sdrc_rfr_ctrl_0_val + strtext r4, omap_sdrc_rfr_ctrl_0_val ldr r4, [sp, #56] - str r4, omap_sdrc_actim_ctrl_a_0_val + strtext r4, omap_sdrc_actim_ctrl_a_0_val ldr r4, [sp, #60] - str r4, omap_sdrc_actim_ctrl_b_0_val + strtext r4, omap_sdrc_actim_ctrl_b_0_val ldr r4, [sp, #64] - str r4, omap_sdrc_mr_0_val + strtext r4, omap_sdrc_mr_0_val ldr r4, [sp, #68] - str r4, omap_sdrc_rfr_ctrl_1_val + strtext r4, omap_sdrc_rfr_ctrl_1_val cmp r4, #0 @ if SDRC_RFR_CTRL_1 is 0, beq skip_cs1_params @ do not use cs1 params ldr r4, [sp, #72] - str r4, omap_sdrc_actim_ctrl_a_1_val + strtext r4, omap_sdrc_actim_ctrl_a_1_val ldr r4, [sp, #76] - str r4, omap_sdrc_actim_ctrl_b_1_val + strtext r4, omap_sdrc_actim_ctrl_b_1_val ldr r4, [sp, #80] - str r4, omap_sdrc_mr_1_val + strtext r4, omap_sdrc_mr_1_val skip_cs1_params: mrc p15, 0, r8, c1, c0, 0 @ read ctrl register bic r10, r8, #0x800 @ clear Z-bit, disable branch prediction @@ -272,6 +290,7 @@ skip_cs1_prog: ldr r12, [r11] @ posted-write barrier for SDRC bx lr + .align omap3_sdrc_power: .word OMAP34XX_SDRC_REGADDR(SDRC_POWER) omap3_cm_clksel1_pll: @@ -320,6 +339,7 @@ omap3_sdrc_dlla_ctrl: .word OMAP34XX_SDRC_REGADDR(SDRC_DLLA_CTRL) core_m2_mask_val: .word 0x07FFFFFF +ENDPROC(omap3_sram_configure_core_dpll) ENTRY(omap3_sram_configure_core_dpll_sz) .word . - omap3_sram_configure_core_dpll diff --git a/arch/arm/mach-omap2/timer-gp.c b/arch/arm/mach-omap2/timer-gp.c index 0fc550e7e48..3b9cf85f4bb 100644 --- a/arch/arm/mach-omap2/timer-gp.c +++ b/arch/arm/mach-omap2/timer-gp.c @@ -40,10 +40,11 @@ #include <plat/dmtimer.h> #include <asm/localtimer.h> #include <asm/sched_clock.h> +#include <plat/common.h> +#include <plat/omap_hwmod.h> #include "timer-gp.h" -#include <plat/common.h> /* MAX_GPTIMER_ID: number of GPTIMERs on the chip */ #define MAX_GPTIMER_ID 12 @@ -133,9 +134,13 @@ static void __init omap2_gp_clockevent_init(void) { u32 tick_rate; int src; + char clockevent_hwmod_name[8]; /* 8 = sizeof("timerXX0") */ inited = 1; + sprintf(clockevent_hwmod_name, "timer%d", gptimer_id); + omap_hwmod_setup_one(clockevent_hwmod_name); + gptimer = omap_dm_timer_request_specific(gptimer_id); BUG_ON(gptimer == NULL); gptimer_wakeup = gptimer; diff --git a/arch/arm/mach-omap2/usb-musb.c b/arch/arm/mach-omap2/usb-musb.c index 241fc94b411..35559f77e2d 100644 --- a/arch/arm/mach-omap2/usb-musb.c +++ b/arch/arm/mach-omap2/usb-musb.c @@ -30,118 +30,11 @@ #include <mach/irqs.h> #include <mach/am35xx.h> #include <plat/usb.h> -#include "control.h" +#include <plat/omap_device.h> +#include "mux.h" #if defined(CONFIG_USB_MUSB_OMAP2PLUS) || defined (CONFIG_USB_MUSB_AM35X) -static void am35x_musb_reset(void) -{ - u32 regval; - - /* Reset the musb interface */ - regval = omap_ctrl_readl(AM35XX_CONTROL_IP_SW_RESET); - - regval |= AM35XX_USBOTGSS_SW_RST; - omap_ctrl_writel(regval, AM35XX_CONTROL_IP_SW_RESET); - - regval &= ~AM35XX_USBOTGSS_SW_RST; - omap_ctrl_writel(regval, AM35XX_CONTROL_IP_SW_RESET); - - regval = omap_ctrl_readl(AM35XX_CONTROL_IP_SW_RESET); -} - -static void am35x_musb_phy_power(u8 on) -{ - unsigned long timeout = jiffies + msecs_to_jiffies(100); - u32 devconf2; - - if (on) { - /* - * Start the on-chip PHY and its PLL. - */ - devconf2 = omap_ctrl_readl(AM35XX_CONTROL_DEVCONF2); - - devconf2 &= ~(CONF2_RESET | CONF2_PHYPWRDN | CONF2_OTGPWRDN); - devconf2 |= CONF2_PHY_PLLON; - - omap_ctrl_writel(devconf2, AM35XX_CONTROL_DEVCONF2); - - pr_info(KERN_INFO "Waiting for PHY clock good...\n"); - while (!(omap_ctrl_readl(AM35XX_CONTROL_DEVCONF2) - & CONF2_PHYCLKGD)) { - cpu_relax(); - - if (time_after(jiffies, timeout)) { - pr_err(KERN_ERR "musb PHY clock good timed out\n"); - break; - } - } - } else { - /* - * Power down the on-chip PHY. - */ - devconf2 = omap_ctrl_readl(AM35XX_CONTROL_DEVCONF2); - - devconf2 &= ~CONF2_PHY_PLLON; - devconf2 |= CONF2_PHYPWRDN | CONF2_OTGPWRDN; - omap_ctrl_writel(devconf2, AM35XX_CONTROL_DEVCONF2); - } -} - -static void am35x_musb_clear_irq(void) -{ - u32 regval; - - regval = omap_ctrl_readl(AM35XX_CONTROL_LVL_INTR_CLEAR); - regval |= AM35XX_USBOTGSS_INT_CLR; - omap_ctrl_writel(regval, AM35XX_CONTROL_LVL_INTR_CLEAR); - regval = omap_ctrl_readl(AM35XX_CONTROL_LVL_INTR_CLEAR); -} - -static void am35x_musb_set_mode(u8 musb_mode) -{ - u32 devconf2 = omap_ctrl_readl(AM35XX_CONTROL_DEVCONF2); - - devconf2 &= ~CONF2_OTGMODE; - switch (musb_mode) { -#ifdef CONFIG_USB_MUSB_HDRC_HCD - case MUSB_HOST: /* Force VBUS valid, ID = 0 */ - devconf2 |= CONF2_FORCE_HOST; - break; -#endif -#ifdef CONFIG_USB_GADGET_MUSB_HDRC - case MUSB_PERIPHERAL: /* Force VBUS valid, ID = 1 */ - devconf2 |= CONF2_FORCE_DEVICE; - break; -#endif -#ifdef CONFIG_USB_MUSB_OTG - case MUSB_OTG: /* Don't override the VBUS/ID comparators */ - devconf2 |= CONF2_NO_OVERRIDE; - break; -#endif - default: - pr_info(KERN_INFO "Unsupported mode %u\n", musb_mode); - } - - omap_ctrl_writel(devconf2, AM35XX_CONTROL_DEVCONF2); -} - -static struct resource musb_resources[] = { - [0] = { /* start and end set dynamically */ - .flags = IORESOURCE_MEM, - }, - [1] = { /* general IRQ */ - .start = INT_243X_HS_USB_MC, - .flags = IORESOURCE_IRQ, - .name = "mc", - }, - [2] = { /* DMA IRQ */ - .start = INT_243X_HS_USB_DMA, - .flags = IORESOURCE_IRQ, - .name = "dma", - }, -}; - static struct musb_hdrc_config musb_config = { .multipoint = 1, .dyn_fifo = 1, @@ -169,38 +62,65 @@ static struct musb_hdrc_platform_data musb_plat = { static u64 musb_dmamask = DMA_BIT_MASK(32); -static struct platform_device musb_device = { - .name = "musb-omap2430", - .id = -1, - .dev = { - .dma_mask = &musb_dmamask, - .coherent_dma_mask = DMA_BIT_MASK(32), - .platform_data = &musb_plat, +static struct omap_device_pm_latency omap_musb_latency[] = { + { + .deactivate_func = omap_device_idle_hwmods, + .activate_func = omap_device_enable_hwmods, + .flags = OMAP_DEVICE_LATENCY_AUTO_ADJUST, }, - .num_resources = ARRAY_SIZE(musb_resources), - .resource = musb_resources, }; +static void usb_musb_mux_init(struct omap_musb_board_data *board_data) +{ + switch (board_data->interface_type) { + case MUSB_INTERFACE_UTMI: + omap_mux_init_signal("usba0_otg_dp", OMAP_PIN_INPUT); + omap_mux_init_signal("usba0_otg_dm", OMAP_PIN_INPUT); + break; + case MUSB_INTERFACE_ULPI: + omap_mux_init_signal("usba0_ulpiphy_clk", + OMAP_PIN_INPUT_PULLDOWN); + omap_mux_init_signal("usba0_ulpiphy_stp", + OMAP_PIN_INPUT_PULLDOWN); + omap_mux_init_signal("usba0_ulpiphy_dir", + OMAP_PIN_INPUT_PULLDOWN); + omap_mux_init_signal("usba0_ulpiphy_nxt", + OMAP_PIN_INPUT_PULLDOWN); + omap_mux_init_signal("usba0_ulpiphy_dat0", + OMAP_PIN_INPUT_PULLDOWN); + omap_mux_init_signal("usba0_ulpiphy_dat1", + OMAP_PIN_INPUT_PULLDOWN); + omap_mux_init_signal("usba0_ulpiphy_dat2", + OMAP_PIN_INPUT_PULLDOWN); + omap_mux_init_signal("usba0_ulpiphy_dat3", + OMAP_PIN_INPUT_PULLDOWN); + omap_mux_init_signal("usba0_ulpiphy_dat4", + OMAP_PIN_INPUT_PULLDOWN); + omap_mux_init_signal("usba0_ulpiphy_dat5", + OMAP_PIN_INPUT_PULLDOWN); + omap_mux_init_signal("usba0_ulpiphy_dat6", + OMAP_PIN_INPUT_PULLDOWN); + omap_mux_init_signal("usba0_ulpiphy_dat7", + OMAP_PIN_INPUT_PULLDOWN); + break; + default: + break; + } +} + void __init usb_musb_init(struct omap_musb_board_data *board_data) { - if (cpu_is_omap243x()) { - musb_resources[0].start = OMAP243X_HS_BASE; - } else if (cpu_is_omap3517() || cpu_is_omap3505()) { - musb_device.name = "musb-am35x"; - musb_resources[0].start = AM35XX_IPSS_USBOTGSS_BASE; - musb_resources[1].start = INT_35XX_USBOTG_IRQ; - board_data->set_phy_power = am35x_musb_phy_power; - board_data->clear_irq = am35x_musb_clear_irq; - board_data->set_mode = am35x_musb_set_mode; - board_data->reset = am35x_musb_reset; - } else if (cpu_is_omap34xx()) { - musb_resources[0].start = OMAP34XX_HSUSB_OTG_BASE; + struct omap_hwmod *oh; + struct omap_device *od; + struct platform_device *pdev; + struct device *dev; + int bus_id = -1; + const char *oh_name, *name; + + if (cpu_is_omap3517() || cpu_is_omap3505()) { } else if (cpu_is_omap44xx()) { - musb_resources[0].start = OMAP44XX_HSUSB_OTG_BASE; - musb_resources[1].start = OMAP44XX_IRQ_HS_USB_MC_N; - musb_resources[2].start = OMAP44XX_IRQ_HS_USB_DMA_N; + usb_musb_mux_init(board_data); } - musb_resources[0].end = musb_resources[0].start + SZ_4K - 1; /* * REVISIT: This line can be removed once all the platforms using @@ -212,12 +132,38 @@ void __init usb_musb_init(struct omap_musb_board_data *board_data) musb_plat.mode = board_data->mode; musb_plat.extvbus = board_data->extvbus; - if (platform_device_register(&musb_device) < 0) - printk(KERN_ERR "Unable to register HS-USB (MUSB) device\n"); - if (cpu_is_omap44xx()) omap4430_phy_init(dev); + if (cpu_is_omap3517() || cpu_is_omap3505()) { + oh_name = "am35x_otg_hs"; + name = "musb-am35x"; + } else { + oh_name = "usb_otg_hs"; + name = "musb-omap2430"; + } + + oh = omap_hwmod_lookup(oh_name); + if (!oh) { + pr_err("Could not look up %s\n", oh_name); + return; + } + + od = omap_device_build(name, bus_id, oh, &musb_plat, + sizeof(musb_plat), omap_musb_latency, + ARRAY_SIZE(omap_musb_latency), false); + if (IS_ERR(od)) { + pr_err("Could not build omap_device for %s %s\n", + name, oh_name); + return; + } + + pdev = &od->pdev; + dev = &pdev->dev; + get_device(dev); + dev->dma_mask = &musb_dmamask; + dev->coherent_dma_mask = musb_dmamask; + put_device(dev); } #else diff --git a/arch/arm/mach-omap2/vc.h b/arch/arm/mach-omap2/vc.h new file mode 100644 index 00000000000..e7767771de4 --- /dev/null +++ b/arch/arm/mach-omap2/vc.h @@ -0,0 +1,83 @@ +/* + * OMAP3/4 Voltage Controller (VC) structure and macro definitions + * + * Copyright (C) 2007, 2010 Texas Instruments, Inc. + * Rajendra Nayak <rnayak@ti.com> + * Lesly A M <x0080970@ti.com> + * Thara Gopinath <thara@ti.com> + * + * Copyright (C) 2008, 2011 Nokia Corporation + * Kalle Jokiniemi + * Paul Walmsley + * + * This program is free software; you can redistribute it and/or + * modify it under the terms of the GNU General Public License version + * 2 as published by the Free Software Foundation. + */ +#ifndef __ARCH_ARM_MACH_OMAP2_VC_H +#define __ARCH_ARM_MACH_OMAP2_VC_H + +#include <linux/kernel.h> + +/** + * struct omap_vc_common_data - per-VC register/bitfield data + * @cmd_on_mask: ON bitmask in PRM_VC_CMD_VAL* register + * @valid: VALID bitmask in PRM_VC_BYPASS_VAL register + * @smps_sa_reg: Offset of PRM_VC_SMPS_SA reg from PRM start + * @smps_volra_reg: Offset of PRM_VC_SMPS_VOL_RA reg from PRM start + * @bypass_val_reg: Offset of PRM_VC_BYPASS_VAL reg from PRM start + * @data_shift: DATA field shift in PRM_VC_BYPASS_VAL register + * @slaveaddr_shift: SLAVEADDR field shift in PRM_VC_BYPASS_VAL register + * @regaddr_shift: REGADDR field shift in PRM_VC_BYPASS_VAL register + * @cmd_on_shift: ON field shift in PRM_VC_CMD_VAL_* register + * @cmd_onlp_shift: ONLP field shift in PRM_VC_CMD_VAL_* register + * @cmd_ret_shift: RET field shift in PRM_VC_CMD_VAL_* register + * @cmd_off_shift: OFF field shift in PRM_VC_CMD_VAL_* register + * + * XXX One of cmd_on_mask and cmd_on_shift are not needed + * XXX VALID should probably be a shift, not a mask + */ +struct omap_vc_common_data { + u32 cmd_on_mask; + u32 valid; + u8 smps_sa_reg; + u8 smps_volra_reg; + u8 bypass_val_reg; + u8 data_shift; + u8 slaveaddr_shift; + u8 regaddr_shift; + u8 cmd_on_shift; + u8 cmd_onlp_shift; + u8 cmd_ret_shift; + u8 cmd_off_shift; +}; + +/** + * struct omap_vc_instance_data - VC per-instance data + * @vc_common: pointer to VC common data for this platform + * @smps_sa_mask: SA* bitmask in the PRM_VC_SMPS_SA register + * @smps_volra_mask: VOLRA* bitmask in the PRM_VC_VOL_RA register + * @smps_sa_shift: SA* field shift in the PRM_VC_SMPS_SA register + * @smps_volra_shift: VOLRA* field shift in the PRM_VC_VOL_RA register + * + * XXX It is not necessary to have both a *_mask and a *_shift - + * remove one + */ +struct omap_vc_instance_data { + const struct omap_vc_common_data *vc_common; + u32 smps_sa_mask; + u32 smps_volra_mask; + u8 cmdval_reg; + u8 smps_sa_shift; + u8 smps_volra_shift; +}; + +extern struct omap_vc_instance_data omap3_vc1_data; +extern struct omap_vc_instance_data omap3_vc2_data; + +extern struct omap_vc_instance_data omap4_vc_mpu_data; +extern struct omap_vc_instance_data omap4_vc_iva_data; +extern struct omap_vc_instance_data omap4_vc_core_data; + +#endif + diff --git a/arch/arm/mach-omap2/vc3xxx_data.c b/arch/arm/mach-omap2/vc3xxx_data.c new file mode 100644 index 00000000000..f37dc4bc379 --- /dev/null +++ b/arch/arm/mach-omap2/vc3xxx_data.c @@ -0,0 +1,63 @@ +/* + * OMAP3 Voltage Controller (VC) data + * + * Copyright (C) 2007, 2010 Texas Instruments, Inc. + * Rajendra Nayak <rnayak@ti.com> + * Lesly A M <x0080970@ti.com> + * Thara Gopinath <thara@ti.com> + * + * Copyright (C) 2008, 2011 Nokia Corporation + * Kalle Jokiniemi + * Paul Walmsley + * + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License version 2 as + * published by the Free Software Foundation. + */ +#include <linux/io.h> +#include <linux/err.h> +#include <linux/init.h> + +#include <plat/common.h> + +#include "prm-regbits-34xx.h" +#include "voltage.h" + +#include "vc.h" + +/* + * VC data common to 34xx/36xx chips + * XXX This stuff presumably belongs in the vc3xxx.c or vc.c file. + */ +static struct omap_vc_common_data omap3_vc_common = { + .smps_sa_reg = OMAP3_PRM_VC_SMPS_SA_OFFSET, + .smps_volra_reg = OMAP3_PRM_VC_SMPS_VOL_RA_OFFSET, + .bypass_val_reg = OMAP3_PRM_VC_BYPASS_VAL_OFFSET, + .data_shift = OMAP3430_DATA_SHIFT, + .slaveaddr_shift = OMAP3430_SLAVEADDR_SHIFT, + .regaddr_shift = OMAP3430_REGADDR_SHIFT, + .valid = OMAP3430_VALID_MASK, + .cmd_on_shift = OMAP3430_VC_CMD_ON_SHIFT, + .cmd_on_mask = OMAP3430_VC_CMD_ON_MASK, + .cmd_onlp_shift = OMAP3430_VC_CMD_ONLP_SHIFT, + .cmd_ret_shift = OMAP3430_VC_CMD_RET_SHIFT, + .cmd_off_shift = OMAP3430_VC_CMD_OFF_SHIFT, +}; + +struct omap_vc_instance_data omap3_vc1_data = { + .vc_common = &omap3_vc_common, + .cmdval_reg = OMAP3_PRM_VC_CMD_VAL_0_OFFSET, + .smps_sa_shift = OMAP3430_PRM_VC_SMPS_SA_SA0_SHIFT, + .smps_sa_mask = OMAP3430_PRM_VC_SMPS_SA_SA0_MASK, + .smps_volra_shift = OMAP3430_VOLRA0_SHIFT, + .smps_volra_mask = OMAP3430_VOLRA0_MASK, +}; + +struct omap_vc_instance_data omap3_vc2_data = { + .vc_common = &omap3_vc_common, + .cmdval_reg = OMAP3_PRM_VC_CMD_VAL_1_OFFSET, + .smps_sa_shift = OMAP3430_PRM_VC_SMPS_SA_SA1_SHIFT, + .smps_sa_mask = OMAP3430_PRM_VC_SMPS_SA_SA1_MASK, + .smps_volra_shift = OMAP3430_VOLRA1_SHIFT, + .smps_volra_mask = OMAP3430_VOLRA1_MASK, +}; diff --git a/arch/arm/mach-omap2/vc44xx_data.c b/arch/arm/mach-omap2/vc44xx_data.c new file mode 100644 index 00000000000..a98da8ddec5 --- /dev/null +++ b/arch/arm/mach-omap2/vc44xx_data.c @@ -0,0 +1,75 @@ +/* + * OMAP4 Voltage Controller (VC) data + * + * Copyright (C) 2007, 2010 Texas Instruments, Inc. + * Rajendra Nayak <rnayak@ti.com> + * Lesly A M <x0080970@ti.com> + * Thara Gopinath <thara@ti.com> + * + * Copyright (C) 2008, 2011 Nokia Corporation + * Kalle Jokiniemi + * Paul Walmsley + * + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License version 2 as + * published by the Free Software Foundation. + */ +#include <linux/io.h> +#include <linux/err.h> +#include <linux/init.h> + +#include <plat/common.h> + +#include "prm44xx.h" +#include "prm-regbits-44xx.h" +#include "voltage.h" + +#include "vc.h" + +/* + * VC data common to 44xx chips + * XXX This stuff presumably belongs in the vc3xxx.c or vc.c file. + */ +static const struct omap_vc_common_data omap4_vc_common = { + .smps_sa_reg = OMAP4_PRM_VC_SMPS_SA_OFFSET, + .smps_volra_reg = OMAP4_PRM_VC_VAL_SMPS_RA_VOL_OFFSET, + .bypass_val_reg = OMAP4_PRM_VC_VAL_BYPASS_OFFSET, + .data_shift = OMAP4430_DATA_SHIFT, + .slaveaddr_shift = OMAP4430_SLAVEADDR_SHIFT, + .regaddr_shift = OMAP4430_REGADDR_SHIFT, + .valid = OMAP4430_VALID_MASK, + .cmd_on_shift = OMAP4430_ON_SHIFT, + .cmd_on_mask = OMAP4430_ON_MASK, + .cmd_onlp_shift = OMAP4430_ONLP_SHIFT, + .cmd_ret_shift = OMAP4430_RET_SHIFT, + .cmd_off_shift = OMAP4430_OFF_SHIFT, +}; + +/* VC instance data for each controllable voltage line */ +struct omap_vc_instance_data omap4_vc_mpu_data = { + .vc_common = &omap4_vc_common, + .cmdval_reg = OMAP4_PRM_VC_VAL_CMD_VDD_MPU_L_OFFSET, + .smps_sa_shift = OMAP4430_SA_VDD_MPU_L_PRM_VC_SMPS_SA_SHIFT, + .smps_sa_mask = OMAP4430_SA_VDD_MPU_L_PRM_VC_SMPS_SA_MASK, + .smps_volra_shift = OMAP4430_VOLRA_VDD_MPU_L_SHIFT, + .smps_volra_mask = OMAP4430_VOLRA_VDD_MPU_L_MASK, +}; + +struct omap_vc_instance_data omap4_vc_iva_data = { + .vc_common = &omap4_vc_common, + .cmdval_reg = OMAP4_PRM_VC_VAL_CMD_VDD_IVA_L_OFFSET, + .smps_sa_shift = OMAP4430_SA_VDD_IVA_L_PRM_VC_SMPS_SA_SHIFT, + .smps_sa_mask = OMAP4430_SA_VDD_IVA_L_PRM_VC_SMPS_SA_MASK, + .smps_volra_shift = OMAP4430_VOLRA_VDD_IVA_L_SHIFT, + .smps_volra_mask = OMAP4430_VOLRA_VDD_IVA_L_MASK, +}; + +struct omap_vc_instance_data omap4_vc_core_data = { + .vc_common = &omap4_vc_common, + .cmdval_reg = OMAP4_PRM_VC_VAL_CMD_VDD_CORE_L_OFFSET, + .smps_sa_shift = OMAP4430_SA_VDD_CORE_L_0_6_SHIFT, + .smps_sa_mask = OMAP4430_SA_VDD_CORE_L_0_6_MASK, + .smps_volra_shift = OMAP4430_VOLRA_VDD_CORE_L_SHIFT, + .smps_volra_mask = OMAP4430_VOLRA_VDD_CORE_L_MASK, +}; + diff --git a/arch/arm/mach-omap2/voltage.c b/arch/arm/mach-omap2/voltage.c index 12be525b8df..c6facf7becf 100644 --- a/arch/arm/mach-omap2/voltage.c +++ b/arch/arm/mach-omap2/voltage.c @@ -7,8 +7,9 @@ * Rajendra Nayak <rnayak@ti.com> * Lesly A M <x0080970@ti.com> * - * Copyright (C) 2008 Nokia Corporation + * Copyright (C) 2008, 2011 Nokia Corporation * Kalle Jokiniemi + * Paul Walmsley * * Copyright (C) 2010 Texas Instruments, Inc. * Thara Gopinath <thara@ti.com> @@ -26,7 +27,6 @@ #include <linux/slab.h> #include <plat/common.h> -#include <plat/voltage.h> #include "prm-regbits-34xx.h" #include "prm-regbits-44xx.h" @@ -35,284 +35,30 @@ #include "prminst44xx.h" #include "control.h" -#define VP_IDLE_TIMEOUT 200 -#define VP_TRANXDONE_TIMEOUT 300 +#include "voltage.h" + +#include "vc.h" +#include "vp.h" + #define VOLTAGE_DIR_SIZE 16 -/* Voltage processor register offsets */ -struct vp_reg_offs { - u8 vpconfig; - u8 vstepmin; - u8 vstepmax; - u8 vlimitto; - u8 vstatus; - u8 voltage; -}; - -/* Voltage Processor bit field values, shifts and masks */ -struct vp_reg_val { - /* PRM module */ - u16 prm_mod; - /* VPx_VPCONFIG */ - u32 vpconfig_erroroffset; - u16 vpconfig_errorgain; - u32 vpconfig_errorgain_mask; - u8 vpconfig_errorgain_shift; - u32 vpconfig_initvoltage_mask; - u8 vpconfig_initvoltage_shift; - u32 vpconfig_timeouten; - u32 vpconfig_initvdd; - u32 vpconfig_forceupdate; - u32 vpconfig_vpenable; - /* VPx_VSTEPMIN */ - u8 vstepmin_stepmin; - u16 vstepmin_smpswaittimemin; - u8 vstepmin_stepmin_shift; - u8 vstepmin_smpswaittimemin_shift; - /* VPx_VSTEPMAX */ - u8 vstepmax_stepmax; - u16 vstepmax_smpswaittimemax; - u8 vstepmax_stepmax_shift; - u8 vstepmax_smpswaittimemax_shift; - /* VPx_VLIMITTO */ - u8 vlimitto_vddmin; - u8 vlimitto_vddmax; - u16 vlimitto_timeout; - u8 vlimitto_vddmin_shift; - u8 vlimitto_vddmax_shift; - u8 vlimitto_timeout_shift; - /* PRM_IRQSTATUS*/ - u32 tranxdone_status; -}; - -/* Voltage controller registers and offsets */ -struct vc_reg_info { - /* PRM module */ - u16 prm_mod; - /* VC register offsets */ - u8 smps_sa_reg; - u8 smps_volra_reg; - u8 bypass_val_reg; - u8 cmdval_reg; - u8 voltsetup_reg; - /*VC_SMPS_SA*/ - u8 smps_sa_shift; - u32 smps_sa_mask; - /* VC_SMPS_VOL_RA */ - u8 smps_volra_shift; - u32 smps_volra_mask; - /* VC_BYPASS_VAL */ - u8 data_shift; - u8 slaveaddr_shift; - u8 regaddr_shift; - u32 valid; - /* VC_CMD_VAL */ - u8 cmd_on_shift; - u8 cmd_onlp_shift; - u8 cmd_ret_shift; - u8 cmd_off_shift; - u32 cmd_on_mask; - /* PRM_VOLTSETUP */ - u8 voltsetup_shift; - u32 voltsetup_mask; -}; -/** - * omap_vdd_info - Per Voltage Domain info - * - * @volt_data : voltage table having the distinct voltages supported - * by the domain and other associated per voltage data. - * @pmic_info : pmic specific parameters which should be populted by - * the pmic drivers. - * @vp_offs : structure containing the offsets for various - * vp registers - * @vp_reg : the register values, shifts, masks for various - * vp registers - * @vc_reg : structure containing various various vc registers, - * shifts, masks etc. - * @voltdm : pointer to the voltage domain structure - * @debug_dir : debug directory for this voltage domain. - * @curr_volt : current voltage for this vdd. - * @ocp_mod : The prm module for accessing the prm irqstatus reg. - * @prm_irqst_reg : prm irqstatus register. - * @vp_enabled : flag to keep track of whether vp is enabled or not - * @volt_scale : API to scale the voltage of the vdd. - */ -struct omap_vdd_info { - struct omap_volt_data *volt_data; - struct omap_volt_pmic_info *pmic_info; - struct vp_reg_offs vp_offs; - struct vp_reg_val vp_reg; - struct vc_reg_info vc_reg; - struct voltagedomain voltdm; - struct dentry *debug_dir; - u32 curr_volt; - u16 ocp_mod; - u8 prm_irqst_reg; - bool vp_enabled; - u32 (*read_reg) (u16 mod, u8 offset); - void (*write_reg) (u32 val, u16 mod, u8 offset); - int (*volt_scale) (struct omap_vdd_info *vdd, - unsigned long target_volt); -}; - -static struct omap_vdd_info *vdd_info; +static struct omap_vdd_info **vdd_info; + /* * Number of scalable voltage domains. */ static int nr_scalable_vdd; -/* OMAP3 VDD sturctures */ -static struct omap_vdd_info omap3_vdd_info[] = { - { - .vp_offs = { - .vpconfig = OMAP3_PRM_VP1_CONFIG_OFFSET, - .vstepmin = OMAP3_PRM_VP1_VSTEPMIN_OFFSET, - .vstepmax = OMAP3_PRM_VP1_VSTEPMAX_OFFSET, - .vlimitto = OMAP3_PRM_VP1_VLIMITTO_OFFSET, - .vstatus = OMAP3_PRM_VP1_STATUS_OFFSET, - .voltage = OMAP3_PRM_VP1_VOLTAGE_OFFSET, - }, - .voltdm = { - .name = "mpu", - }, - }, - { - .vp_offs = { - .vpconfig = OMAP3_PRM_VP2_CONFIG_OFFSET, - .vstepmin = OMAP3_PRM_VP2_VSTEPMIN_OFFSET, - .vstepmax = OMAP3_PRM_VP2_VSTEPMAX_OFFSET, - .vlimitto = OMAP3_PRM_VP2_VLIMITTO_OFFSET, - .vstatus = OMAP3_PRM_VP2_STATUS_OFFSET, - .voltage = OMAP3_PRM_VP2_VOLTAGE_OFFSET, - }, - .voltdm = { - .name = "core", - }, - }, -}; - -#define OMAP3_NR_SCALABLE_VDD ARRAY_SIZE(omap3_vdd_info) - -/* OMAP4 VDD sturctures */ -static struct omap_vdd_info omap4_vdd_info[] = { - { - .vp_offs = { - .vpconfig = OMAP4_PRM_VP_MPU_CONFIG_OFFSET, - .vstepmin = OMAP4_PRM_VP_MPU_VSTEPMIN_OFFSET, - .vstepmax = OMAP4_PRM_VP_MPU_VSTEPMAX_OFFSET, - .vlimitto = OMAP4_PRM_VP_MPU_VLIMITTO_OFFSET, - .vstatus = OMAP4_PRM_VP_MPU_STATUS_OFFSET, - .voltage = OMAP4_PRM_VP_MPU_VOLTAGE_OFFSET, - }, - .voltdm = { - .name = "mpu", - }, - }, - { - .vp_offs = { - .vpconfig = OMAP4_PRM_VP_IVA_CONFIG_OFFSET, - .vstepmin = OMAP4_PRM_VP_IVA_VSTEPMIN_OFFSET, - .vstepmax = OMAP4_PRM_VP_IVA_VSTEPMAX_OFFSET, - .vlimitto = OMAP4_PRM_VP_IVA_VLIMITTO_OFFSET, - .vstatus = OMAP4_PRM_VP_IVA_STATUS_OFFSET, - .voltage = OMAP4_PRM_VP_IVA_VOLTAGE_OFFSET, - }, - .voltdm = { - .name = "iva", - }, - }, - { - .vp_offs = { - .vpconfig = OMAP4_PRM_VP_CORE_CONFIG_OFFSET, - .vstepmin = OMAP4_PRM_VP_CORE_VSTEPMIN_OFFSET, - .vstepmax = OMAP4_PRM_VP_CORE_VSTEPMAX_OFFSET, - .vlimitto = OMAP4_PRM_VP_CORE_VLIMITTO_OFFSET, - .vstatus = OMAP4_PRM_VP_CORE_STATUS_OFFSET, - .voltage = OMAP4_PRM_VP_CORE_VOLTAGE_OFFSET, - }, - .voltdm = { - .name = "core", - }, - }, -}; - -#define OMAP4_NR_SCALABLE_VDD ARRAY_SIZE(omap4_vdd_info) - -/* - * Structures containing OMAP3430/OMAP3630 voltage supported and various - * voltage dependent data for each VDD. - */ -#define VOLT_DATA_DEFINE(_v_nom, _efuse_offs, _errminlimit, _errgain) \ -{ \ - .volt_nominal = _v_nom, \ - .sr_efuse_offs = _efuse_offs, \ - .sr_errminlimit = _errminlimit, \ - .vp_errgain = _errgain \ -} - -/* VDD1 */ -static struct omap_volt_data omap34xx_vddmpu_volt_data[] = { - VOLT_DATA_DEFINE(OMAP3430_VDD_MPU_OPP1_UV, OMAP343X_CONTROL_FUSE_OPP1_VDD1, 0xf4, 0x0c), - VOLT_DATA_DEFINE(OMAP3430_VDD_MPU_OPP2_UV, OMAP343X_CONTROL_FUSE_OPP2_VDD1, 0xf4, 0x0c), - VOLT_DATA_DEFINE(OMAP3430_VDD_MPU_OPP3_UV, OMAP343X_CONTROL_FUSE_OPP3_VDD1, 0xf9, 0x18), - VOLT_DATA_DEFINE(OMAP3430_VDD_MPU_OPP4_UV, OMAP343X_CONTROL_FUSE_OPP4_VDD1, 0xf9, 0x18), - VOLT_DATA_DEFINE(OMAP3430_VDD_MPU_OPP5_UV, OMAP343X_CONTROL_FUSE_OPP5_VDD1, 0xf9, 0x18), - VOLT_DATA_DEFINE(0, 0, 0, 0), -}; - -static struct omap_volt_data omap36xx_vddmpu_volt_data[] = { - VOLT_DATA_DEFINE(OMAP3630_VDD_MPU_OPP50_UV, OMAP3630_CONTROL_FUSE_OPP50_VDD1, 0xf4, 0x0c), - VOLT_DATA_DEFINE(OMAP3630_VDD_MPU_OPP100_UV, OMAP3630_CONTROL_FUSE_OPP100_VDD1, 0xf9, 0x16), - VOLT_DATA_DEFINE(OMAP3630_VDD_MPU_OPP120_UV, OMAP3630_CONTROL_FUSE_OPP120_VDD1, 0xfa, 0x23), - VOLT_DATA_DEFINE(OMAP3630_VDD_MPU_OPP1G_UV, OMAP3630_CONTROL_FUSE_OPP1G_VDD1, 0xfa, 0x27), - VOLT_DATA_DEFINE(0, 0, 0, 0), -}; - -/* VDD2 */ -static struct omap_volt_data omap34xx_vddcore_volt_data[] = { - VOLT_DATA_DEFINE(OMAP3430_VDD_CORE_OPP1_UV, OMAP343X_CONTROL_FUSE_OPP1_VDD2, 0xf4, 0x0c), - VOLT_DATA_DEFINE(OMAP3430_VDD_CORE_OPP2_UV, OMAP343X_CONTROL_FUSE_OPP2_VDD2, 0xf4, 0x0c), - VOLT_DATA_DEFINE(OMAP3430_VDD_CORE_OPP3_UV, OMAP343X_CONTROL_FUSE_OPP3_VDD2, 0xf9, 0x18), - VOLT_DATA_DEFINE(0, 0, 0, 0), -}; - -static struct omap_volt_data omap36xx_vddcore_volt_data[] = { - VOLT_DATA_DEFINE(OMAP3630_VDD_CORE_OPP50_UV, OMAP3630_CONTROL_FUSE_OPP50_VDD2, 0xf4, 0x0c), - VOLT_DATA_DEFINE(OMAP3630_VDD_CORE_OPP100_UV, OMAP3630_CONTROL_FUSE_OPP100_VDD2, 0xf9, 0x16), - VOLT_DATA_DEFINE(0, 0, 0, 0), -}; - -/* - * Structures containing OMAP4430 voltage supported and various - * voltage dependent data for each VDD. - */ -static struct omap_volt_data omap44xx_vdd_mpu_volt_data[] = { - VOLT_DATA_DEFINE(OMAP4430_VDD_MPU_OPP50_UV, OMAP44XX_CONTROL_FUSE_MPU_OPP50, 0xf4, 0x0c), - VOLT_DATA_DEFINE(OMAP4430_VDD_MPU_OPP100_UV, OMAP44XX_CONTROL_FUSE_MPU_OPP100, 0xf9, 0x16), - VOLT_DATA_DEFINE(OMAP4430_VDD_MPU_OPPTURBO_UV, OMAP44XX_CONTROL_FUSE_MPU_OPPTURBO, 0xfa, 0x23), - VOLT_DATA_DEFINE(OMAP4430_VDD_MPU_OPPNITRO_UV, OMAP44XX_CONTROL_FUSE_MPU_OPPNITRO, 0xfa, 0x27), - VOLT_DATA_DEFINE(0, 0, 0, 0), -}; - -static struct omap_volt_data omap44xx_vdd_iva_volt_data[] = { - VOLT_DATA_DEFINE(OMAP4430_VDD_IVA_OPP50_UV, OMAP44XX_CONTROL_FUSE_IVA_OPP50, 0xf4, 0x0c), - VOLT_DATA_DEFINE(OMAP4430_VDD_IVA_OPP100_UV, OMAP44XX_CONTROL_FUSE_IVA_OPP100, 0xf9, 0x16), - VOLT_DATA_DEFINE(OMAP4430_VDD_IVA_OPPTURBO_UV, OMAP44XX_CONTROL_FUSE_IVA_OPPTURBO, 0xfa, 0x23), - VOLT_DATA_DEFINE(0, 0, 0, 0), -}; - -static struct omap_volt_data omap44xx_vdd_core_volt_data[] = { - VOLT_DATA_DEFINE(OMAP4430_VDD_CORE_OPP50_UV, OMAP44XX_CONTROL_FUSE_CORE_OPP50, 0xf4, 0x0c), - VOLT_DATA_DEFINE(OMAP4430_VDD_CORE_OPP100_UV, OMAP44XX_CONTROL_FUSE_CORE_OPP100, 0xf9, 0x16), - VOLT_DATA_DEFINE(0, 0, 0, 0), -}; +/* XXX document */ +static s16 prm_mod_offs; +static s16 prm_irqst_ocp_mod_offs; static struct dentry *voltage_dir; /* Init function pointers */ -static void (*vc_init) (struct omap_vdd_info *vdd); -static int (*vdd_data_configure) (struct omap_vdd_info *vdd); +static int vp_forceupdate_scale_voltage(struct omap_vdd_info *vdd, + unsigned long target_volt); static u32 omap3_voltage_read_reg(u16 mod, u8 offset) { @@ -335,6 +81,62 @@ static void omap4_voltage_write_reg(u32 val, u16 mod, u8 offset) omap4_prminst_write_inst_reg(val, OMAP4430_PRM_PARTITION, mod, offset); } +static int __init _config_common_vdd_data(struct omap_vdd_info *vdd) +{ + char *sys_ck_name; + struct clk *sys_ck; + u32 sys_clk_speed, timeout_val, waittime; + + /* + * XXX Clockfw should handle this, or this should be in a + * struct record + */ + if (cpu_is_omap24xx() || cpu_is_omap34xx()) + sys_ck_name = "sys_ck"; + else if (cpu_is_omap44xx()) + sys_ck_name = "sys_clkin_ck"; + else + return -EINVAL; + + /* + * Sys clk rate is require to calculate vp timeout value and + * smpswaittimemin and smpswaittimemax. + */ + sys_ck = clk_get(NULL, sys_ck_name); + if (IS_ERR(sys_ck)) { + pr_warning("%s: Could not get the sys clk to calculate" + "various vdd_%s params\n", __func__, vdd->voltdm.name); + return -EINVAL; + } + sys_clk_speed = clk_get_rate(sys_ck); + clk_put(sys_ck); + /* Divide to avoid overflow */ + sys_clk_speed /= 1000; + + /* Generic voltage parameters */ + vdd->curr_volt = 1200000; + vdd->volt_scale = vp_forceupdate_scale_voltage; + vdd->vp_enabled = false; + + vdd->vp_rt_data.vpconfig_erroroffset = + (vdd->pmic_info->vp_erroroffset << + vdd->vp_data->vp_common->vpconfig_erroroffset_shift); + + timeout_val = (sys_clk_speed * vdd->pmic_info->vp_timeout_us) / 1000; + vdd->vp_rt_data.vlimitto_timeout = timeout_val; + vdd->vp_rt_data.vlimitto_vddmin = vdd->pmic_info->vp_vddmin; + vdd->vp_rt_data.vlimitto_vddmax = vdd->pmic_info->vp_vddmax; + + waittime = ((vdd->pmic_info->step_size / vdd->pmic_info->slew_rate) * + sys_clk_speed) / 1000; + vdd->vp_rt_data.vstepmin_smpswaittimemin = waittime; + vdd->vp_rt_data.vstepmax_smpswaittimemax = waittime; + vdd->vp_rt_data.vstepmin_stepmin = vdd->pmic_info->vp_vstepmin; + vdd->vp_rt_data.vstepmax_stepmax = vdd->pmic_info->vp_vstepmax; + + return 0; +} + /* Voltage debugfs support */ static int vp_volt_debug_get(void *data, u64 *val) { @@ -346,7 +148,7 @@ static int vp_volt_debug_get(void *data, u64 *val) return -EINVAL; } - vsel = vdd->read_reg(vdd->vp_reg.prm_mod, vdd->vp_offs.voltage); + vsel = vdd->read_reg(prm_mod_offs, vdd->vp_data->voltage); pr_notice("curr_vsel = %x\n", vsel); if (!vdd->pmic_info->vsel_to_uv) { @@ -379,7 +181,6 @@ DEFINE_SIMPLE_ATTRIBUTE(nom_volt_debug_fops, nom_volt_debug_get, NULL, static void vp_latch_vsel(struct omap_vdd_info *vdd) { u32 vpconfig; - u16 mod; unsigned long uvdc; char vsel; @@ -396,30 +197,27 @@ static void vp_latch_vsel(struct omap_vdd_info *vdd) return; } - mod = vdd->vp_reg.prm_mod; - vsel = vdd->pmic_info->uv_to_vsel(uvdc); - vpconfig = vdd->read_reg(mod, vdd->vp_offs.vpconfig); - vpconfig &= ~(vdd->vp_reg.vpconfig_initvoltage_mask | - vdd->vp_reg.vpconfig_initvdd); - vpconfig |= vsel << vdd->vp_reg.vpconfig_initvoltage_shift; + vpconfig = vdd->read_reg(prm_mod_offs, vdd->vp_data->vpconfig); + vpconfig &= ~(vdd->vp_data->vp_common->vpconfig_initvoltage_mask | + vdd->vp_data->vp_common->vpconfig_initvdd); + vpconfig |= vsel << vdd->vp_data->vp_common->vpconfig_initvoltage_shift; - vdd->write_reg(vpconfig, mod, vdd->vp_offs.vpconfig); + vdd->write_reg(vpconfig, prm_mod_offs, vdd->vp_data->vpconfig); /* Trigger initVDD value copy to voltage processor */ - vdd->write_reg((vpconfig | vdd->vp_reg.vpconfig_initvdd), mod, - vdd->vp_offs.vpconfig); + vdd->write_reg((vpconfig | vdd->vp_data->vp_common->vpconfig_initvdd), + prm_mod_offs, vdd->vp_data->vpconfig); /* Clear initVDD copy trigger bit */ - vdd->write_reg(vpconfig, mod, vdd->vp_offs.vpconfig); + vdd->write_reg(vpconfig, prm_mod_offs, vdd->vp_data->vpconfig); } /* Generic voltage init functions */ static void __init vp_init(struct omap_vdd_info *vdd) { u32 vp_val; - u16 mod; if (!vdd->read_reg || !vdd->write_reg) { pr_err("%s: No read/write API for accessing vdd_%s regs\n", @@ -427,33 +225,31 @@ static void __init vp_init(struct omap_vdd_info *vdd) return; } - mod = vdd->vp_reg.prm_mod; - - vp_val = vdd->vp_reg.vpconfig_erroroffset | - (vdd->vp_reg.vpconfig_errorgain << - vdd->vp_reg.vpconfig_errorgain_shift) | - vdd->vp_reg.vpconfig_timeouten; - vdd->write_reg(vp_val, mod, vdd->vp_offs.vpconfig); - - vp_val = ((vdd->vp_reg.vstepmin_smpswaittimemin << - vdd->vp_reg.vstepmin_smpswaittimemin_shift) | - (vdd->vp_reg.vstepmin_stepmin << - vdd->vp_reg.vstepmin_stepmin_shift)); - vdd->write_reg(vp_val, mod, vdd->vp_offs.vstepmin); - - vp_val = ((vdd->vp_reg.vstepmax_smpswaittimemax << - vdd->vp_reg.vstepmax_smpswaittimemax_shift) | - (vdd->vp_reg.vstepmax_stepmax << - vdd->vp_reg.vstepmax_stepmax_shift)); - vdd->write_reg(vp_val, mod, vdd->vp_offs.vstepmax); - - vp_val = ((vdd->vp_reg.vlimitto_vddmax << - vdd->vp_reg.vlimitto_vddmax_shift) | - (vdd->vp_reg.vlimitto_vddmin << - vdd->vp_reg.vlimitto_vddmin_shift) | - (vdd->vp_reg.vlimitto_timeout << - vdd->vp_reg.vlimitto_timeout_shift)); - vdd->write_reg(vp_val, mod, vdd->vp_offs.vlimitto); + vp_val = vdd->vp_rt_data.vpconfig_erroroffset | + (vdd->vp_rt_data.vpconfig_errorgain << + vdd->vp_data->vp_common->vpconfig_errorgain_shift) | + vdd->vp_data->vp_common->vpconfig_timeouten; + vdd->write_reg(vp_val, prm_mod_offs, vdd->vp_data->vpconfig); + + vp_val = ((vdd->vp_rt_data.vstepmin_smpswaittimemin << + vdd->vp_data->vp_common->vstepmin_smpswaittimemin_shift) | + (vdd->vp_rt_data.vstepmin_stepmin << + vdd->vp_data->vp_common->vstepmin_stepmin_shift)); + vdd->write_reg(vp_val, prm_mod_offs, vdd->vp_data->vstepmin); + + vp_val = ((vdd->vp_rt_data.vstepmax_smpswaittimemax << + vdd->vp_data->vp_common->vstepmax_smpswaittimemax_shift) | + (vdd->vp_rt_data.vstepmax_stepmax << + vdd->vp_data->vp_common->vstepmax_stepmax_shift)); + vdd->write_reg(vp_val, prm_mod_offs, vdd->vp_data->vstepmax); + + vp_val = ((vdd->vp_rt_data.vlimitto_vddmax << + vdd->vp_data->vp_common->vlimitto_vddmax_shift) | + (vdd->vp_rt_data.vlimitto_vddmin << + vdd->vp_data->vp_common->vlimitto_vddmin_shift) | + (vdd->vp_rt_data.vlimitto_timeout << + vdd->vp_data->vp_common->vlimitto_timeout_shift)); + vdd->write_reg(vp_val, prm_mod_offs, vdd->vp_data->vlimitto); } static void __init vdd_debugfs_init(struct omap_vdd_info *vdd) @@ -480,23 +276,23 @@ static void __init vdd_debugfs_init(struct omap_vdd_info *vdd) } (void) debugfs_create_x16("vp_errorgain", S_IRUGO, vdd->debug_dir, - &(vdd->vp_reg.vpconfig_errorgain)); + &(vdd->vp_rt_data.vpconfig_errorgain)); (void) debugfs_create_x16("vp_smpswaittimemin", S_IRUGO, vdd->debug_dir, - &(vdd->vp_reg.vstepmin_smpswaittimemin)); + &(vdd->vp_rt_data.vstepmin_smpswaittimemin)); (void) debugfs_create_x8("vp_stepmin", S_IRUGO, vdd->debug_dir, - &(vdd->vp_reg.vstepmin_stepmin)); + &(vdd->vp_rt_data.vstepmin_stepmin)); (void) debugfs_create_x16("vp_smpswaittimemax", S_IRUGO, vdd->debug_dir, - &(vdd->vp_reg.vstepmax_smpswaittimemax)); + &(vdd->vp_rt_data.vstepmax_smpswaittimemax)); (void) debugfs_create_x8("vp_stepmax", S_IRUGO, vdd->debug_dir, - &(vdd->vp_reg.vstepmax_stepmax)); + &(vdd->vp_rt_data.vstepmax_stepmax)); (void) debugfs_create_x8("vp_vddmax", S_IRUGO, vdd->debug_dir, - &(vdd->vp_reg.vlimitto_vddmax)); + &(vdd->vp_rt_data.vlimitto_vddmax)); (void) debugfs_create_x8("vp_vddmin", S_IRUGO, vdd->debug_dir, - &(vdd->vp_reg.vlimitto_vddmin)); + &(vdd->vp_rt_data.vlimitto_vddmin)); (void) debugfs_create_x16("vp_timeout", S_IRUGO, vdd->debug_dir, - &(vdd->vp_reg.vlimitto_timeout)); + &(vdd->vp_rt_data.vlimitto_timeout)); (void) debugfs_create_file("curr_vp_volt", S_IRUGO, vdd->debug_dir, (void *) vdd, &vp_volt_debug_fops); (void) debugfs_create_file("curr_nominal_volt", S_IRUGO, @@ -509,8 +305,12 @@ static int _pre_volt_scale(struct omap_vdd_info *vdd, unsigned long target_volt, u8 *target_vsel, u8 *current_vsel) { struct omap_volt_data *volt_data; + const struct omap_vc_common_data *vc_common; + const struct omap_vp_common_data *vp_common; u32 vc_cmdval, vp_errgain_val; - u16 vp_mod, vc_mod; + + vc_common = vdd->vc_data->vc_common; + vp_common = vdd->vp_data->vp_common; /* Check if suffiecient pmic info is available for this vdd */ if (!vdd->pmic_info) { @@ -532,33 +332,30 @@ static int _pre_volt_scale(struct omap_vdd_info *vdd, return -EINVAL; } - vp_mod = vdd->vp_reg.prm_mod; - vc_mod = vdd->vc_reg.prm_mod; - /* Get volt_data corresponding to target_volt */ volt_data = omap_voltage_get_voltdata(&vdd->voltdm, target_volt); if (IS_ERR(volt_data)) volt_data = NULL; *target_vsel = vdd->pmic_info->uv_to_vsel(target_volt); - *current_vsel = vdd->read_reg(vp_mod, vdd->vp_offs.voltage); + *current_vsel = vdd->read_reg(prm_mod_offs, vdd->vp_data->voltage); /* Setting the ON voltage to the new target voltage */ - vc_cmdval = vdd->read_reg(vc_mod, vdd->vc_reg.cmdval_reg); - vc_cmdval &= ~vdd->vc_reg.cmd_on_mask; - vc_cmdval |= (*target_vsel << vdd->vc_reg.cmd_on_shift); - vdd->write_reg(vc_cmdval, vc_mod, vdd->vc_reg.cmdval_reg); + vc_cmdval = vdd->read_reg(prm_mod_offs, vdd->vc_data->cmdval_reg); + vc_cmdval &= ~vc_common->cmd_on_mask; + vc_cmdval |= (*target_vsel << vc_common->cmd_on_shift); + vdd->write_reg(vc_cmdval, prm_mod_offs, vdd->vc_data->cmdval_reg); /* Setting vp errorgain based on the voltage */ if (volt_data) { - vp_errgain_val = vdd->read_reg(vp_mod, - vdd->vp_offs.vpconfig); - vdd->vp_reg.vpconfig_errorgain = volt_data->vp_errgain; - vp_errgain_val &= ~vdd->vp_reg.vpconfig_errorgain_mask; - vp_errgain_val |= vdd->vp_reg.vpconfig_errorgain << - vdd->vp_reg.vpconfig_errorgain_shift; - vdd->write_reg(vp_errgain_val, vp_mod, - vdd->vp_offs.vpconfig); + vp_errgain_val = vdd->read_reg(prm_mod_offs, + vdd->vp_data->vpconfig); + vdd->vp_rt_data.vpconfig_errorgain = volt_data->vp_errgain; + vp_errgain_val &= ~vp_common->vpconfig_errorgain_mask; + vp_errgain_val |= vdd->vp_rt_data.vpconfig_errorgain << + vp_common->vpconfig_errorgain_shift; + vdd->write_reg(vp_errgain_val, prm_mod_offs, + vdd->vp_data->vpconfig); } return 0; @@ -584,7 +381,6 @@ static int vc_bypass_scale_voltage(struct omap_vdd_info *vdd, { u32 loop_cnt = 0, retries_cnt = 0; u32 vc_valid, vc_bypass_val_reg, vc_bypass_value; - u16 mod; u8 target_vsel, current_vsel; int ret; @@ -592,20 +388,19 @@ static int vc_bypass_scale_voltage(struct omap_vdd_info *vdd, if (ret) return ret; - mod = vdd->vc_reg.prm_mod; - - vc_valid = vdd->vc_reg.valid; - vc_bypass_val_reg = vdd->vc_reg.bypass_val_reg; - vc_bypass_value = (target_vsel << vdd->vc_reg.data_shift) | + vc_valid = vdd->vc_data->vc_common->valid; + vc_bypass_val_reg = vdd->vc_data->vc_common->bypass_val_reg; + vc_bypass_value = (target_vsel << vdd->vc_data->vc_common->data_shift) | (vdd->pmic_info->pmic_reg << - vdd->vc_reg.regaddr_shift) | + vdd->vc_data->vc_common->regaddr_shift) | (vdd->pmic_info->i2c_slave_addr << - vdd->vc_reg.slaveaddr_shift); + vdd->vc_data->vc_common->slaveaddr_shift); - vdd->write_reg(vc_bypass_value, mod, vc_bypass_val_reg); - vdd->write_reg(vc_bypass_value | vc_valid, mod, vc_bypass_val_reg); + vdd->write_reg(vc_bypass_value, prm_mod_offs, vc_bypass_val_reg); + vdd->write_reg(vc_bypass_value | vc_valid, prm_mod_offs, + vc_bypass_val_reg); - vc_bypass_value = vdd->read_reg(mod, vc_bypass_val_reg); + vc_bypass_value = vdd->read_reg(prm_mod_offs, vc_bypass_val_reg); /* * Loop till the bypass command is acknowledged from the SMPS. * NOTE: This is legacy code. The loop count and retry count needs @@ -624,7 +419,8 @@ static int vc_bypass_scale_voltage(struct omap_vdd_info *vdd, loop_cnt = 0; udelay(10); } - vc_bypass_value = vdd->read_reg(mod, vc_bypass_val_reg); + vc_bypass_value = vdd->read_reg(prm_mod_offs, + vc_bypass_val_reg); } _post_volt_scale(vdd, target_volt, target_vsel, current_vsel); @@ -636,7 +432,6 @@ static int vp_forceupdate_scale_voltage(struct omap_vdd_info *vdd, unsigned long target_volt) { u32 vpconfig; - u16 mod, ocp_mod; u8 target_vsel, current_vsel, prm_irqst_reg; int ret, timeout = 0; @@ -644,20 +439,18 @@ static int vp_forceupdate_scale_voltage(struct omap_vdd_info *vdd, if (ret) return ret; - mod = vdd->vp_reg.prm_mod; - ocp_mod = vdd->ocp_mod; - prm_irqst_reg = vdd->prm_irqst_reg; + prm_irqst_reg = vdd->vp_data->prm_irqst_data->prm_irqst_reg; /* * Clear all pending TransactionDone interrupt/status. Typical latency * is <3us */ while (timeout++ < VP_TRANXDONE_TIMEOUT) { - vdd->write_reg(vdd->vp_reg.tranxdone_status, - ocp_mod, prm_irqst_reg); - if (!(vdd->read_reg(ocp_mod, prm_irqst_reg) & - vdd->vp_reg.tranxdone_status)) - break; + vdd->write_reg(vdd->vp_data->prm_irqst_data->tranxdone_status, + prm_irqst_ocp_mod_offs, prm_irqst_reg); + if (!(vdd->read_reg(prm_irqst_ocp_mod_offs, prm_irqst_reg) & + vdd->vp_data->prm_irqst_data->tranxdone_status)) + break; udelay(1); } if (timeout >= VP_TRANXDONE_TIMEOUT) { @@ -667,30 +460,30 @@ static int vp_forceupdate_scale_voltage(struct omap_vdd_info *vdd, } /* Configure for VP-Force Update */ - vpconfig = vdd->read_reg(mod, vdd->vp_offs.vpconfig); - vpconfig &= ~(vdd->vp_reg.vpconfig_initvdd | - vdd->vp_reg.vpconfig_forceupdate | - vdd->vp_reg.vpconfig_initvoltage_mask); + vpconfig = vdd->read_reg(prm_mod_offs, vdd->vp_data->vpconfig); + vpconfig &= ~(vdd->vp_data->vp_common->vpconfig_initvdd | + vdd->vp_data->vp_common->vpconfig_forceupdate | + vdd->vp_data->vp_common->vpconfig_initvoltage_mask); vpconfig |= ((target_vsel << - vdd->vp_reg.vpconfig_initvoltage_shift)); - vdd->write_reg(vpconfig, mod, vdd->vp_offs.vpconfig); + vdd->vp_data->vp_common->vpconfig_initvoltage_shift)); + vdd->write_reg(vpconfig, prm_mod_offs, vdd->vp_data->vpconfig); /* Trigger initVDD value copy to voltage processor */ - vpconfig |= vdd->vp_reg.vpconfig_initvdd; - vdd->write_reg(vpconfig, mod, vdd->vp_offs.vpconfig); + vpconfig |= vdd->vp_data->vp_common->vpconfig_initvdd; + vdd->write_reg(vpconfig, prm_mod_offs, vdd->vp_data->vpconfig); /* Force update of voltage */ - vpconfig |= vdd->vp_reg.vpconfig_forceupdate; - vdd->write_reg(vpconfig, mod, vdd->vp_offs.vpconfig); + vpconfig |= vdd->vp_data->vp_common->vpconfig_forceupdate; + vdd->write_reg(vpconfig, prm_mod_offs, vdd->vp_data->vpconfig); /* * Wait for TransactionDone. Typical latency is <200us. * Depends on SMPSWAITTIMEMIN/MAX and voltage change */ timeout = 0; - omap_test_timeout((vdd->read_reg(ocp_mod, prm_irqst_reg) & - vdd->vp_reg.tranxdone_status), - VP_TRANXDONE_TIMEOUT, timeout); + omap_test_timeout((vdd->read_reg(prm_irqst_ocp_mod_offs, prm_irqst_reg) & + vdd->vp_data->prm_irqst_data->tranxdone_status), + VP_TRANXDONE_TIMEOUT, timeout); if (timeout >= VP_TRANXDONE_TIMEOUT) pr_err("%s: vdd_%s TRANXDONE timeout exceeded." "TRANXDONE never got set after the voltage update\n", @@ -704,11 +497,11 @@ static int vp_forceupdate_scale_voltage(struct omap_vdd_info *vdd, */ timeout = 0; while (timeout++ < VP_TRANXDONE_TIMEOUT) { - vdd->write_reg(vdd->vp_reg.tranxdone_status, - ocp_mod, prm_irqst_reg); - if (!(vdd->read_reg(ocp_mod, prm_irqst_reg) & - vdd->vp_reg.tranxdone_status)) - break; + vdd->write_reg(vdd->vp_data->prm_irqst_data->tranxdone_status, + prm_irqst_ocp_mod_offs, prm_irqst_reg); + if (!(vdd->read_reg(prm_irqst_ocp_mod_offs, prm_irqst_reg) & + vdd->vp_data->prm_irqst_data->tranxdone_status)) + break; udelay(1); } @@ -717,222 +510,95 @@ static int vp_forceupdate_scale_voltage(struct omap_vdd_info *vdd, "to clear the TRANXDONE status\n", __func__, vdd->voltdm.name); - vpconfig = vdd->read_reg(mod, vdd->vp_offs.vpconfig); + vpconfig = vdd->read_reg(prm_mod_offs, vdd->vp_data->vpconfig); /* Clear initVDD copy trigger bit */ - vpconfig &= ~vdd->vp_reg.vpconfig_initvdd;; - vdd->write_reg(vpconfig, mod, vdd->vp_offs.vpconfig); + vpconfig &= ~vdd->vp_data->vp_common->vpconfig_initvdd; + vdd->write_reg(vpconfig, prm_mod_offs, vdd->vp_data->vpconfig); /* Clear force bit */ - vpconfig &= ~vdd->vp_reg.vpconfig_forceupdate; - vdd->write_reg(vpconfig, mod, vdd->vp_offs.vpconfig); + vpconfig &= ~vdd->vp_data->vp_common->vpconfig_forceupdate; + vdd->write_reg(vpconfig, prm_mod_offs, vdd->vp_data->vpconfig); return 0; } -/* OMAP3 specific voltage init functions */ +static void __init omap3_vfsm_init(struct omap_vdd_info *vdd) +{ + /* + * Voltage Manager FSM parameters init + * XXX This data should be passed in from the board file + */ + vdd->write_reg(OMAP3_CLKSETUP, prm_mod_offs, OMAP3_PRM_CLKSETUP_OFFSET); + vdd->write_reg(OMAP3_VOLTOFFSET, prm_mod_offs, + OMAP3_PRM_VOLTOFFSET_OFFSET); + vdd->write_reg(OMAP3_VOLTSETUP2, prm_mod_offs, + OMAP3_PRM_VOLTSETUP2_OFFSET); +} -/* - * Intializes the voltage controller registers with the PMIC and board - * specific parameters and voltage setup times for OMAP3. - */ static void __init omap3_vc_init(struct omap_vdd_info *vdd) { - u32 vc_val; - u16 mod; - u8 on_vsel, onlp_vsel, ret_vsel, off_vsel; static bool is_initialized; + u8 on_vsel, onlp_vsel, ret_vsel, off_vsel; + u32 vc_val; - if (!vdd->pmic_info || !vdd->pmic_info->uv_to_vsel) { - pr_err("%s: PMIC info requried to configure vc for" - "vdd_%s not populated.Hence cannot initialize vc\n", - __func__, vdd->voltdm.name); - return; - } - - if (!vdd->read_reg || !vdd->write_reg) { - pr_err("%s: No read/write API for accessing vdd_%s regs\n", - __func__, vdd->voltdm.name); + if (is_initialized) return; - } - - mod = vdd->vc_reg.prm_mod; - - /* Set up the SMPS_SA(i2c slave address in VC */ - vc_val = vdd->read_reg(mod, vdd->vc_reg.smps_sa_reg); - vc_val &= ~vdd->vc_reg.smps_sa_mask; - vc_val |= vdd->pmic_info->i2c_slave_addr << vdd->vc_reg.smps_sa_shift; - vdd->write_reg(vc_val, mod, vdd->vc_reg.smps_sa_reg); - - /* Setup the VOLRA(pmic reg addr) in VC */ - vc_val = vdd->read_reg(mod, vdd->vc_reg.smps_volra_reg); - vc_val &= ~vdd->vc_reg.smps_volra_mask; - vc_val |= vdd->pmic_info->pmic_reg << vdd->vc_reg.smps_volra_shift; - vdd->write_reg(vc_val, mod, vdd->vc_reg.smps_volra_reg); - - /*Configure the setup times */ - vc_val = vdd->read_reg(mod, vdd->vc_reg.voltsetup_reg); - vc_val &= ~vdd->vc_reg.voltsetup_mask; - vc_val |= vdd->pmic_info->volt_setup_time << - vdd->vc_reg.voltsetup_shift; - vdd->write_reg(vc_val, mod, vdd->vc_reg.voltsetup_reg); /* Set up the on, inactive, retention and off voltage */ on_vsel = vdd->pmic_info->uv_to_vsel(vdd->pmic_info->on_volt); onlp_vsel = vdd->pmic_info->uv_to_vsel(vdd->pmic_info->onlp_volt); ret_vsel = vdd->pmic_info->uv_to_vsel(vdd->pmic_info->ret_volt); off_vsel = vdd->pmic_info->uv_to_vsel(vdd->pmic_info->off_volt); - vc_val = ((on_vsel << vdd->vc_reg.cmd_on_shift) | - (onlp_vsel << vdd->vc_reg.cmd_onlp_shift) | - (ret_vsel << vdd->vc_reg.cmd_ret_shift) | - (off_vsel << vdd->vc_reg.cmd_off_shift)); - vdd->write_reg(vc_val, mod, vdd->vc_reg.cmdval_reg); - - if (is_initialized) - return; + vc_val = ((on_vsel << vdd->vc_data->vc_common->cmd_on_shift) | + (onlp_vsel << vdd->vc_data->vc_common->cmd_onlp_shift) | + (ret_vsel << vdd->vc_data->vc_common->cmd_ret_shift) | + (off_vsel << vdd->vc_data->vc_common->cmd_off_shift)); + vdd->write_reg(vc_val, prm_mod_offs, vdd->vc_data->cmdval_reg); - /* Generic VC parameters init */ - vdd->write_reg(OMAP3430_CMD1_MASK | OMAP3430_RAV1_MASK, mod, + /* + * Generic VC parameters init + * XXX This data should be abstracted out + */ + vdd->write_reg(OMAP3430_CMD1_MASK | OMAP3430_RAV1_MASK, prm_mod_offs, OMAP3_PRM_VC_CH_CONF_OFFSET); - vdd->write_reg(OMAP3430_MCODE_SHIFT | OMAP3430_HSEN_MASK, mod, + vdd->write_reg(OMAP3430_MCODE_SHIFT | OMAP3430_HSEN_MASK, prm_mod_offs, OMAP3_PRM_VC_I2C_CFG_OFFSET); - vdd->write_reg(OMAP3_CLKSETUP, mod, OMAP3_PRM_CLKSETUP_OFFSET); - vdd->write_reg(OMAP3_VOLTOFFSET, mod, OMAP3_PRM_VOLTOFFSET_OFFSET); - vdd->write_reg(OMAP3_VOLTSETUP2, mod, OMAP3_PRM_VOLTSETUP2_OFFSET); + + omap3_vfsm_init(vdd); + is_initialized = true; } -/* Sets up all the VDD related info for OMAP3 */ -static int __init omap3_vdd_data_configure(struct omap_vdd_info *vdd) + +/* OMAP4 specific voltage init functions */ +static void __init omap4_vc_init(struct omap_vdd_info *vdd) { - struct clk *sys_ck; - u32 sys_clk_speed, timeout_val, waittime; + static bool is_initialized; + u32 vc_val; - if (!vdd->pmic_info) { - pr_err("%s: PMIC info requried to configure vdd_%s not" - "populated.Hence cannot initialize vdd_%s\n", - __func__, vdd->voltdm.name, vdd->voltdm.name); - return -EINVAL; - } + if (is_initialized) + return; - if (!strcmp(vdd->voltdm.name, "mpu")) { - if (cpu_is_omap3630()) - vdd->volt_data = omap36xx_vddmpu_volt_data; - else - vdd->volt_data = omap34xx_vddmpu_volt_data; - - vdd->vp_reg.tranxdone_status = OMAP3430_VP1_TRANXDONE_ST_MASK; - vdd->vc_reg.cmdval_reg = OMAP3_PRM_VC_CMD_VAL_0_OFFSET; - vdd->vc_reg.smps_sa_shift = OMAP3430_PRM_VC_SMPS_SA_SA0_SHIFT; - vdd->vc_reg.smps_sa_mask = OMAP3430_PRM_VC_SMPS_SA_SA0_MASK; - vdd->vc_reg.smps_volra_shift = OMAP3430_VOLRA0_SHIFT; - vdd->vc_reg.smps_volra_mask = OMAP3430_VOLRA0_MASK; - vdd->vc_reg.voltsetup_shift = OMAP3430_SETUP_TIME1_SHIFT; - vdd->vc_reg.voltsetup_mask = OMAP3430_SETUP_TIME1_MASK; - } else if (!strcmp(vdd->voltdm.name, "core")) { - if (cpu_is_omap3630()) - vdd->volt_data = omap36xx_vddcore_volt_data; - else - vdd->volt_data = omap34xx_vddcore_volt_data; - - vdd->vp_reg.tranxdone_status = OMAP3430_VP2_TRANXDONE_ST_MASK; - vdd->vc_reg.cmdval_reg = OMAP3_PRM_VC_CMD_VAL_1_OFFSET; - vdd->vc_reg.smps_sa_shift = OMAP3430_PRM_VC_SMPS_SA_SA1_SHIFT; - vdd->vc_reg.smps_sa_mask = OMAP3430_PRM_VC_SMPS_SA_SA1_MASK; - vdd->vc_reg.smps_volra_shift = OMAP3430_VOLRA1_SHIFT; - vdd->vc_reg.smps_volra_mask = OMAP3430_VOLRA1_MASK; - vdd->vc_reg.voltsetup_shift = OMAP3430_SETUP_TIME2_SHIFT; - vdd->vc_reg.voltsetup_mask = OMAP3430_SETUP_TIME2_MASK; - } else { - pr_warning("%s: vdd_%s does not exisit in OMAP3\n", - __func__, vdd->voltdm.name); - return -EINVAL; - } + /* TODO: Configure setup times and CMD_VAL values*/ /* - * Sys clk rate is require to calculate vp timeout value and - * smpswaittimemin and smpswaittimemax. + * Generic VC parameters init + * XXX This data should be abstracted out */ - sys_ck = clk_get(NULL, "sys_ck"); - if (IS_ERR(sys_ck)) { - pr_warning("%s: Could not get the sys clk to calculate" - "various vdd_%s params\n", __func__, vdd->voltdm.name); - return -EINVAL; - } - sys_clk_speed = clk_get_rate(sys_ck); - clk_put(sys_ck); - /* Divide to avoid overflow */ - sys_clk_speed /= 1000; - - /* Generic voltage parameters */ - vdd->curr_volt = 1200000; - vdd->ocp_mod = OCP_MOD; - vdd->prm_irqst_reg = OMAP3_PRM_IRQSTATUS_MPU_OFFSET; - vdd->read_reg = omap3_voltage_read_reg; - vdd->write_reg = omap3_voltage_write_reg; - vdd->volt_scale = vp_forceupdate_scale_voltage; - vdd->vp_enabled = false; + vc_val = (OMAP4430_RAV_VDD_MPU_L_MASK | OMAP4430_CMD_VDD_MPU_L_MASK | + OMAP4430_RAV_VDD_IVA_L_MASK | OMAP4430_CMD_VDD_IVA_L_MASK | + OMAP4430_RAV_VDD_CORE_L_MASK | OMAP4430_CMD_VDD_CORE_L_MASK); + vdd->write_reg(vc_val, prm_mod_offs, OMAP4_PRM_VC_CFG_CHANNEL_OFFSET); - /* VC parameters */ - vdd->vc_reg.prm_mod = OMAP3430_GR_MOD; - vdd->vc_reg.smps_sa_reg = OMAP3_PRM_VC_SMPS_SA_OFFSET; - vdd->vc_reg.smps_volra_reg = OMAP3_PRM_VC_SMPS_VOL_RA_OFFSET; - vdd->vc_reg.bypass_val_reg = OMAP3_PRM_VC_BYPASS_VAL_OFFSET; - vdd->vc_reg.voltsetup_reg = OMAP3_PRM_VOLTSETUP1_OFFSET; - vdd->vc_reg.data_shift = OMAP3430_DATA_SHIFT; - vdd->vc_reg.slaveaddr_shift = OMAP3430_SLAVEADDR_SHIFT; - vdd->vc_reg.regaddr_shift = OMAP3430_REGADDR_SHIFT; - vdd->vc_reg.valid = OMAP3430_VALID_MASK; - vdd->vc_reg.cmd_on_shift = OMAP3430_VC_CMD_ON_SHIFT; - vdd->vc_reg.cmd_on_mask = OMAP3430_VC_CMD_ON_MASK; - vdd->vc_reg.cmd_onlp_shift = OMAP3430_VC_CMD_ONLP_SHIFT; - vdd->vc_reg.cmd_ret_shift = OMAP3430_VC_CMD_RET_SHIFT; - vdd->vc_reg.cmd_off_shift = OMAP3430_VC_CMD_OFF_SHIFT; - - vdd->vp_reg.prm_mod = OMAP3430_GR_MOD; - - /* VPCONFIG bit fields */ - vdd->vp_reg.vpconfig_erroroffset = (vdd->pmic_info->vp_erroroffset << - OMAP3430_ERROROFFSET_SHIFT); - vdd->vp_reg.vpconfig_errorgain_mask = OMAP3430_ERRORGAIN_MASK; - vdd->vp_reg.vpconfig_errorgain_shift = OMAP3430_ERRORGAIN_SHIFT; - vdd->vp_reg.vpconfig_initvoltage_shift = OMAP3430_INITVOLTAGE_SHIFT; - vdd->vp_reg.vpconfig_initvoltage_mask = OMAP3430_INITVOLTAGE_MASK; - vdd->vp_reg.vpconfig_timeouten = OMAP3430_TIMEOUTEN_MASK; - vdd->vp_reg.vpconfig_initvdd = OMAP3430_INITVDD_MASK; - vdd->vp_reg.vpconfig_forceupdate = OMAP3430_FORCEUPDATE_MASK; - vdd->vp_reg.vpconfig_vpenable = OMAP3430_VPENABLE_MASK; - - /* VSTEPMIN VSTEPMAX bit fields */ - waittime = ((vdd->pmic_info->step_size / vdd->pmic_info->slew_rate) * - sys_clk_speed) / 1000; - vdd->vp_reg.vstepmin_smpswaittimemin = waittime; - vdd->vp_reg.vstepmax_smpswaittimemax = waittime; - vdd->vp_reg.vstepmin_stepmin = vdd->pmic_info->vp_vstepmin; - vdd->vp_reg.vstepmax_stepmax = vdd->pmic_info->vp_vstepmax; - vdd->vp_reg.vstepmin_smpswaittimemin_shift = - OMAP3430_SMPSWAITTIMEMIN_SHIFT; - vdd->vp_reg.vstepmax_smpswaittimemax_shift = - OMAP3430_SMPSWAITTIMEMAX_SHIFT; - vdd->vp_reg.vstepmin_stepmin_shift = OMAP3430_VSTEPMIN_SHIFT; - vdd->vp_reg.vstepmax_stepmax_shift = OMAP3430_VSTEPMAX_SHIFT; - - /* VLIMITTO bit fields */ - timeout_val = (sys_clk_speed * vdd->pmic_info->vp_timeout_us) / 1000; - vdd->vp_reg.vlimitto_timeout = timeout_val; - vdd->vp_reg.vlimitto_vddmin = vdd->pmic_info->vp_vddmin; - vdd->vp_reg.vlimitto_vddmax = vdd->pmic_info->vp_vddmax; - vdd->vp_reg.vlimitto_vddmin_shift = OMAP3430_VDDMIN_SHIFT; - vdd->vp_reg.vlimitto_vddmax_shift = OMAP3430_VDDMAX_SHIFT; - vdd->vp_reg.vlimitto_timeout_shift = OMAP3430_TIMEOUT_SHIFT; + /* XXX These are magic numbers and do not belong! */ + vc_val = (0x60 << OMAP4430_SCLL_SHIFT | 0x26 << OMAP4430_SCLH_SHIFT); + vdd->write_reg(vc_val, prm_mod_offs, OMAP4_PRM_VC_CFG_I2C_CLK_OFFSET); - return 0; + is_initialized = true; } -/* OMAP4 specific voltage init functions */ -static void __init omap4_vc_init(struct omap_vdd_info *vdd) +static void __init omap_vc_init(struct omap_vdd_info *vdd) { u32 vc_val; - u16 mod; - static bool is_initialized; if (!vdd->pmic_info || !vdd->pmic_info->uv_to_vsel) { pr_err("%s: PMIC info requried to configure vc for" @@ -947,173 +613,61 @@ static void __init omap4_vc_init(struct omap_vdd_info *vdd) return; } - mod = vdd->vc_reg.prm_mod; - /* Set up the SMPS_SA(i2c slave address in VC */ - vc_val = vdd->read_reg(mod, vdd->vc_reg.smps_sa_reg); - vc_val &= ~vdd->vc_reg.smps_sa_mask; - vc_val |= vdd->pmic_info->i2c_slave_addr << vdd->vc_reg.smps_sa_shift; - vdd->write_reg(vc_val, mod, vdd->vc_reg.smps_sa_reg); + vc_val = vdd->read_reg(prm_mod_offs, + vdd->vc_data->vc_common->smps_sa_reg); + vc_val &= ~vdd->vc_data->smps_sa_mask; + vc_val |= vdd->pmic_info->i2c_slave_addr << vdd->vc_data->smps_sa_shift; + vdd->write_reg(vc_val, prm_mod_offs, + vdd->vc_data->vc_common->smps_sa_reg); /* Setup the VOLRA(pmic reg addr) in VC */ - vc_val = vdd->read_reg(mod, vdd->vc_reg.smps_volra_reg); - vc_val &= ~vdd->vc_reg.smps_volra_mask; - vc_val |= vdd->pmic_info->pmic_reg << vdd->vc_reg.smps_volra_shift; - vdd->write_reg(vc_val, mod, vdd->vc_reg.smps_volra_reg); - - /* TODO: Configure setup times and CMD_VAL values*/ - - if (is_initialized) - return; - - /* Generic VC parameters init */ - vc_val = (OMAP4430_RAV_VDD_MPU_L_MASK | OMAP4430_CMD_VDD_MPU_L_MASK | - OMAP4430_RAV_VDD_IVA_L_MASK | OMAP4430_CMD_VDD_IVA_L_MASK | - OMAP4430_RAV_VDD_CORE_L_MASK | OMAP4430_CMD_VDD_CORE_L_MASK); - vdd->write_reg(vc_val, mod, OMAP4_PRM_VC_CFG_CHANNEL_OFFSET); - - vc_val = (0x60 << OMAP4430_SCLL_SHIFT | 0x26 << OMAP4430_SCLH_SHIFT); - vdd->write_reg(vc_val, mod, OMAP4_PRM_VC_CFG_I2C_CLK_OFFSET); + vc_val = vdd->read_reg(prm_mod_offs, + vdd->vc_data->vc_common->smps_volra_reg); + vc_val &= ~vdd->vc_data->smps_volra_mask; + vc_val |= vdd->pmic_info->pmic_reg << vdd->vc_data->smps_volra_shift; + vdd->write_reg(vc_val, prm_mod_offs, + vdd->vc_data->vc_common->smps_volra_reg); + + /* Configure the setup times */ + vc_val = vdd->read_reg(prm_mod_offs, vdd->vfsm->voltsetup_reg); + vc_val &= ~vdd->vfsm->voltsetup_mask; + vc_val |= vdd->pmic_info->volt_setup_time << + vdd->vfsm->voltsetup_shift; + vdd->write_reg(vc_val, prm_mod_offs, vdd->vfsm->voltsetup_reg); - is_initialized = true; + if (cpu_is_omap34xx()) + omap3_vc_init(vdd); + else if (cpu_is_omap44xx()) + omap4_vc_init(vdd); } -/* Sets up all the VDD related info for OMAP4 */ -static int __init omap4_vdd_data_configure(struct omap_vdd_info *vdd) +static int __init omap_vdd_data_configure(struct omap_vdd_info *vdd) { - struct clk *sys_ck; - u32 sys_clk_speed, timeout_val, waittime; + int ret = -EINVAL; if (!vdd->pmic_info) { pr_err("%s: PMIC info requried to configure vdd_%s not" "populated.Hence cannot initialize vdd_%s\n", __func__, vdd->voltdm.name, vdd->voltdm.name); - return -EINVAL; + goto ovdc_out; } - if (!strcmp(vdd->voltdm.name, "mpu")) { - vdd->volt_data = omap44xx_vdd_mpu_volt_data; - vdd->vp_reg.tranxdone_status = - OMAP4430_VP_MPU_TRANXDONE_ST_MASK; - vdd->vc_reg.cmdval_reg = OMAP4_PRM_VC_VAL_CMD_VDD_MPU_L_OFFSET; - vdd->vc_reg.smps_sa_shift = - OMAP4430_SA_VDD_MPU_L_PRM_VC_SMPS_SA_SHIFT; - vdd->vc_reg.smps_sa_mask = - OMAP4430_SA_VDD_MPU_L_PRM_VC_SMPS_SA_MASK; - vdd->vc_reg.smps_volra_shift = OMAP4430_VOLRA_VDD_MPU_L_SHIFT; - vdd->vc_reg.smps_volra_mask = OMAP4430_VOLRA_VDD_MPU_L_MASK; - vdd->vc_reg.voltsetup_reg = - OMAP4_PRM_VOLTSETUP_MPU_RET_SLEEP_OFFSET; - vdd->prm_irqst_reg = OMAP4_PRM_IRQSTATUS_MPU_2_OFFSET; - } else if (!strcmp(vdd->voltdm.name, "core")) { - vdd->volt_data = omap44xx_vdd_core_volt_data; - vdd->vp_reg.tranxdone_status = - OMAP4430_VP_CORE_TRANXDONE_ST_MASK; - vdd->vc_reg.cmdval_reg = - OMAP4_PRM_VC_VAL_CMD_VDD_CORE_L_OFFSET; - vdd->vc_reg.smps_sa_shift = OMAP4430_SA_VDD_CORE_L_0_6_SHIFT; - vdd->vc_reg.smps_sa_mask = OMAP4430_SA_VDD_CORE_L_0_6_MASK; - vdd->vc_reg.smps_volra_shift = OMAP4430_VOLRA_VDD_CORE_L_SHIFT; - vdd->vc_reg.smps_volra_mask = OMAP4430_VOLRA_VDD_CORE_L_MASK; - vdd->vc_reg.voltsetup_reg = - OMAP4_PRM_VOLTSETUP_CORE_RET_SLEEP_OFFSET; - vdd->prm_irqst_reg = OMAP4_PRM_IRQSTATUS_MPU_OFFSET; - } else if (!strcmp(vdd->voltdm.name, "iva")) { - vdd->volt_data = omap44xx_vdd_iva_volt_data; - vdd->vp_reg.tranxdone_status = - OMAP4430_VP_IVA_TRANXDONE_ST_MASK; - vdd->vc_reg.cmdval_reg = OMAP4_PRM_VC_VAL_CMD_VDD_IVA_L_OFFSET; - vdd->vc_reg.smps_sa_shift = - OMAP4430_SA_VDD_IVA_L_PRM_VC_SMPS_SA_SHIFT; - vdd->vc_reg.smps_sa_mask = - OMAP4430_SA_VDD_IVA_L_PRM_VC_SMPS_SA_MASK; - vdd->vc_reg.smps_volra_shift = OMAP4430_VOLRA_VDD_IVA_L_SHIFT; - vdd->vc_reg.smps_volra_mask = OMAP4430_VOLRA_VDD_IVA_L_MASK; - vdd->vc_reg.voltsetup_reg = - OMAP4_PRM_VOLTSETUP_IVA_RET_SLEEP_OFFSET; - vdd->prm_irqst_reg = OMAP4_PRM_IRQSTATUS_MPU_OFFSET; - } else { - pr_warning("%s: vdd_%s does not exisit in OMAP4\n", - __func__, vdd->voltdm.name); - return -EINVAL; - } + if (IS_ERR_VALUE(_config_common_vdd_data(vdd))) + goto ovdc_out; - /* - * Sys clk rate is require to calculate vp timeout value and - * smpswaittimemin and smpswaittimemax. - */ - sys_ck = clk_get(NULL, "sys_clkin_ck"); - if (IS_ERR(sys_ck)) { - pr_warning("%s: Could not get the sys clk to calculate" - "various vdd_%s params\n", __func__, vdd->voltdm.name); - return -EINVAL; + if (cpu_is_omap34xx()) { + vdd->read_reg = omap3_voltage_read_reg; + vdd->write_reg = omap3_voltage_write_reg; + ret = 0; + } else if (cpu_is_omap44xx()) { + vdd->read_reg = omap4_voltage_read_reg; + vdd->write_reg = omap4_voltage_write_reg; + ret = 0; } - sys_clk_speed = clk_get_rate(sys_ck); - clk_put(sys_ck); - /* Divide to avoid overflow */ - sys_clk_speed /= 1000; - - /* Generic voltage parameters */ - vdd->curr_volt = 1200000; - vdd->ocp_mod = OMAP4430_PRM_OCP_SOCKET_INST; - vdd->read_reg = omap4_voltage_read_reg; - vdd->write_reg = omap4_voltage_write_reg; - vdd->volt_scale = vp_forceupdate_scale_voltage; - vdd->vp_enabled = false; - /* VC parameters */ - vdd->vc_reg.prm_mod = OMAP4430_PRM_DEVICE_INST; - vdd->vc_reg.smps_sa_reg = OMAP4_PRM_VC_SMPS_SA_OFFSET; - vdd->vc_reg.smps_volra_reg = OMAP4_PRM_VC_VAL_SMPS_RA_VOL_OFFSET; - vdd->vc_reg.bypass_val_reg = OMAP4_PRM_VC_VAL_BYPASS_OFFSET; - vdd->vc_reg.data_shift = OMAP4430_DATA_SHIFT; - vdd->vc_reg.slaveaddr_shift = OMAP4430_SLAVEADDR_SHIFT; - vdd->vc_reg.regaddr_shift = OMAP4430_REGADDR_SHIFT; - vdd->vc_reg.valid = OMAP4430_VALID_MASK; - vdd->vc_reg.cmd_on_shift = OMAP4430_ON_SHIFT; - vdd->vc_reg.cmd_on_mask = OMAP4430_ON_MASK; - vdd->vc_reg.cmd_onlp_shift = OMAP4430_ONLP_SHIFT; - vdd->vc_reg.cmd_ret_shift = OMAP4430_RET_SHIFT; - vdd->vc_reg.cmd_off_shift = OMAP4430_OFF_SHIFT; - - vdd->vp_reg.prm_mod = OMAP4430_PRM_DEVICE_INST; - - /* VPCONFIG bit fields */ - vdd->vp_reg.vpconfig_erroroffset = (vdd->pmic_info->vp_erroroffset << - OMAP4430_ERROROFFSET_SHIFT); - vdd->vp_reg.vpconfig_errorgain_mask = OMAP4430_ERRORGAIN_MASK; - vdd->vp_reg.vpconfig_errorgain_shift = OMAP4430_ERRORGAIN_SHIFT; - vdd->vp_reg.vpconfig_initvoltage_shift = OMAP4430_INITVOLTAGE_SHIFT; - vdd->vp_reg.vpconfig_initvoltage_mask = OMAP4430_INITVOLTAGE_MASK; - vdd->vp_reg.vpconfig_timeouten = OMAP4430_TIMEOUTEN_MASK; - vdd->vp_reg.vpconfig_initvdd = OMAP4430_INITVDD_MASK; - vdd->vp_reg.vpconfig_forceupdate = OMAP4430_FORCEUPDATE_MASK; - vdd->vp_reg.vpconfig_vpenable = OMAP4430_VPENABLE_MASK; - - /* VSTEPMIN VSTEPMAX bit fields */ - waittime = ((vdd->pmic_info->step_size / vdd->pmic_info->slew_rate) * - sys_clk_speed) / 1000; - vdd->vp_reg.vstepmin_smpswaittimemin = waittime; - vdd->vp_reg.vstepmax_smpswaittimemax = waittime; - vdd->vp_reg.vstepmin_stepmin = vdd->pmic_info->vp_vstepmin; - vdd->vp_reg.vstepmax_stepmax = vdd->pmic_info->vp_vstepmax; - vdd->vp_reg.vstepmin_smpswaittimemin_shift = - OMAP4430_SMPSWAITTIMEMIN_SHIFT; - vdd->vp_reg.vstepmax_smpswaittimemax_shift = - OMAP4430_SMPSWAITTIMEMAX_SHIFT; - vdd->vp_reg.vstepmin_stepmin_shift = OMAP4430_VSTEPMIN_SHIFT; - vdd->vp_reg.vstepmax_stepmax_shift = OMAP4430_VSTEPMAX_SHIFT; - - /* VLIMITTO bit fields */ - timeout_val = (sys_clk_speed * vdd->pmic_info->vp_timeout_us) / 1000; - vdd->vp_reg.vlimitto_timeout = timeout_val; - vdd->vp_reg.vlimitto_vddmin = vdd->pmic_info->vp_vddmin; - vdd->vp_reg.vlimitto_vddmax = vdd->pmic_info->vp_vddmax; - vdd->vp_reg.vlimitto_vddmin_shift = OMAP4430_VDDMIN_SHIFT; - vdd->vp_reg.vlimitto_vddmax_shift = OMAP4430_VDDMAX_SHIFT; - vdd->vp_reg.vlimitto_timeout_shift = OMAP4430_TIMEOUT_SHIFT; - - return 0; +ovdc_out: + return ret; } /* Public functions */ @@ -1161,8 +715,7 @@ unsigned long omap_vp_get_curr_volt(struct voltagedomain *voltdm) return 0; } - curr_vsel = vdd->read_reg(vdd->vp_reg.prm_mod, - vdd->vp_offs.voltage); + curr_vsel = vdd->read_reg(prm_mod_offs, vdd->vp_data->voltage); if (!vdd->pmic_info || !vdd->pmic_info->vsel_to_uv) { pr_warning("%s: PMIC function to convert vsel to voltage" @@ -1184,7 +737,6 @@ void omap_vp_enable(struct voltagedomain *voltdm) { struct omap_vdd_info *vdd; u32 vpconfig; - u16 mod; if (!voltdm || IS_ERR(voltdm)) { pr_warning("%s: VDD specified does not exist!\n", __func__); @@ -1198,8 +750,6 @@ void omap_vp_enable(struct voltagedomain *voltdm) return; } - mod = vdd->vp_reg.prm_mod; - /* If VP is already enabled, do nothing. Return */ if (vdd->vp_enabled) return; @@ -1207,9 +757,9 @@ void omap_vp_enable(struct voltagedomain *voltdm) vp_latch_vsel(vdd); /* Enable VP */ - vpconfig = vdd->read_reg(mod, vdd->vp_offs.vpconfig); - vpconfig |= vdd->vp_reg.vpconfig_vpenable; - vdd->write_reg(vpconfig, mod, vdd->vp_offs.vpconfig); + vpconfig = vdd->read_reg(prm_mod_offs, vdd->vp_data->vpconfig); + vpconfig |= vdd->vp_data->vp_common->vpconfig_vpenable; + vdd->write_reg(vpconfig, prm_mod_offs, vdd->vp_data->vpconfig); vdd->vp_enabled = true; } @@ -1224,7 +774,6 @@ void omap_vp_disable(struct voltagedomain *voltdm) { struct omap_vdd_info *vdd; u32 vpconfig; - u16 mod; int timeout; if (!voltdm || IS_ERR(voltdm)) { @@ -1239,8 +788,6 @@ void omap_vp_disable(struct voltagedomain *voltdm) return; } - mod = vdd->vp_reg.prm_mod; - /* If VP is already disabled, do nothing. Return */ if (!vdd->vp_enabled) { pr_warning("%s: Trying to disable VP for vdd_%s when" @@ -1249,14 +796,14 @@ void omap_vp_disable(struct voltagedomain *voltdm) } /* Disable VP */ - vpconfig = vdd->read_reg(mod, vdd->vp_offs.vpconfig); - vpconfig &= ~vdd->vp_reg.vpconfig_vpenable; - vdd->write_reg(vpconfig, mod, vdd->vp_offs.vpconfig); + vpconfig = vdd->read_reg(prm_mod_offs, vdd->vp_data->vpconfig); + vpconfig &= ~vdd->vp_data->vp_common->vpconfig_vpenable; + vdd->write_reg(vpconfig, prm_mod_offs, vdd->vp_data->vpconfig); /* * Wait for VP idle Typical latency is <2us. Maximum latency is ~100us */ - omap_test_timeout((vdd->read_reg(mod, vdd->vp_offs.vstatus)), + omap_test_timeout((vdd->read_reg(prm_mod_offs, vdd->vp_data->vstatus)), VP_IDLE_TIMEOUT, timeout); if (timeout >= VP_IDLE_TIMEOUT) @@ -1509,8 +1056,8 @@ struct voltagedomain *omap_voltage_domain_lookup(char *name) } for (i = 0; i < nr_scalable_vdd; i++) { - if (!(strcmp(name, vdd_info[i].voltdm.name))) - return &vdd_info[i].voltdm; + if (!(strcmp(name, vdd_info[i]->voltdm.name))) + return &vdd_info[i]->voltdm; } return ERR_PTR(-EINVAL); @@ -1538,35 +1085,24 @@ int __init omap_voltage_late_init(void) pr_err("%s: Unable to create voltage debugfs main dir\n", __func__); for (i = 0; i < nr_scalable_vdd; i++) { - if (vdd_data_configure(&vdd_info[i])) + if (omap_vdd_data_configure(vdd_info[i])) continue; - vc_init(&vdd_info[i]); - vp_init(&vdd_info[i]); - vdd_debugfs_init(&vdd_info[i]); + omap_vc_init(vdd_info[i]); + vp_init(vdd_info[i]); + vdd_debugfs_init(vdd_info[i]); } return 0; } -/** - * omap_voltage_early_init()- Volatage driver early init - */ -static int __init omap_voltage_early_init(void) +/* XXX document */ +int __init omap_voltage_early_init(s16 prm_mod, s16 prm_irqst_ocp_mod, + struct omap_vdd_info *omap_vdd_array[], + u8 omap_vdd_count) { - if (cpu_is_omap34xx()) { - vdd_info = omap3_vdd_info; - nr_scalable_vdd = OMAP3_NR_SCALABLE_VDD; - vc_init = omap3_vc_init; - vdd_data_configure = omap3_vdd_data_configure; - } else if (cpu_is_omap44xx()) { - vdd_info = omap4_vdd_info; - nr_scalable_vdd = OMAP4_NR_SCALABLE_VDD; - vc_init = omap4_vc_init; - vdd_data_configure = omap4_vdd_data_configure; - } else { - pr_warning("%s: voltage driver support not added\n", __func__); - } - + prm_mod_offs = prm_mod; + prm_irqst_ocp_mod_offs = prm_irqst_ocp_mod; + vdd_info = omap_vdd_array; + nr_scalable_vdd = omap_vdd_count; return 0; } -core_initcall(omap_voltage_early_init); diff --git a/arch/arm/plat-omap/include/plat/voltage.h b/arch/arm/mach-omap2/voltage.h index 5bd204e55c3..e9f5408244e 100644 --- a/arch/arm/plat-omap/include/plat/voltage.h +++ b/arch/arm/mach-omap2/voltage.h @@ -16,6 +16,10 @@ #include <linux/err.h> +#include "vc.h" +#include "vp.h" + +/* XXX document */ #define VOLTSCALE_VPFORCEUPDATE 1 #define VOLTSCALE_VCBYPASS 2 @@ -27,36 +31,22 @@ #define OMAP3_VOLTOFFSET 0xff #define OMAP3_VOLTSETUP2 0xff -/* Voltage value defines */ -#define OMAP3430_VDD_MPU_OPP1_UV 975000 -#define OMAP3430_VDD_MPU_OPP2_UV 1075000 -#define OMAP3430_VDD_MPU_OPP3_UV 1200000 -#define OMAP3430_VDD_MPU_OPP4_UV 1270000 -#define OMAP3430_VDD_MPU_OPP5_UV 1350000 - -#define OMAP3430_VDD_CORE_OPP1_UV 975000 -#define OMAP3430_VDD_CORE_OPP2_UV 1050000 -#define OMAP3430_VDD_CORE_OPP3_UV 1150000 - -#define OMAP3630_VDD_MPU_OPP50_UV 1012500 -#define OMAP3630_VDD_MPU_OPP100_UV 1200000 -#define OMAP3630_VDD_MPU_OPP120_UV 1325000 -#define OMAP3630_VDD_MPU_OPP1G_UV 1375000 - -#define OMAP3630_VDD_CORE_OPP50_UV 1000000 -#define OMAP3630_VDD_CORE_OPP100_UV 1200000 - -#define OMAP4430_VDD_MPU_OPP50_UV 930000 -#define OMAP4430_VDD_MPU_OPP100_UV 1100000 -#define OMAP4430_VDD_MPU_OPPTURBO_UV 1260000 -#define OMAP4430_VDD_MPU_OPPNITRO_UV 1350000 - -#define OMAP4430_VDD_IVA_OPP50_UV 930000 -#define OMAP4430_VDD_IVA_OPP100_UV 1100000 -#define OMAP4430_VDD_IVA_OPPTURBO_UV 1260000 - -#define OMAP4430_VDD_CORE_OPP50_UV 930000 -#define OMAP4430_VDD_CORE_OPP100_UV 1100000 +/** + * struct omap_vfsm_instance_data - per-voltage manager FSM register/bitfield + * data + * @voltsetup_mask: SETUP_TIME* bitmask in the PRM_VOLTSETUP* register + * @voltsetup_reg: register offset of PRM_VOLTSETUP from PRM base + * @voltsetup_shift: SETUP_TIME* field shift in the PRM_VOLTSETUP* register + * + * XXX What about VOLTOFFSET/VOLTCTRL? + * XXX It is not necessary to have both a _mask and a _shift for the same + * bitfield - remove one! + */ +struct omap_vfsm_instance_data { + u32 voltsetup_mask; + u8 voltsetup_reg; + u8 voltsetup_shift; +}; /** * struct voltagedomain - omap voltage domain global structure. @@ -113,6 +103,42 @@ struct omap_volt_pmic_info { u8 (*uv_to_vsel) (unsigned long uV); }; +/** + * omap_vdd_info - Per Voltage Domain info + * + * @volt_data : voltage table having the distinct voltages supported + * by the domain and other associated per voltage data. + * @pmic_info : pmic specific parameters which should be populted by + * the pmic drivers. + * @vp_data : the register values, shifts, masks for various + * vp registers + * @vp_rt_data : VP data derived at runtime, not predefined + * @vc_data : structure containing various various vc registers, + * shifts, masks etc. + * @vfsm : voltage manager FSM data + * @voltdm : pointer to the voltage domain structure + * @debug_dir : debug directory for this voltage domain. + * @curr_volt : current voltage for this vdd. + * @vp_enabled : flag to keep track of whether vp is enabled or not + * @volt_scale : API to scale the voltage of the vdd. + */ +struct omap_vdd_info { + struct omap_volt_data *volt_data; + struct omap_volt_pmic_info *pmic_info; + struct omap_vp_instance_data *vp_data; + struct omap_vp_runtime_data vp_rt_data; + struct omap_vc_instance_data *vc_data; + const struct omap_vfsm_instance_data *vfsm; + struct voltagedomain voltdm; + struct dentry *debug_dir; + u32 curr_volt; + bool vp_enabled; + u32 (*read_reg) (u16 mod, u8 offset); + void (*write_reg) (u32 val, u16 mod, u8 offset); + int (*volt_scale) (struct omap_vdd_info *vdd, + unsigned long target_volt); +}; + unsigned long omap_vp_get_curr_volt(struct voltagedomain *voltdm); void omap_vp_enable(struct voltagedomain *voltdm); void omap_vp_disable(struct voltagedomain *voltdm); @@ -125,6 +151,9 @@ struct omap_volt_data *omap_voltage_get_voltdata(struct voltagedomain *voltdm, unsigned long volt); unsigned long omap_voltage_get_nom_volt(struct voltagedomain *voltdm); struct dentry *omap_voltage_get_dbgdir(struct voltagedomain *voltdm); +int __init omap_voltage_early_init(s16 prm_mod, s16 prm_irqst_mod, + struct omap_vdd_info *omap_vdd_array[], + u8 omap_vdd_count); #ifdef CONFIG_PM int omap_voltage_register_pmic(struct voltagedomain *voltdm, struct omap_volt_pmic_info *pmic_info); diff --git a/arch/arm/mach-omap2/voltagedomains3xxx_data.c b/arch/arm/mach-omap2/voltagedomains3xxx_data.c new file mode 100644 index 00000000000..def230fd2fd --- /dev/null +++ b/arch/arm/mach-omap2/voltagedomains3xxx_data.c @@ -0,0 +1,95 @@ +/* + * OMAP3 voltage domain data + * + * Copyright (C) 2007, 2010 Texas Instruments, Inc. + * Rajendra Nayak <rnayak@ti.com> + * Lesly A M <x0080970@ti.com> + * Thara Gopinath <thara@ti.com> + * + * Copyright (C) 2008, 2011 Nokia Corporation + * Kalle Jokiniemi + * Paul Walmsley + * + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License version 2 as + * published by the Free Software Foundation. + */ +#include <linux/kernel.h> +#include <linux/err.h> +#include <linux/init.h> + +#include <plat/common.h> +#include <plat/cpu.h> + +#include "prm-regbits-34xx.h" +#include "omap_opp_data.h" +#include "voltage.h" +#include "vc.h" +#include "vp.h" + +/* + * VDD data + */ + +static const struct omap_vfsm_instance_data omap3_vdd1_vfsm_data = { + .voltsetup_reg = OMAP3_PRM_VOLTSETUP1_OFFSET, + .voltsetup_shift = OMAP3430_SETUP_TIME1_SHIFT, + .voltsetup_mask = OMAP3430_SETUP_TIME1_MASK, +}; + +static struct omap_vdd_info omap3_vdd1_info = { + .vp_data = &omap3_vp1_data, + .vc_data = &omap3_vc1_data, + .vfsm = &omap3_vdd1_vfsm_data, + .voltdm = { + .name = "mpu", + }, +}; + +static const struct omap_vfsm_instance_data omap3_vdd2_vfsm_data = { + .voltsetup_reg = OMAP3_PRM_VOLTSETUP1_OFFSET, + .voltsetup_shift = OMAP3430_SETUP_TIME2_SHIFT, + .voltsetup_mask = OMAP3430_SETUP_TIME2_MASK, +}; + +static struct omap_vdd_info omap3_vdd2_info = { + .vp_data = &omap3_vp2_data, + .vc_data = &omap3_vc2_data, + .vfsm = &omap3_vdd2_vfsm_data, + .voltdm = { + .name = "core", + }, +}; + +/* OMAP3 VDD structures */ +static struct omap_vdd_info *omap3_vdd_info[] = { + &omap3_vdd1_info, + &omap3_vdd2_info, +}; + +/* OMAP3 specific voltage init functions */ +static int __init omap3xxx_voltage_early_init(void) +{ + s16 prm_mod = OMAP3430_GR_MOD; + s16 prm_irqst_ocp_mod = OCP_MOD; + + if (!cpu_is_omap34xx()) + return 0; + + /* + * XXX Will depend on the process, validation, and binning + * for the currently-running IC + */ + if (cpu_is_omap3630()) { + omap3_vdd1_info.volt_data = omap36xx_vddmpu_volt_data; + omap3_vdd2_info.volt_data = omap36xx_vddcore_volt_data; + } else { + omap3_vdd1_info.volt_data = omap34xx_vddmpu_volt_data; + omap3_vdd2_info.volt_data = omap34xx_vddcore_volt_data; + } + + return omap_voltage_early_init(prm_mod, prm_irqst_ocp_mod, + omap3_vdd_info, + ARRAY_SIZE(omap3_vdd_info)); +}; +core_initcall(omap3xxx_voltage_early_init); diff --git a/arch/arm/mach-omap2/voltagedomains44xx_data.c b/arch/arm/mach-omap2/voltagedomains44xx_data.c new file mode 100644 index 00000000000..cb64996de0e --- /dev/null +++ b/arch/arm/mach-omap2/voltagedomains44xx_data.c @@ -0,0 +1,102 @@ +/* + * OMAP3/OMAP4 Voltage Management Routines + * + * Author: Thara Gopinath <thara@ti.com> + * + * Copyright (C) 2007 Texas Instruments, Inc. + * Rajendra Nayak <rnayak@ti.com> + * Lesly A M <x0080970@ti.com> + * + * Copyright (C) 2008 Nokia Corporation + * Kalle Jokiniemi + * + * Copyright (C) 2010 Texas Instruments, Inc. + * Thara Gopinath <thara@ti.com> + * + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License version 2 as + * published by the Free Software Foundation. + */ +#include <linux/kernel.h> +#include <linux/err.h> +#include <linux/init.h> + +#include <plat/common.h> + +#include "prm-regbits-44xx.h" +#include "prm44xx.h" +#include "prcm44xx.h" +#include "prminst44xx.h" +#include "voltage.h" +#include "omap_opp_data.h" +#include "vc.h" +#include "vp.h" + +static const struct omap_vfsm_instance_data omap4_vdd_mpu_vfsm_data = { + .voltsetup_reg = OMAP4_PRM_VOLTSETUP_MPU_RET_SLEEP_OFFSET, +}; + +static struct omap_vdd_info omap4_vdd_mpu_info = { + .vp_data = &omap4_vp_mpu_data, + .vc_data = &omap4_vc_mpu_data, + .vfsm = &omap4_vdd_mpu_vfsm_data, + .voltdm = { + .name = "mpu", + }, +}; + +static const struct omap_vfsm_instance_data omap4_vdd_iva_vfsm_data = { + .voltsetup_reg = OMAP4_PRM_VOLTSETUP_IVA_RET_SLEEP_OFFSET, +}; + +static struct omap_vdd_info omap4_vdd_iva_info = { + .vp_data = &omap4_vp_iva_data, + .vc_data = &omap4_vc_iva_data, + .vfsm = &omap4_vdd_iva_vfsm_data, + .voltdm = { + .name = "iva", + }, +}; + +static const struct omap_vfsm_instance_data omap4_vdd_core_vfsm_data = { + .voltsetup_reg = OMAP4_PRM_VOLTSETUP_CORE_RET_SLEEP_OFFSET, +}; + +static struct omap_vdd_info omap4_vdd_core_info = { + .vp_data = &omap4_vp_core_data, + .vc_data = &omap4_vc_core_data, + .vfsm = &omap4_vdd_core_vfsm_data, + .voltdm = { + .name = "core", + }, +}; + +/* OMAP4 VDD structures */ +static struct omap_vdd_info *omap4_vdd_info[] = { + &omap4_vdd_mpu_info, + &omap4_vdd_iva_info, + &omap4_vdd_core_info, +}; + +/* OMAP4 specific voltage init functions */ +static int __init omap44xx_voltage_early_init(void) +{ + s16 prm_mod = OMAP4430_PRM_DEVICE_INST; + s16 prm_irqst_ocp_mod = OMAP4430_PRM_OCP_SOCKET_INST; + + if (!cpu_is_omap44xx()) + return 0; + + /* + * XXX Will depend on the process, validation, and binning + * for the currently-running IC + */ + omap4_vdd_mpu_info.volt_data = omap44xx_vdd_mpu_volt_data; + omap4_vdd_iva_info.volt_data = omap44xx_vdd_iva_volt_data; + omap4_vdd_core_info.volt_data = omap44xx_vdd_core_volt_data; + + return omap_voltage_early_init(prm_mod, prm_irqst_ocp_mod, + omap4_vdd_info, + ARRAY_SIZE(omap4_vdd_info)); +}; +core_initcall(omap44xx_voltage_early_init); diff --git a/arch/arm/mach-omap2/vp.h b/arch/arm/mach-omap2/vp.h new file mode 100644 index 00000000000..7ce134f7de7 --- /dev/null +++ b/arch/arm/mach-omap2/vp.h @@ -0,0 +1,143 @@ +/* + * OMAP3/4 Voltage Processor (VP) structure and macro definitions + * + * Copyright (C) 2007, 2010 Texas Instruments, Inc. + * Rajendra Nayak <rnayak@ti.com> + * Lesly A M <x0080970@ti.com> + * Thara Gopinath <thara@ti.com> + * + * Copyright (C) 2008, 2011 Nokia Corporation + * Kalle Jokiniemi + * Paul Walmsley + * + * This program is free software; you can redistribute it and/or + * modify it under the terms of the GNU General Public License version + * 2 as published by the Free Software Foundation. + */ +#ifndef __ARCH_ARM_MACH_OMAP2_VP_H +#define __ARCH_ARM_MACH_OMAP2_VP_H + +#include <linux/kernel.h> + +/* XXX document */ +#define VP_IDLE_TIMEOUT 200 +#define VP_TRANXDONE_TIMEOUT 300 + + +/** + * struct omap_vp_common_data - register data common to all VDDs + * @vpconfig_errorgain_mask: ERRORGAIN bitmask in the PRM_VP*_CONFIG reg + * @vpconfig_initvoltage_mask: INITVOLTAGE bitmask in the PRM_VP*_CONFIG reg + * @vpconfig_timeouten_mask: TIMEOUT bitmask in the PRM_VP*_CONFIG reg + * @vpconfig_initvdd: INITVDD bitmask in the PRM_VP*_CONFIG reg + * @vpconfig_forceupdate: FORCEUPDATE bitmask in the PRM_VP*_CONFIG reg + * @vpconfig_vpenable: VPENABLE bitmask in the PRM_VP*_CONFIG reg + * @vpconfig_erroroffset_shift: ERROROFFSET field shift in PRM_VP*_CONFIG reg + * @vpconfig_errorgain_shift: ERRORGAIN field shift in PRM_VP*_CONFIG reg + * @vpconfig_initvoltage_shift: INITVOLTAGE field shift in PRM_VP*_CONFIG reg + * @vpconfig_stepmin_shift: VSTEPMIN field shift in the PRM_VP*_VSTEPMIN reg + * @vpconfig_smpswaittimemin_shift: SMPSWAITTIMEMIN field shift in PRM_VP*_VSTEPMIN reg + * @vpconfig_stepmax_shift: VSTEPMAX field shift in the PRM_VP*_VSTEPMAX reg + * @vpconfig_smpswaittimemax_shift: SMPSWAITTIMEMAX field shift in PRM_VP*_VSTEPMAX reg + * @vpconfig_vlimitto_vddmin_shift: VDDMIN field shift in PRM_VP*_VLIMITTO reg + * @vpconfig_vlimitto_vddmax_shift: VDDMAX field shift in PRM_VP*_VLIMITTO reg + * @vpconfig_vlimitto_timeout_shift: TIMEOUT field shift in PRM_VP*_VLIMITTO reg + * + * XXX It it not necessary to have both a mask and a shift for the same + * bitfield - remove one + * XXX Many of these fields are wrongly named -- e.g., vpconfig_smps* -- fix! + */ +struct omap_vp_common_data { + u32 vpconfig_errorgain_mask; + u32 vpconfig_initvoltage_mask; + u32 vpconfig_timeouten; + u32 vpconfig_initvdd; + u32 vpconfig_forceupdate; + u32 vpconfig_vpenable; + u8 vpconfig_erroroffset_shift; + u8 vpconfig_errorgain_shift; + u8 vpconfig_initvoltage_shift; + u8 vstepmin_stepmin_shift; + u8 vstepmin_smpswaittimemin_shift; + u8 vstepmax_stepmax_shift; + u8 vstepmax_smpswaittimemax_shift; + u8 vlimitto_vddmin_shift; + u8 vlimitto_vddmax_shift; + u8 vlimitto_timeout_shift; +}; + +/** + * struct omap_vp_prm_irqst_data - PRM_IRQSTATUS_MPU.VP_TRANXDONE_ST data + * @prm_irqst_reg: reg offset for PRM_IRQSTATUS_MPU from top of PRM + * @tranxdone_status: VP_TRANXDONE_ST bitmask in PRM_IRQSTATUS_MPU reg + * + * XXX prm_irqst_reg does not belong here + * XXX Note that on OMAP3, VP_TRANXDONE interrupt may not work due to a + * hardware bug + * XXX This structure is probably not needed + */ +struct omap_vp_prm_irqst_data { + u8 prm_irqst_reg; + u32 tranxdone_status; +}; + +/** + * struct omap_vp_instance_data - VP register offsets (per-VDD) + * @vp_common: pointer to struct omap_vp_common_data * for this SoC + * @prm_irqst_data: pointer to struct omap_vp_prm_irqst_data for this VDD + * @vpconfig: PRM_VP*_CONFIG reg offset from PRM start + * @vstepmin: PRM_VP*_VSTEPMIN reg offset from PRM start + * @vlimitto: PRM_VP*_VLIMITTO reg offset from PRM start + * @vstatus: PRM_VP*_VSTATUS reg offset from PRM start + * @voltage: PRM_VP*_VOLTAGE reg offset from PRM start + * + * XXX vp_common is probably not needed since it is per-SoC + */ +struct omap_vp_instance_data { + const struct omap_vp_common_data *vp_common; + const struct omap_vp_prm_irqst_data *prm_irqst_data; + u8 vpconfig; + u8 vstepmin; + u8 vstepmax; + u8 vlimitto; + u8 vstatus; + u8 voltage; +}; + +/** + * struct omap_vp_runtime_data - VP data populated at runtime by code + * @vpconfig_erroroffset: value of ERROROFFSET bitfield in PRM_VP*_CONFIG + * @vpconfig_errorgain: value of ERRORGAIN bitfield in PRM_VP*_CONFIG + * @vstepmin_smpswaittimemin: value of SMPSWAITTIMEMIN bitfield in PRM_VP*_VSTEPMIN + * @vstepmax_smpswaittimemax: value of SMPSWAITTIMEMAX bitfield in PRM_VP*_VSTEPMAX + * @vlimitto_timeout: value of TIMEOUT bitfield in PRM_VP*_VLIMITTO + * @vstepmin_stepmin: value of VSTEPMIN bitfield in PRM_VP*_VSTEPMIN + * @vstepmax_stepmax: value of VSTEPMAX bitfield in PRM_VP*_VSTEPMAX + * @vlimitto_vddmin: value of VDDMIN bitfield in PRM_VP*_VLIMITTO + * @vlimitto_vddmax: value of VDDMAX bitfield in PRM_VP*_VLIMITTO + * + * XXX Is this structure really needed? Why not just program the + * device directly? They are in PRM space, therefore in the WKUP + * powerdomain, so register contents should not be lost in off-mode. + * XXX Some of these fields are incorrectly named, e.g., vstep* + */ +struct omap_vp_runtime_data { + u32 vpconfig_erroroffset; + u16 vpconfig_errorgain; + u16 vstepmin_smpswaittimemin; + u16 vstepmax_smpswaittimemax; + u16 vlimitto_timeout; + u8 vstepmin_stepmin; + u8 vstepmax_stepmax; + u8 vlimitto_vddmin; + u8 vlimitto_vddmax; +}; + +extern struct omap_vp_instance_data omap3_vp1_data; +extern struct omap_vp_instance_data omap3_vp2_data; + +extern struct omap_vp_instance_data omap4_vp_mpu_data; +extern struct omap_vp_instance_data omap4_vp_iva_data; +extern struct omap_vp_instance_data omap4_vp_core_data; + +#endif diff --git a/arch/arm/mach-omap2/vp3xxx_data.c b/arch/arm/mach-omap2/vp3xxx_data.c new file mode 100644 index 00000000000..645217094e5 --- /dev/null +++ b/arch/arm/mach-omap2/vp3xxx_data.c @@ -0,0 +1,82 @@ +/* + * OMAP3 Voltage Processor (VP) data + * + * Copyright (C) 2007, 2010 Texas Instruments, Inc. + * Rajendra Nayak <rnayak@ti.com> + * Lesly A M <x0080970@ti.com> + * Thara Gopinath <thara@ti.com> + * + * Copyright (C) 2008, 2011 Nokia Corporation + * Kalle Jokiniemi + * Paul Walmsley + * + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License version 2 as + * published by the Free Software Foundation. + */ + +#include <linux/io.h> +#include <linux/err.h> +#include <linux/init.h> + +#include <plat/common.h> + +#include "prm-regbits-34xx.h" +#include "voltage.h" + +#include "vp.h" + +/* + * VP data common to 34xx/36xx chips + * XXX This stuff presumably belongs in the vp3xxx.c or vp.c file. + */ +static const struct omap_vp_common_data omap3_vp_common = { + .vpconfig_erroroffset_shift = OMAP3430_ERROROFFSET_SHIFT, + .vpconfig_errorgain_mask = OMAP3430_ERRORGAIN_MASK, + .vpconfig_errorgain_shift = OMAP3430_ERRORGAIN_SHIFT, + .vpconfig_initvoltage_shift = OMAP3430_INITVOLTAGE_SHIFT, + .vpconfig_initvoltage_mask = OMAP3430_INITVOLTAGE_MASK, + .vpconfig_timeouten = OMAP3430_TIMEOUTEN_MASK, + .vpconfig_initvdd = OMAP3430_INITVDD_MASK, + .vpconfig_forceupdate = OMAP3430_FORCEUPDATE_MASK, + .vpconfig_vpenable = OMAP3430_VPENABLE_MASK, + .vstepmin_smpswaittimemin_shift = OMAP3430_SMPSWAITTIMEMIN_SHIFT, + .vstepmax_smpswaittimemax_shift = OMAP3430_SMPSWAITTIMEMAX_SHIFT, + .vstepmin_stepmin_shift = OMAP3430_VSTEPMIN_SHIFT, + .vstepmax_stepmax_shift = OMAP3430_VSTEPMAX_SHIFT, + .vlimitto_vddmin_shift = OMAP3430_VDDMIN_SHIFT, + .vlimitto_vddmax_shift = OMAP3430_VDDMAX_SHIFT, + .vlimitto_timeout_shift = OMAP3430_TIMEOUT_SHIFT, +}; + +static const struct omap_vp_prm_irqst_data omap3_vp1_prm_irqst_data = { + .prm_irqst_reg = OMAP3_PRM_IRQSTATUS_MPU_OFFSET, + .tranxdone_status = OMAP3430_VP1_TRANXDONE_ST_MASK, +}; + +struct omap_vp_instance_data omap3_vp1_data = { + .vp_common = &omap3_vp_common, + .vpconfig = OMAP3_PRM_VP1_CONFIG_OFFSET, + .vstepmin = OMAP3_PRM_VP1_VSTEPMIN_OFFSET, + .vstepmax = OMAP3_PRM_VP1_VSTEPMAX_OFFSET, + .vlimitto = OMAP3_PRM_VP1_VLIMITTO_OFFSET, + .vstatus = OMAP3_PRM_VP1_STATUS_OFFSET, + .voltage = OMAP3_PRM_VP1_VOLTAGE_OFFSET, + .prm_irqst_data = &omap3_vp1_prm_irqst_data, +}; + +static const struct omap_vp_prm_irqst_data omap3_vp2_prm_irqst_data = { + .prm_irqst_reg = OMAP3_PRM_IRQSTATUS_MPU_OFFSET, + .tranxdone_status = OMAP3430_VP2_TRANXDONE_ST_MASK, +}; + +struct omap_vp_instance_data omap3_vp2_data = { + .vp_common = &omap3_vp_common, + .vpconfig = OMAP3_PRM_VP2_CONFIG_OFFSET, + .vstepmin = OMAP3_PRM_VP2_VSTEPMIN_OFFSET, + .vstepmax = OMAP3_PRM_VP2_VSTEPMAX_OFFSET, + .vlimitto = OMAP3_PRM_VP2_VLIMITTO_OFFSET, + .vstatus = OMAP3_PRM_VP2_STATUS_OFFSET, + .voltage = OMAP3_PRM_VP2_VOLTAGE_OFFSET, + .prm_irqst_data = &omap3_vp2_prm_irqst_data, +}; diff --git a/arch/arm/mach-omap2/vp44xx_data.c b/arch/arm/mach-omap2/vp44xx_data.c new file mode 100644 index 00000000000..65d1ad63800 --- /dev/null +++ b/arch/arm/mach-omap2/vp44xx_data.c @@ -0,0 +1,100 @@ +/* + * OMAP3 Voltage Processor (VP) data + * + * Copyright (C) 2007, 2010 Texas Instruments, Inc. + * Rajendra Nayak <rnayak@ti.com> + * Lesly A M <x0080970@ti.com> + * Thara Gopinath <thara@ti.com> + * + * Copyright (C) 2008, 2011 Nokia Corporation + * Kalle Jokiniemi + * Paul Walmsley + * + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License version 2 as + * published by the Free Software Foundation. + */ + +#include <linux/io.h> +#include <linux/err.h> +#include <linux/init.h> + +#include <plat/common.h> + +#include "prm44xx.h" +#include "prm-regbits-44xx.h" +#include "voltage.h" + +#include "vp.h" + +/* + * VP data common to 44xx chips + * XXX This stuff presumably belongs in the vp44xx.c or vp.c file. + */ +static const struct omap_vp_common_data omap4_vp_common = { + .vpconfig_erroroffset_shift = OMAP4430_ERROROFFSET_SHIFT, + .vpconfig_errorgain_mask = OMAP4430_ERRORGAIN_MASK, + .vpconfig_errorgain_shift = OMAP4430_ERRORGAIN_SHIFT, + .vpconfig_initvoltage_shift = OMAP4430_INITVOLTAGE_SHIFT, + .vpconfig_initvoltage_mask = OMAP4430_INITVOLTAGE_MASK, + .vpconfig_timeouten = OMAP4430_TIMEOUTEN_MASK, + .vpconfig_initvdd = OMAP4430_INITVDD_MASK, + .vpconfig_forceupdate = OMAP4430_FORCEUPDATE_MASK, + .vpconfig_vpenable = OMAP4430_VPENABLE_MASK, + .vstepmin_smpswaittimemin_shift = OMAP4430_SMPSWAITTIMEMIN_SHIFT, + .vstepmax_smpswaittimemax_shift = OMAP4430_SMPSWAITTIMEMAX_SHIFT, + .vstepmin_stepmin_shift = OMAP4430_VSTEPMIN_SHIFT, + .vstepmax_stepmax_shift = OMAP4430_VSTEPMAX_SHIFT, + .vlimitto_vddmin_shift = OMAP4430_VDDMIN_SHIFT, + .vlimitto_vddmax_shift = OMAP4430_VDDMAX_SHIFT, + .vlimitto_timeout_shift = OMAP4430_TIMEOUT_SHIFT, +}; + +static const struct omap_vp_prm_irqst_data omap4_vp_mpu_prm_irqst_data = { + .prm_irqst_reg = OMAP4_PRM_IRQSTATUS_MPU_2_OFFSET, + .tranxdone_status = OMAP4430_VP_MPU_TRANXDONE_ST_MASK, +}; + +struct omap_vp_instance_data omap4_vp_mpu_data = { + .vp_common = &omap4_vp_common, + .vpconfig = OMAP4_PRM_VP_MPU_CONFIG_OFFSET, + .vstepmin = OMAP4_PRM_VP_MPU_VSTEPMIN_OFFSET, + .vstepmax = OMAP4_PRM_VP_MPU_VSTEPMAX_OFFSET, + .vlimitto = OMAP4_PRM_VP_MPU_VLIMITTO_OFFSET, + .vstatus = OMAP4_PRM_VP_MPU_STATUS_OFFSET, + .voltage = OMAP4_PRM_VP_MPU_VOLTAGE_OFFSET, + .prm_irqst_data = &omap4_vp_mpu_prm_irqst_data, +}; + +static const struct omap_vp_prm_irqst_data omap4_vp_iva_prm_irqst_data = { + .prm_irqst_reg = OMAP4_PRM_IRQSTATUS_MPU_OFFSET, + .tranxdone_status = OMAP4430_VP_IVA_TRANXDONE_ST_MASK, +}; + +struct omap_vp_instance_data omap4_vp_iva_data = { + .vp_common = &omap4_vp_common, + .vpconfig = OMAP4_PRM_VP_IVA_CONFIG_OFFSET, + .vstepmin = OMAP4_PRM_VP_IVA_VSTEPMIN_OFFSET, + .vstepmax = OMAP4_PRM_VP_IVA_VSTEPMAX_OFFSET, + .vlimitto = OMAP4_PRM_VP_IVA_VLIMITTO_OFFSET, + .vstatus = OMAP4_PRM_VP_IVA_STATUS_OFFSET, + .voltage = OMAP4_PRM_VP_IVA_VOLTAGE_OFFSET, + .prm_irqst_data = &omap4_vp_iva_prm_irqst_data, +}; + +static const struct omap_vp_prm_irqst_data omap4_vp_core_prm_irqst_data = { + .prm_irqst_reg = OMAP4_PRM_IRQSTATUS_MPU_OFFSET, + .tranxdone_status = OMAP4430_VP_CORE_TRANXDONE_ST_MASK, +}; + +struct omap_vp_instance_data omap4_vp_core_data = { + .vp_common = &omap4_vp_common, + .vpconfig = OMAP4_PRM_VP_CORE_CONFIG_OFFSET, + .vstepmin = OMAP4_PRM_VP_CORE_VSTEPMIN_OFFSET, + .vstepmax = OMAP4_PRM_VP_CORE_VSTEPMAX_OFFSET, + .vlimitto = OMAP4_PRM_VP_CORE_VLIMITTO_OFFSET, + .vstatus = OMAP4_PRM_VP_CORE_STATUS_OFFSET, + .voltage = OMAP4_PRM_VP_CORE_VOLTAGE_OFFSET, + .prm_irqst_data = &omap4_vp_core_prm_irqst_data, +}; + diff --git a/arch/arm/plat-omap/clock.c b/arch/arm/plat-omap/clock.c index fc62fb5fc20..c9122dd6ee8 100644 --- a/arch/arm/plat-omap/clock.c +++ b/arch/arm/plat-omap/clock.c @@ -37,14 +37,16 @@ static struct clk_functions *arch_clock; int clk_enable(struct clk *clk) { unsigned long flags; - int ret = 0; + int ret; if (clk == NULL || IS_ERR(clk)) return -EINVAL; + if (!arch_clock || !arch_clock->clk_enable) + return -EINVAL; + spin_lock_irqsave(&clockfw_lock, flags); - if (arch_clock->clk_enable) - ret = arch_clock->clk_enable(clk); + ret = arch_clock->clk_enable(clk); spin_unlock_irqrestore(&clockfw_lock, flags); return ret; @@ -58,6 +60,9 @@ void clk_disable(struct clk *clk) if (clk == NULL || IS_ERR(clk)) return; + if (!arch_clock || !arch_clock->clk_disable) + return; + spin_lock_irqsave(&clockfw_lock, flags); if (clk->usecount == 0) { pr_err("Trying disable clock %s with 0 usecount\n", @@ -66,8 +71,7 @@ void clk_disable(struct clk *clk) goto out; } - if (arch_clock->clk_disable) - arch_clock->clk_disable(clk); + arch_clock->clk_disable(clk); out: spin_unlock_irqrestore(&clockfw_lock, flags); @@ -77,7 +81,7 @@ EXPORT_SYMBOL(clk_disable); unsigned long clk_get_rate(struct clk *clk) { unsigned long flags; - unsigned long ret = 0; + unsigned long ret; if (clk == NULL || IS_ERR(clk)) return 0; @@ -97,14 +101,16 @@ EXPORT_SYMBOL(clk_get_rate); long clk_round_rate(struct clk *clk, unsigned long rate) { unsigned long flags; - long ret = 0; + long ret; if (clk == NULL || IS_ERR(clk)) - return ret; + return 0; + + if (!arch_clock || !arch_clock->clk_round_rate) + return 0; spin_lock_irqsave(&clockfw_lock, flags); - if (arch_clock->clk_round_rate) - ret = arch_clock->clk_round_rate(clk, rate); + ret = arch_clock->clk_round_rate(clk, rate); spin_unlock_irqrestore(&clockfw_lock, flags); return ret; @@ -119,14 +125,13 @@ int clk_set_rate(struct clk *clk, unsigned long rate) if (clk == NULL || IS_ERR(clk)) return ret; + if (!arch_clock || !arch_clock->clk_set_rate) + return ret; + spin_lock_irqsave(&clockfw_lock, flags); - if (arch_clock->clk_set_rate) - ret = arch_clock->clk_set_rate(clk, rate); - if (ret == 0) { - if (clk->recalc) - clk->rate = clk->recalc(clk); + ret = arch_clock->clk_set_rate(clk, rate); + if (ret == 0) propagate_rate(clk); - } spin_unlock_irqrestore(&clockfw_lock, flags); return ret; @@ -141,15 +146,14 @@ int clk_set_parent(struct clk *clk, struct clk *parent) if (clk == NULL || IS_ERR(clk) || parent == NULL || IS_ERR(parent)) return ret; + if (!arch_clock || !arch_clock->clk_set_parent) + return ret; + spin_lock_irqsave(&clockfw_lock, flags); if (clk->usecount == 0) { - if (arch_clock->clk_set_parent) - ret = arch_clock->clk_set_parent(clk, parent); - if (ret == 0) { - if (clk->recalc) - clk->rate = clk->recalc(clk); + ret = arch_clock->clk_set_parent(clk, parent); + if (ret == 0) propagate_rate(clk); - } } else ret = -EBUSY; spin_unlock_irqrestore(&clockfw_lock, flags); @@ -335,6 +339,38 @@ struct clk *omap_clk_get_by_name(const char *name) return ret; } +int omap_clk_enable_autoidle_all(void) +{ + struct clk *c; + unsigned long flags; + + spin_lock_irqsave(&clockfw_lock, flags); + + list_for_each_entry(c, &clocks, node) + if (c->ops->allow_idle) + c->ops->allow_idle(c); + + spin_unlock_irqrestore(&clockfw_lock, flags); + + return 0; +} + +int omap_clk_disable_autoidle_all(void) +{ + struct clk *c; + unsigned long flags; + + spin_lock_irqsave(&clockfw_lock, flags); + + list_for_each_entry(c, &clocks, node) + if (c->ops->deny_idle) + c->ops->deny_idle(c); + + spin_unlock_irqrestore(&clockfw_lock, flags); + + return 0; +} + /* * Low level helpers */ @@ -367,9 +403,11 @@ void clk_init_cpufreq_table(struct cpufreq_frequency_table **table) { unsigned long flags; + if (!arch_clock || !arch_clock->clk_init_cpufreq_table) + return; + spin_lock_irqsave(&clockfw_lock, flags); - if (arch_clock->clk_init_cpufreq_table) - arch_clock->clk_init_cpufreq_table(table); + arch_clock->clk_init_cpufreq_table(table); spin_unlock_irqrestore(&clockfw_lock, flags); } @@ -377,9 +415,11 @@ void clk_exit_cpufreq_table(struct cpufreq_frequency_table **table) { unsigned long flags; + if (!arch_clock || !arch_clock->clk_exit_cpufreq_table) + return; + spin_lock_irqsave(&clockfw_lock, flags); - if (arch_clock->clk_exit_cpufreq_table) - arch_clock->clk_exit_cpufreq_table(table); + arch_clock->clk_exit_cpufreq_table(table); spin_unlock_irqrestore(&clockfw_lock, flags); } #endif @@ -397,6 +437,9 @@ static int __init clk_disable_unused(void) struct clk *ck; unsigned long flags; + if (!arch_clock || !arch_clock->clk_disable_unused) + return 0; + pr_info("clock: disabling unused clocks to save power\n"); list_for_each_entry(ck, &clocks, node) { if (ck->ops == &clkops_null) @@ -406,14 +449,14 @@ static int __init clk_disable_unused(void) continue; spin_lock_irqsave(&clockfw_lock, flags); - if (arch_clock->clk_disable_unused) - arch_clock->clk_disable_unused(ck); + arch_clock->clk_disable_unused(ck); spin_unlock_irqrestore(&clockfw_lock, flags); } return 0; } late_initcall(clk_disable_unused); +late_initcall(omap_clk_enable_autoidle_all); #endif int __init clk_init(struct clk_functions * custom_clocks) diff --git a/arch/arm/plat-omap/common.c b/arch/arm/plat-omap/common.c index f0473182030..d9f10a31e60 100644 --- a/arch/arm/plat-omap/common.c +++ b/arch/arm/plat-omap/common.c @@ -24,10 +24,11 @@ #define NO_LENGTH_CHECK 0xffffffff -struct omap_board_config_kernel *omap_board_config; +struct omap_board_config_kernel *omap_board_config __initdata; int omap_board_config_size; -static const void *get_config(u16 tag, size_t len, int skip, size_t *len_out) +static const void *__init get_config(u16 tag, size_t len, + int skip, size_t *len_out) { struct omap_board_config_kernel *kinfo = NULL; int i; @@ -49,17 +50,15 @@ static const void *get_config(u16 tag, size_t len, int skip, size_t *len_out) return kinfo->data; } -const void *__omap_get_config(u16 tag, size_t len, int nr) +const void *__init __omap_get_config(u16 tag, size_t len, int nr) { return get_config(tag, len, nr, NULL); } -EXPORT_SYMBOL(__omap_get_config); -const void *omap_get_var_config(u16 tag, size_t *len) +const void *__init omap_get_var_config(u16 tag, size_t *len) { return get_config(tag, NO_LENGTH_CHECK, 0, len); } -EXPORT_SYMBOL(omap_get_var_config); void __init omap_reserve(void) { diff --git a/arch/arm/plat-omap/counter_32k.c b/arch/arm/plat-omap/counter_32k.c index 862dda95d61..f7fed608019 100644 --- a/arch/arm/plat-omap/counter_32k.c +++ b/arch/arm/plat-omap/counter_32k.c @@ -54,7 +54,7 @@ static cycle_t notrace omap16xx_32k_read(struct clocksource *cs) #define omap16xx_32k_read NULL #endif -#ifdef CONFIG_ARCH_OMAP2420 +#ifdef CONFIG_SOC_OMAP2420 static cycle_t notrace omap2420_32k_read(struct clocksource *cs) { return omap_readl(OMAP2420_32KSYNCT_BASE + 0x10) - offset_32k; @@ -63,7 +63,7 @@ static cycle_t notrace omap2420_32k_read(struct clocksource *cs) #define omap2420_32k_read NULL #endif -#ifdef CONFIG_ARCH_OMAP2430 +#ifdef CONFIG_SOC_OMAP2430 static cycle_t notrace omap2430_32k_read(struct clocksource *cs) { return omap_readl(OMAP2430_32KSYNCT_BASE + 0x10) - offset_32k; diff --git a/arch/arm/plat-omap/cpu-omap.c b/arch/arm/plat-omap/cpu-omap.c index 11c54ec8d47..da4f68dbba1 100644 --- a/arch/arm/plat-omap/cpu-omap.c +++ b/arch/arm/plat-omap/cpu-omap.c @@ -101,7 +101,7 @@ static int omap_target(struct cpufreq_policy *policy, return ret; } -static int __init omap_cpu_init(struct cpufreq_policy *policy) +static int __cpuinit omap_cpu_init(struct cpufreq_policy *policy) { int result = 0; diff --git a/arch/arm/plat-omap/devices.c b/arch/arm/plat-omap/devices.c index 10245b837c1..7d9f815cede 100644 --- a/arch/arm/plat-omap/devices.c +++ b/arch/arm/plat-omap/devices.c @@ -35,8 +35,8 @@ static struct platform_device **omap_mcbsp_devices; -void omap_mcbsp_register_board_cfg(struct omap_mcbsp_platform_data *config, - int size) +void omap_mcbsp_register_board_cfg(struct resource *res, int res_count, + struct omap_mcbsp_platform_data *config, int size) { int i; @@ -54,6 +54,8 @@ void omap_mcbsp_register_board_cfg(struct omap_mcbsp_platform_data *config, new_mcbsp = platform_device_alloc("omap-mcbsp", i + 1); if (!new_mcbsp) continue; + platform_device_add_resources(new_mcbsp, &res[i * res_count], + res_count); new_mcbsp->dev.platform_data = &config[i]; ret = platform_device_add(new_mcbsp); if (ret) { @@ -65,8 +67,8 @@ void omap_mcbsp_register_board_cfg(struct omap_mcbsp_platform_data *config, } #else -void omap_mcbsp_register_board_cfg(struct omap_mcbsp_platform_data *config, - int size) +void omap_mcbsp_register_board_cfg(struct resource *res, int res_count, + struct omap_mcbsp_platform_data *config, int size) { } #endif diff --git a/arch/arm/plat-omap/dma.c b/arch/arm/plat-omap/dma.c index 85363084cc1..2ec3b5d9f21 100644 --- a/arch/arm/plat-omap/dma.c +++ b/arch/arm/plat-omap/dma.c @@ -134,7 +134,7 @@ static inline void omap_enable_channel_irq(int lch); #ifdef CONFIG_ARCH_OMAP15XX /* Returns 1 if the DMA module is in OMAP1510-compatible mode, 0 otherwise */ -int omap_dma_in_1510_mode(void) +static int omap_dma_in_1510_mode(void) { return enable_1510_mode; } diff --git a/arch/arm/plat-omap/dmtimer.c b/arch/arm/plat-omap/dmtimer.c index 1d706cf63ca..ee9f6ebba29 100644 --- a/arch/arm/plat-omap/dmtimer.c +++ b/arch/arm/plat-omap/dmtimer.c @@ -342,6 +342,10 @@ static void omap_dm_timer_reset(struct omap_dm_timer *timer) l |= 0x02 << 3; /* Set to smart-idle mode */ l |= 0x2 << 8; /* Set clock activity to perserve f-clock on idle */ + /* Enable autoidle on OMAP2 / OMAP3 */ + if (cpu_is_omap24xx() || cpu_is_omap34xx()) + l |= 0x1 << 0; + /* * Enable wake-up on OMAP2 CPUs. */ diff --git a/arch/arm/plat-omap/i2c.c b/arch/arm/plat-omap/i2c.c index a4f8003de66..3341ca4703e 100644 --- a/arch/arm/plat-omap/i2c.c +++ b/arch/arm/plat-omap/i2c.c @@ -112,6 +112,7 @@ static inline int omap1_i2c_add_bus(int bus_id) } +#ifdef CONFIG_ARCH_OMAP2PLUS /* * XXX This function is a temporary compatibility wrapper - only * needed until the I2C driver can be converted to call @@ -130,7 +131,6 @@ static struct omap_device_pm_latency omap_i2c_latency[] = { }, }; -#ifdef CONFIG_ARCH_OMAP2PLUS static inline int omap2_i2c_add_bus(int bus_id) { int l; diff --git a/arch/arm/plat-omap/include/plat/board.h b/arch/arm/plat-omap/include/plat/board.h index 3cf4fa25ab3..97126dfd288 100644 --- a/arch/arm/plat-omap/include/plat/board.h +++ b/arch/arm/plat-omap/include/plat/board.h @@ -151,14 +151,14 @@ struct omap_board_config_kernel { const void *data; }; -extern const void *__omap_get_config(u16 tag, size_t len, int nr); +extern const void *__init __omap_get_config(u16 tag, size_t len, int nr); #define omap_get_config(tag, type) \ ((const type *) __omap_get_config((tag), sizeof(type), 0)) #define omap_get_nr_config(tag, type, nr) \ ((const type *) __omap_get_config((tag), sizeof(type), (nr))) -extern const void *omap_get_var_config(u16 tag, size_t *len); +extern const void *__init omap_get_var_config(u16 tag, size_t *len); extern struct omap_board_config_kernel *omap_board_config; extern int omap_board_config_size; diff --git a/arch/arm/plat-omap/include/plat/clkdev_omap.h b/arch/arm/plat-omap/include/plat/clkdev_omap.h index 256ab3f1ec8..f1899a3e417 100644 --- a/arch/arm/plat-omap/include/plat/clkdev_omap.h +++ b/arch/arm/plat-omap/include/plat/clkdev_omap.h @@ -38,6 +38,7 @@ struct omap_clk { #define CK_3517 (1 << 9) #define CK_36XX (1 << 10) /* 36xx/37xx-specific clocks */ #define CK_443X (1 << 11) +#define CK_TI816X (1 << 12) #define CK_34XX (CK_3430ES1 | CK_3430ES2PLUS) diff --git a/arch/arm/plat-omap/include/plat/clock.h b/arch/arm/plat-omap/include/plat/clock.h index 8eb0adab19e..006e599c661 100644 --- a/arch/arm/plat-omap/include/plat/clock.h +++ b/arch/arm/plat-omap/include/plat/clock.h @@ -25,6 +25,8 @@ struct clockdomain; * @disable: fn ptr that enables the current clock in hardware * @find_idlest: function returning the IDLEST register for the clock's IP blk * @find_companion: function returning the "companion" clk reg for the clock + * @allow_idle: fn ptr that enables autoidle for the current clock in hardware + * @deny_idle: fn ptr that disables autoidle for the current clock in hardware * * A "companion" clk is an accompanying clock to the one being queried * that must be enabled for the IP module connected to the clock to @@ -42,6 +44,8 @@ struct clkops { u8 *, u8 *); void (*find_companion)(struct clk *, void __iomem **, u8 *); + void (*allow_idle)(struct clk *); + void (*deny_idle)(struct clk *); }; #ifdef CONFIG_ARCH_OMAP2PLUS @@ -53,6 +57,7 @@ struct clkops { #define RATE_IN_3430ES2PLUS (1 << 3) /* 3430 ES >= 2 rates only */ #define RATE_IN_36XX (1 << 4) #define RATE_IN_4430 (1 << 5) +#define RATE_IN_TI816X (1 << 6) #define RATE_IN_24XX (RATE_IN_242X | RATE_IN_243X) #define RATE_IN_34XX (RATE_IN_3430ES1 | RATE_IN_3430ES2PLUS) @@ -104,7 +109,6 @@ struct clksel { * @clk_ref: struct clk pointer to the clock's reference clock input * @control_reg: register containing the DPLL mode bitfield * @enable_mask: mask of the DPLL mode bitfield in @control_reg - * @rate_tolerance: maximum variance allowed from target rate (in Hz) * @last_rounded_rate: cache of the last rate result of omap2_dpll_round_rate() * @last_rounded_m: cache of the last M result of omap2_dpll_round_rate() * @max_multiplier: maximum valid non-bypass multiplier value (actual) @@ -130,12 +134,9 @@ struct clksel { * XXX Some DPLLs have multiple bypass inputs, so it's not technically * correct to only have one @clk_bypass pointer. * - * XXX @rate_tolerance should probably be deprecated - currently there - * don't seem to be any usecases for DPLL rounding that is not exact. - * * XXX The runtime-variable fields (@last_rounded_rate, @last_rounded_m, * @last_rounded_n) should be separated from the runtime-fixed fields - * and placed into a differenct structure, so that the runtime-fixed data + * and placed into a different structure, so that the runtime-fixed data * can be placed into read-only space. */ struct dpll_data { @@ -146,7 +147,6 @@ struct dpll_data { struct clk *clk_ref; void __iomem *control_reg; u32 enable_mask; - unsigned int rate_tolerance; unsigned long last_rounded_rate; u16 last_rounded_m; u16 max_multiplier; @@ -171,12 +171,24 @@ struct dpll_data { #endif -/* struct clk.flags possibilities */ +/* + * struct clk.flags possibilities + * + * XXX document the rest of the clock flags here + * + * CLOCK_CLKOUTX2: (OMAP4 only) DPLL CLKOUT and CLKOUTX2 GATE_CTRL + * bits share the same register. This flag allows the + * omap4_dpllmx*() code to determine which GATE_CTRL bit field + * should be used. This is a temporary solution - a better approach + * would be to associate clock type-specific data with the clock, + * similar to the struct dpll_data approach. + */ #define ENABLE_REG_32BIT (1 << 0) /* Use 32-bit access */ #define CLOCK_IDLE_CONTROL (1 << 1) #define CLOCK_NO_IDLE_PARENT (1 << 2) #define ENABLE_ON_INIT (1 << 3) /* Enable upon framework init */ #define INVERT_ENABLE (1 << 4) /* 0 enables, 1 disables */ +#define CLOCK_CLKOUTX2 (1 << 5) /** * struct clk - OMAP struct clk @@ -292,6 +304,8 @@ extern void clk_init_cpufreq_table(struct cpufreq_frequency_table **table); extern void clk_exit_cpufreq_table(struct cpufreq_frequency_table **table); #endif extern struct clk *omap_clk_get_by_name(const char *name); +extern int omap_clk_enable_autoidle_all(void); +extern int omap_clk_disable_autoidle_all(void); extern const struct clkops clkops_null; diff --git a/arch/arm/plat-omap/include/plat/common.h b/arch/arm/plat-omap/include/plat/common.h index 29b2afb4288..5288130be96 100644 --- a/arch/arm/plat-omap/include/plat/common.h +++ b/arch/arm/plat-omap/include/plat/common.h @@ -56,16 +56,13 @@ struct omap_globals { unsigned long prm; /* Power and Reset Management */ unsigned long cm; /* Clock Management */ unsigned long cm2; - unsigned long uart1_phys; - unsigned long uart2_phys; - unsigned long uart3_phys; - unsigned long uart4_phys; }; void omap2_set_globals_242x(void); void omap2_set_globals_243x(void); void omap2_set_globals_3xxx(void); void omap2_set_globals_443x(void); +void omap2_set_globals_ti816x(void); /* These get called from omap2_set_globals_xxxx(), do not call these */ void omap2_set_globals_tap(struct omap_globals *); diff --git a/arch/arm/plat-omap/include/plat/cpu.h b/arch/arm/plat-omap/include/plat/cpu.h index 3fd8b405572..8198bb6cdb5 100644 --- a/arch/arm/plat-omap/include/plat/cpu.h +++ b/arch/arm/plat-omap/include/plat/cpu.h @@ -5,7 +5,7 @@ * * Copyright (C) 2004, 2008 Nokia Corporation * - * Copyright (C) 2009 Texas Instruments. + * Copyright (C) 2009-11 Texas Instruments. * * Written by Tony Lindgren <tony.lindgren@nokia.com> * @@ -105,6 +105,12 @@ static inline int is_omap ##subclass (void) \ return (GET_OMAP_SUBCLASS == (id)) ? 1 : 0; \ } +#define IS_TI_SUBCLASS(subclass, id) \ +static inline int is_ti ##subclass (void) \ +{ \ + return (GET_OMAP_SUBCLASS == (id)) ? 1 : 0; \ +} + IS_OMAP_CLASS(7xx, 0x07) IS_OMAP_CLASS(15xx, 0x15) IS_OMAP_CLASS(16xx, 0x16) @@ -118,6 +124,8 @@ IS_OMAP_SUBCLASS(343x, 0x343) IS_OMAP_SUBCLASS(363x, 0x363) IS_OMAP_SUBCLASS(443x, 0x443) +IS_TI_SUBCLASS(816x, 0x816) + #define cpu_is_omap7xx() 0 #define cpu_is_omap15xx() 0 #define cpu_is_omap16xx() 0 @@ -126,6 +134,7 @@ IS_OMAP_SUBCLASS(443x, 0x443) #define cpu_is_omap243x() 0 #define cpu_is_omap34xx() 0 #define cpu_is_omap343x() 0 +#define cpu_is_ti816x() 0 #define cpu_is_omap44xx() 0 #define cpu_is_omap443x() 0 @@ -170,11 +179,11 @@ IS_OMAP_SUBCLASS(443x, 0x443) # undef cpu_is_omap24xx # define cpu_is_omap24xx() is_omap24xx() # endif -# if defined (CONFIG_ARCH_OMAP2420) +# if defined (CONFIG_SOC_OMAP2420) # undef cpu_is_omap242x # define cpu_is_omap242x() is_omap242x() # endif -# if defined (CONFIG_ARCH_OMAP2430) +# if defined (CONFIG_SOC_OMAP2430) # undef cpu_is_omap243x # define cpu_is_omap243x() is_omap243x() # endif @@ -189,11 +198,11 @@ IS_OMAP_SUBCLASS(443x, 0x443) # undef cpu_is_omap24xx # define cpu_is_omap24xx() 1 # endif -# if defined(CONFIG_ARCH_OMAP2420) +# if defined(CONFIG_SOC_OMAP2420) # undef cpu_is_omap242x # define cpu_is_omap242x() 1 # endif -# if defined(CONFIG_ARCH_OMAP2430) +# if defined(CONFIG_SOC_OMAP2430) # undef cpu_is_omap243x # define cpu_is_omap243x() 1 # endif @@ -201,7 +210,7 @@ IS_OMAP_SUBCLASS(443x, 0x443) # undef cpu_is_omap34xx # define cpu_is_omap34xx() 1 # endif -# if defined(CONFIG_ARCH_OMAP3430) +# if defined(CONFIG_SOC_OMAP3430) # undef cpu_is_omap343x # define cpu_is_omap343x() 1 # endif @@ -330,6 +339,7 @@ IS_OMAP_TYPE(3517, 0x3517) # undef cpu_is_omap3530 # undef cpu_is_omap3505 # undef cpu_is_omap3517 +# undef cpu_is_ti816x # define cpu_is_omap3430() is_omap3430() # define cpu_is_omap3503() (cpu_is_omap3430() && \ (!omap3_has_iva()) && \ @@ -345,6 +355,7 @@ IS_OMAP_TYPE(3517, 0x3517) # define cpu_is_omap3517() is_omap3517() # undef cpu_is_omap3630 # define cpu_is_omap3630() is_omap363x() +# define cpu_is_ti816x() is_ti816x() #endif # if defined(CONFIG_ARCH_OMAP4) @@ -389,9 +400,15 @@ IS_OMAP_TYPE(3517, 0x3517) #define OMAP3505_REV(v) (OMAP35XX_CLASS | (0x3505 << 16) | (v << 8)) #define OMAP3517_REV(v) (OMAP35XX_CLASS | (0x3517 << 16) | (v << 8)) +#define TI816X_CLASS 0x81600034 +#define TI8168_REV_ES1_0 TI816X_CLASS +#define TI8168_REV_ES1_1 (TI816X_CLASS | (OMAP_REVBITS_01 << 8)) + #define OMAP443X_CLASS 0x44300044 -#define OMAP4430_REV_ES1_0 OMAP443X_CLASS -#define OMAP4430_REV_ES2_0 0x44301044 +#define OMAP4430_REV_ES1_0 (OMAP443X_CLASS | (0x10 << 8)) +#define OMAP4430_REV_ES2_0 (OMAP443X_CLASS | (0x20 << 8)) +#define OMAP4430_REV_ES2_1 (OMAP443X_CLASS | (0x21 << 8)) +#define OMAP4430_REV_ES2_2 (OMAP443X_CLASS | (0x22 << 8)) /* * omap_chip bits @@ -419,11 +436,16 @@ IS_OMAP_TYPE(3517, 0x3517) #define CHIP_IS_OMAP3630ES1_1 (1 << 9) #define CHIP_IS_OMAP3630ES1_2 (1 << 10) #define CHIP_IS_OMAP4430ES2 (1 << 11) +#define CHIP_IS_OMAP4430ES2_1 (1 << 12) +#define CHIP_IS_OMAP4430ES2_2 (1 << 13) +#define CHIP_IS_TI816X (1 << 14) #define CHIP_IS_OMAP24XX (CHIP_IS_OMAP2420 | CHIP_IS_OMAP2430) -#define CHIP_IS_OMAP4430 (CHIP_IS_OMAP4430ES1 | \ - CHIP_IS_OMAP4430ES2) +#define CHIP_IS_OMAP4430 (CHIP_IS_OMAP4430ES1 | \ + CHIP_IS_OMAP4430ES2 | \ + CHIP_IS_OMAP4430ES2_1 | \ + CHIP_IS_OMAP4430ES2_2) /* * "GE" here represents "greater than or equal to" in terms of ES @@ -455,6 +477,7 @@ extern u32 omap3_features; #define OMAP3_HAS_ISP BIT(4) #define OMAP3_HAS_192MHZ_CLK BIT(5) #define OMAP3_HAS_IO_WAKEUP BIT(6) +#define OMAP3_HAS_SDRC BIT(7) #define OMAP3_HAS_FEATURE(feat,flag) \ static inline unsigned int omap3_has_ ##feat(void) \ @@ -469,5 +492,6 @@ OMAP3_HAS_FEATURE(neon, NEON) OMAP3_HAS_FEATURE(isp, ISP) OMAP3_HAS_FEATURE(192mhz_clk, 192MHZ_CLK) OMAP3_HAS_FEATURE(io_wakeup, IO_WAKEUP) +OMAP3_HAS_FEATURE(sdrc, SDRC) #endif diff --git a/arch/arm/plat-omap/include/plat/display.h b/arch/arm/plat-omap/include/plat/display.h index 537f4e449f5..0f140ecedb0 100644 --- a/arch/arm/plat-omap/include/plat/display.h +++ b/arch/arm/plat-omap/include/plat/display.h @@ -23,6 +23,7 @@ #include <linux/list.h> #include <linux/kobject.h> #include <linux/device.h> +#include <linux/platform_device.h> #include <asm/atomic.h> #define DISPC_IRQ_FRAMEDONE (1 << 0) @@ -226,6 +227,16 @@ struct omap_dss_board_info { struct omap_dss_device *default_device; }; +#if defined(CONFIG_OMAP2_DSS_MODULE) || defined(CONFIG_OMAP2_DSS) +/* Init with the board info */ +extern int omap_display_init(struct omap_dss_board_info *board_data); +#else +static inline int omap_display_init(struct omap_dss_board_info *board_data) +{ + return 0; +} +#endif + struct omap_video_timings { /* Unit: pixels */ u16 x_res; diff --git a/arch/arm/plat-omap/include/plat/dmtimer.h b/arch/arm/plat-omap/include/plat/dmtimer.h index dfa3aff9761..d6c70d2f403 100644 --- a/arch/arm/plat-omap/include/plat/dmtimer.h +++ b/arch/arm/plat-omap/include/plat/dmtimer.h @@ -3,6 +3,12 @@ * * OMAP Dual-Mode Timers * + * Copyright (C) 2010 Texas Instruments Incorporated - http://www.ti.com/ + * Tarun Kanti DebBarma <tarun.kanti@ti.com> + * Thara Gopinath <thara@ti.com> + * + * Platform device conversion and hwmod support. + * * Copyright (C) 2005 Nokia Corporation * Author: Lauri Leukkunen <lauri.leukkunen@nokia.com> * PWM and clock framwork support by Timo Teras. @@ -44,6 +50,11 @@ #define OMAP_TIMER_TRIGGER_OVERFLOW 0x01 #define OMAP_TIMER_TRIGGER_OVERFLOW_AND_COMPARE 0x02 +/* + * IP revision identifier so that Highlander IP + * in OMAP4 can be distinguished. + */ +#define OMAP_TIMER_IP_VERSION_1 0x1 struct omap_dm_timer; extern struct omap_dm_timer *gptimer_wakeup; extern struct sys_timer omap_timer; diff --git a/arch/arm/plat-omap/include/plat/fpga.h b/arch/arm/plat-omap/include/plat/fpga.h index ae39bcb3f5b..bd3c6324ae1 100644 --- a/arch/arm/plat-omap/include/plat/fpga.h +++ b/arch/arm/plat-omap/include/plat/fpga.h @@ -30,18 +30,18 @@ extern void omap1510_fpga_init_irq(void); * --------------------------------------------------------------------------- */ /* maps in the FPGA registers and the ETHR registers */ -#define H2P2_DBG_FPGA_BASE IOMEM(0xE8000000) /* VA */ +#define H2P2_DBG_FPGA_BASE 0xE8000000 /* VA */ #define H2P2_DBG_FPGA_SIZE SZ_4K /* SIZE */ #define H2P2_DBG_FPGA_START 0x04000000 /* PA */ #define H2P2_DBG_FPGA_ETHR_START (H2P2_DBG_FPGA_START + 0x300) -#define H2P2_DBG_FPGA_FPGA_REV (H2P2_DBG_FPGA_BASE + 0x10) /* FPGA Revision */ -#define H2P2_DBG_FPGA_BOARD_REV (H2P2_DBG_FPGA_BASE + 0x12) /* Board Revision */ -#define H2P2_DBG_FPGA_GPIO (H2P2_DBG_FPGA_BASE + 0x14) /* GPIO outputs */ -#define H2P2_DBG_FPGA_LEDS (H2P2_DBG_FPGA_BASE + 0x16) /* LEDs outputs */ -#define H2P2_DBG_FPGA_MISC_INPUTS (H2P2_DBG_FPGA_BASE + 0x18) /* Misc inputs */ -#define H2P2_DBG_FPGA_LAN_STATUS (H2P2_DBG_FPGA_BASE + 0x1A) /* LAN Status line */ -#define H2P2_DBG_FPGA_LAN_RESET (H2P2_DBG_FPGA_BASE + 0x1C) /* LAN Reset line */ +#define H2P2_DBG_FPGA_FPGA_REV IOMEM(H2P2_DBG_FPGA_BASE + 0x10) /* FPGA Revision */ +#define H2P2_DBG_FPGA_BOARD_REV IOMEM(H2P2_DBG_FPGA_BASE + 0x12) /* Board Revision */ +#define H2P2_DBG_FPGA_GPIO IOMEM(H2P2_DBG_FPGA_BASE + 0x14) /* GPIO outputs */ +#define H2P2_DBG_FPGA_LEDS IOMEM(H2P2_DBG_FPGA_BASE + 0x16) /* LEDs outputs */ +#define H2P2_DBG_FPGA_MISC_INPUTS IOMEM(H2P2_DBG_FPGA_BASE + 0x18) /* Misc inputs */ +#define H2P2_DBG_FPGA_LAN_STATUS IOMEM(H2P2_DBG_FPGA_BASE + 0x1A) /* LAN Status line */ +#define H2P2_DBG_FPGA_LAN_RESET IOMEM(H2P2_DBG_FPGA_BASE + 0x1C) /* LAN Reset line */ /* NOTE: most boards don't have a static mapping for the FPGA ... */ struct h2p2_dbg_fpga { @@ -81,55 +81,55 @@ struct h2p2_dbg_fpga { * OMAP-1510 FPGA * --------------------------------------------------------------------------- */ -#define OMAP1510_FPGA_BASE IOMEM(0xE8000000) /* VA */ +#define OMAP1510_FPGA_BASE 0xE8000000 /* VA */ #define OMAP1510_FPGA_SIZE SZ_4K #define OMAP1510_FPGA_START 0x08000000 /* PA */ /* Revision */ -#define OMAP1510_FPGA_REV_LOW (OMAP1510_FPGA_BASE + 0x0) -#define OMAP1510_FPGA_REV_HIGH (OMAP1510_FPGA_BASE + 0x1) +#define OMAP1510_FPGA_REV_LOW IOMEM(OMAP1510_FPGA_BASE + 0x0) +#define OMAP1510_FPGA_REV_HIGH IOMEM(OMAP1510_FPGA_BASE + 0x1) -#define OMAP1510_FPGA_LCD_PANEL_CONTROL (OMAP1510_FPGA_BASE + 0x2) -#define OMAP1510_FPGA_LED_DIGIT (OMAP1510_FPGA_BASE + 0x3) -#define INNOVATOR_FPGA_HID_SPI (OMAP1510_FPGA_BASE + 0x4) -#define OMAP1510_FPGA_POWER (OMAP1510_FPGA_BASE + 0x5) +#define OMAP1510_FPGA_LCD_PANEL_CONTROL IOMEM(OMAP1510_FPGA_BASE + 0x2) +#define OMAP1510_FPGA_LED_DIGIT IOMEM(OMAP1510_FPGA_BASE + 0x3) +#define INNOVATOR_FPGA_HID_SPI IOMEM(OMAP1510_FPGA_BASE + 0x4) +#define OMAP1510_FPGA_POWER IOMEM(OMAP1510_FPGA_BASE + 0x5) /* Interrupt status */ -#define OMAP1510_FPGA_ISR_LO (OMAP1510_FPGA_BASE + 0x6) -#define OMAP1510_FPGA_ISR_HI (OMAP1510_FPGA_BASE + 0x7) +#define OMAP1510_FPGA_ISR_LO IOMEM(OMAP1510_FPGA_BASE + 0x6) +#define OMAP1510_FPGA_ISR_HI IOMEM(OMAP1510_FPGA_BASE + 0x7) /* Interrupt mask */ -#define OMAP1510_FPGA_IMR_LO (OMAP1510_FPGA_BASE + 0x8) -#define OMAP1510_FPGA_IMR_HI (OMAP1510_FPGA_BASE + 0x9) +#define OMAP1510_FPGA_IMR_LO IOMEM(OMAP1510_FPGA_BASE + 0x8) +#define OMAP1510_FPGA_IMR_HI IOMEM(OMAP1510_FPGA_BASE + 0x9) /* Reset registers */ -#define OMAP1510_FPGA_HOST_RESET (OMAP1510_FPGA_BASE + 0xa) -#define OMAP1510_FPGA_RST (OMAP1510_FPGA_BASE + 0xb) - -#define OMAP1510_FPGA_AUDIO (OMAP1510_FPGA_BASE + 0xc) -#define OMAP1510_FPGA_DIP (OMAP1510_FPGA_BASE + 0xe) -#define OMAP1510_FPGA_FPGA_IO (OMAP1510_FPGA_BASE + 0xf) -#define OMAP1510_FPGA_UART1 (OMAP1510_FPGA_BASE + 0x14) -#define OMAP1510_FPGA_UART2 (OMAP1510_FPGA_BASE + 0x15) -#define OMAP1510_FPGA_OMAP1510_STATUS (OMAP1510_FPGA_BASE + 0x16) -#define OMAP1510_FPGA_BOARD_REV (OMAP1510_FPGA_BASE + 0x18) -#define OMAP1510P1_PPT_DATA (OMAP1510_FPGA_BASE + 0x100) -#define OMAP1510P1_PPT_STATUS (OMAP1510_FPGA_BASE + 0x101) -#define OMAP1510P1_PPT_CONTROL (OMAP1510_FPGA_BASE + 0x102) - -#define OMAP1510_FPGA_TOUCHSCREEN (OMAP1510_FPGA_BASE + 0x204) - -#define INNOVATOR_FPGA_INFO (OMAP1510_FPGA_BASE + 0x205) -#define INNOVATOR_FPGA_LCD_BRIGHT_LO (OMAP1510_FPGA_BASE + 0x206) -#define INNOVATOR_FPGA_LCD_BRIGHT_HI (OMAP1510_FPGA_BASE + 0x207) -#define INNOVATOR_FPGA_LED_GRN_LO (OMAP1510_FPGA_BASE + 0x208) -#define INNOVATOR_FPGA_LED_GRN_HI (OMAP1510_FPGA_BASE + 0x209) -#define INNOVATOR_FPGA_LED_RED_LO (OMAP1510_FPGA_BASE + 0x20a) -#define INNOVATOR_FPGA_LED_RED_HI (OMAP1510_FPGA_BASE + 0x20b) -#define INNOVATOR_FPGA_CAM_USB_CONTROL (OMAP1510_FPGA_BASE + 0x20c) -#define INNOVATOR_FPGA_EXP_CONTROL (OMAP1510_FPGA_BASE + 0x20d) -#define INNOVATOR_FPGA_ISR2 (OMAP1510_FPGA_BASE + 0x20e) -#define INNOVATOR_FPGA_IMR2 (OMAP1510_FPGA_BASE + 0x210) +#define OMAP1510_FPGA_HOST_RESET IOMEM(OMAP1510_FPGA_BASE + 0xa) +#define OMAP1510_FPGA_RST IOMEM(OMAP1510_FPGA_BASE + 0xb) + +#define OMAP1510_FPGA_AUDIO IOMEM(OMAP1510_FPGA_BASE + 0xc) +#define OMAP1510_FPGA_DIP IOMEM(OMAP1510_FPGA_BASE + 0xe) +#define OMAP1510_FPGA_FPGA_IO IOMEM(OMAP1510_FPGA_BASE + 0xf) +#define OMAP1510_FPGA_UART1 IOMEM(OMAP1510_FPGA_BASE + 0x14) +#define OMAP1510_FPGA_UART2 IOMEM(OMAP1510_FPGA_BASE + 0x15) +#define OMAP1510_FPGA_OMAP1510_STATUS IOMEM(OMAP1510_FPGA_BASE + 0x16) +#define OMAP1510_FPGA_BOARD_REV IOMEM(OMAP1510_FPGA_BASE + 0x18) +#define OMAP1510P1_PPT_DATA IOMEM(OMAP1510_FPGA_BASE + 0x100) +#define OMAP1510P1_PPT_STATUS IOMEM(OMAP1510_FPGA_BASE + 0x101) +#define OMAP1510P1_PPT_CONTROL IOMEM(OMAP1510_FPGA_BASE + 0x102) + +#define OMAP1510_FPGA_TOUCHSCREEN IOMEM(OMAP1510_FPGA_BASE + 0x204) + +#define INNOVATOR_FPGA_INFO IOMEM(OMAP1510_FPGA_BASE + 0x205) +#define INNOVATOR_FPGA_LCD_BRIGHT_LO IOMEM(OMAP1510_FPGA_BASE + 0x206) +#define INNOVATOR_FPGA_LCD_BRIGHT_HI IOMEM(OMAP1510_FPGA_BASE + 0x207) +#define INNOVATOR_FPGA_LED_GRN_LO IOMEM(OMAP1510_FPGA_BASE + 0x208) +#define INNOVATOR_FPGA_LED_GRN_HI IOMEM(OMAP1510_FPGA_BASE + 0x209) +#define INNOVATOR_FPGA_LED_RED_LO IOMEM(OMAP1510_FPGA_BASE + 0x20a) +#define INNOVATOR_FPGA_LED_RED_HI IOMEM(OMAP1510_FPGA_BASE + 0x20b) +#define INNOVATOR_FPGA_CAM_USB_CONTROL IOMEM(OMAP1510_FPGA_BASE + 0x20c) +#define INNOVATOR_FPGA_EXP_CONTROL IOMEM(OMAP1510_FPGA_BASE + 0x20d) +#define INNOVATOR_FPGA_ISR2 IOMEM(OMAP1510_FPGA_BASE + 0x20e) +#define INNOVATOR_FPGA_IMR2 IOMEM(OMAP1510_FPGA_BASE + 0x210) #define OMAP1510_FPGA_ETHR_START (OMAP1510_FPGA_START + 0x300) diff --git a/arch/arm/plat-omap/include/plat/gpmc.h b/arch/arm/plat-omap/include/plat/gpmc.h index 85ded598853..12b31616503 100644 --- a/arch/arm/plat-omap/include/plat/gpmc.h +++ b/arch/arm/plat-omap/include/plat/gpmc.h @@ -41,6 +41,8 @@ #define GPMC_NAND_ADDRESS 0x0000000b #define GPMC_NAND_DATA 0x0000000c +#define GPMC_ENABLE_IRQ 0x0000000d + /* ECC commands */ #define GPMC_ECC_READ 0 /* Reset Hardware ECC for read */ #define GPMC_ECC_WRITE 1 /* Reset Hardware ECC for write */ @@ -78,6 +80,19 @@ #define WR_RD_PIN_MONITORING 0x00600000 #define GPMC_PREFETCH_STATUS_FIFO_CNT(val) ((val >> 24) & 0x7F) #define GPMC_PREFETCH_STATUS_COUNT(val) (val & 0x00003fff) +#define GPMC_IRQ_FIFOEVENTENABLE 0x01 +#define GPMC_IRQ_COUNT_EVENT 0x02 + +#define PREFETCH_FIFOTHRESHOLD_MAX 0x40 +#define PREFETCH_FIFOTHRESHOLD(val) ((val) << 8) + +enum omap_ecc { + /* 1-bit ecc: stored at end of spare area */ + OMAP_ECC_HAMMING_CODE_DEFAULT = 0, /* Default, s/w method */ + OMAP_ECC_HAMMING_CODE_HW, /* gpmc to detect the error */ + /* 1-bit ecc: stored at begining of spare area as romcode */ + OMAP_ECC_HAMMING_CODE_HW_ROMCODE, /* gpmc method & romcode layout */ +}; /* * Note that all values in this struct are in nanoseconds except sync_clk @@ -130,12 +145,11 @@ extern int gpmc_cs_request(int cs, unsigned long size, unsigned long *base); extern void gpmc_cs_free(int cs); extern int gpmc_cs_set_reserved(int cs, int reserved); extern int gpmc_cs_reserved(int cs); -extern int gpmc_prefetch_enable(int cs, int dma_mode, +extern int gpmc_prefetch_enable(int cs, int fifo_th, int dma_mode, unsigned int u32_count, int is_write); extern int gpmc_prefetch_reset(int cs); extern void omap3_gpmc_save_context(void); extern void omap3_gpmc_restore_context(void); -extern void gpmc_init(void); extern int gpmc_read_status(int cmd); extern int gpmc_cs_configure(int cs, int cmd, int wval); extern int gpmc_nand_read(int cs, int cmd); diff --git a/arch/arm/plat-omap/include/plat/hardware.h b/arch/arm/plat-omap/include/plat/hardware.h index d5b26adfb89..e87efe1499b 100644 --- a/arch/arm/plat-omap/include/plat/hardware.h +++ b/arch/arm/plat-omap/include/plat/hardware.h @@ -286,5 +286,6 @@ #include <plat/omap24xx.h> #include <plat/omap34xx.h> #include <plat/omap44xx.h> +#include <plat/ti816x.h> #endif /* __ASM_ARCH_OMAP_HARDWARE_H */ diff --git a/arch/arm/plat-omap/include/plat/io.h b/arch/arm/plat-omap/include/plat/io.h index ef4106c1318..d72ec85c97e 100644 --- a/arch/arm/plat-omap/include/plat/io.h +++ b/arch/arm/plat-omap/include/plat/io.h @@ -259,7 +259,7 @@ struct omap_sdrc_params; extern void omap1_map_common_io(void); extern void omap1_init_common_hw(void); -#ifdef CONFIG_ARCH_OMAP2420 +#ifdef CONFIG_SOC_OMAP2420 extern void omap242x_map_common_io(void); #else static inline void omap242x_map_common_io(void) @@ -267,7 +267,7 @@ static inline void omap242x_map_common_io(void) } #endif -#ifdef CONFIG_ARCH_OMAP2430 +#ifdef CONFIG_SOC_OMAP2430 extern void omap243x_map_common_io(void); #else static inline void omap243x_map_common_io(void) @@ -283,6 +283,14 @@ static inline void omap34xx_map_common_io(void) } #endif +#ifdef CONFIG_SOC_OMAPTI816X +extern void omapti816x_map_common_io(void); +#else +static inline void omapti816x_map_common_io(void) +{ +} +#endif + #ifdef CONFIG_ARCH_OMAP4 extern void omap44xx_map_common_io(void); #else diff --git a/arch/arm/plat-omap/include/plat/iommu.h b/arch/arm/plat-omap/include/plat/iommu.h index 69230d68553..174f1b9c8c0 100644 --- a/arch/arm/plat-omap/include/plat/iommu.h +++ b/arch/arm/plat-omap/include/plat/iommu.h @@ -31,6 +31,7 @@ struct iommu { struct clk *clk; void __iomem *regbase; struct device *dev; + void *isr_priv; unsigned int refcount; struct mutex iommu_lock; /* global for this whole object */ @@ -47,7 +48,7 @@ struct iommu { struct list_head mmap; struct mutex mmap_lock; /* protect mmap */ - int (*isr)(struct iommu *obj); + int (*isr)(struct iommu *obj, u32 da, u32 iommu_errs, void *priv); void *ctx; /* iommu context: registres saved area */ u32 da_start; @@ -109,6 +110,13 @@ struct iommu_platform_data { u32 da_end; }; +/* IOMMU errors */ +#define OMAP_IOMMU_ERR_TLB_MISS (1 << 0) +#define OMAP_IOMMU_ERR_TRANS_FAULT (1 << 1) +#define OMAP_IOMMU_ERR_EMU_MISS (1 << 2) +#define OMAP_IOMMU_ERR_TBLWALK_FAULT (1 << 3) +#define OMAP_IOMMU_ERR_MULTIHIT_FAULT (1 << 4) + #if defined(CONFIG_ARCH_OMAP1) #error "iommu for this processor not implemented yet" #else @@ -154,11 +162,17 @@ extern void flush_iotlb_range(struct iommu *obj, u32 start, u32 end); extern void flush_iotlb_all(struct iommu *obj); extern int iopgtable_store_entry(struct iommu *obj, struct iotlb_entry *e); +extern void iopgtable_lookup_entry(struct iommu *obj, u32 da, u32 **ppgd, + u32 **ppte); extern size_t iopgtable_clear_entry(struct iommu *obj, u32 iova); extern int iommu_set_da_range(struct iommu *obj, u32 start, u32 end); extern struct iommu *iommu_get(const char *name); extern void iommu_put(struct iommu *obj); +extern int iommu_set_isr(const char *name, + int (*isr)(struct iommu *obj, u32 da, u32 iommu_errs, + void *priv), + void *isr_priv); extern void iommu_save_ctx(struct iommu *obj); extern void iommu_restore_ctx(struct iommu *obj); diff --git a/arch/arm/plat-omap/include/plat/iovmm.h b/arch/arm/plat-omap/include/plat/iovmm.h index bdc7ce5d7a4..32a2f6c4d39 100644 --- a/arch/arm/plat-omap/include/plat/iovmm.h +++ b/arch/arm/plat-omap/include/plat/iovmm.h @@ -71,8 +71,6 @@ struct iovm_struct { #define IOVMF_LINEAR_MASK (3 << (2 + IOVMF_SW_SHIFT)) #define IOVMF_DA_FIXED (1 << (4 + IOVMF_SW_SHIFT)) -#define IOVMF_DA_ANON (2 << (4 + IOVMF_SW_SHIFT)) -#define IOVMF_DA_MASK (3 << (4 + IOVMF_SW_SHIFT)) extern struct iovm_struct *find_iovm_area(struct iommu *obj, u32 da); diff --git a/arch/arm/plat-omap/include/plat/irqs.h b/arch/arm/plat-omap/include/plat/irqs.h index 2910de921c5..d7792837046 100644 --- a/arch/arm/plat-omap/include/plat/irqs.h +++ b/arch/arm/plat-omap/include/plat/irqs.h @@ -315,9 +315,12 @@ #define INT_34XX_SSM_ABORT_IRQ 6 #define INT_34XX_SYS_NIRQ 7 #define INT_34XX_D2D_FW_IRQ 8 +#define INT_34XX_L3_DBG_IRQ 9 +#define INT_34XX_L3_APP_IRQ 10 #define INT_34XX_PRCM_MPU_IRQ 11 #define INT_34XX_MCBSP1_IRQ 16 #define INT_34XX_MCBSP2_IRQ 17 +#define INT_34XX_GPMC_IRQ 20 #define INT_34XX_MCBSP3_IRQ 22 #define INT_34XX_MCBSP4_IRQ 23 #define INT_34XX_CAM_IRQ 24 @@ -411,7 +414,13 @@ #define TWL_IRQ_END TWL6030_IRQ_END #endif -#define NR_IRQS TWL_IRQ_END +/* GPMC related */ +#define OMAP_GPMC_IRQ_BASE (TWL_IRQ_END) +#define OMAP_GPMC_NR_IRQS 7 +#define OMAP_GPMC_IRQ_END (OMAP_GPMC_IRQ_BASE + OMAP_GPMC_NR_IRQS) + + +#define NR_IRQS OMAP_GPMC_IRQ_END #define OMAP_IRQ_BIT(irq) (1 << ((irq) % 32)) diff --git a/arch/arm/plat-omap/include/plat/l3_2xxx.h b/arch/arm/plat-omap/include/plat/l3_2xxx.h new file mode 100644 index 00000000000..b8b5641379b --- /dev/null +++ b/arch/arm/plat-omap/include/plat/l3_2xxx.h @@ -0,0 +1,20 @@ +/* + * arch/arm/plat-omap/include/plat/l3_2xxx.h - L3 firewall definitions + * + * Copyright (C) 2010 Texas Instruments Incorporated - http://www.ti.com/ + * Sumit Semwal + * + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2 of the License, or + * (at your option) any later version. + * + */ +#ifndef __ARCH_ARM_PLAT_OMAP_INCLUDE_PLAT_L3_2XXX_H +#define __ARCH_ARM_PLAT_OMAP_INCLUDE_PLAT_L3_2XXX_H + +/* L3 CONNIDs */ +/* Display Sub system (DSS) */ +#define OMAP2_L3_CORE_FW_CONNID_DSS 8 + +#endif diff --git a/arch/arm/plat-omap/include/plat/l3_3xxx.h b/arch/arm/plat-omap/include/plat/l3_3xxx.h new file mode 100644 index 00000000000..cde1938c5f8 --- /dev/null +++ b/arch/arm/plat-omap/include/plat/l3_3xxx.h @@ -0,0 +1,20 @@ +/* + * arch/arm/plat-omap/include/plat/l3_3xxx.h - L3 firewall definitions + * + * Copyright (C) 2010 Texas Instruments Incorporated - http://www.ti.com/ + * Sumit Semwal + * + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2 of the License, or + * (at your option) any later version. + * + */ +#ifndef __ARCH_ARM_PLAT_OMAP_INCLUDE_PLAT_L3_3XXX_H +#define __ARCH_ARM_PLAT_OMAP_INCLUDE_PLAT_L3_3XXX_H + +/* L3 Initiator IDs */ +/* Display Sub system (DSS) */ +#define OMAP3_L3_CORE_FW_INIT_ID_DSS 29 + +#endif diff --git a/arch/arm/plat-omap/include/plat/l4_2xxx.h b/arch/arm/plat-omap/include/plat/l4_2xxx.h new file mode 100644 index 00000000000..3f39cf8a35c --- /dev/null +++ b/arch/arm/plat-omap/include/plat/l4_2xxx.h @@ -0,0 +1,24 @@ +/* + * arch/arm/plat-omap/include/plat/l4_2xxx.h - L4 firewall definitions + * + * Copyright (C) 2010 Texas Instruments Incorporated - http://www.ti.com/ + * Sumit Semwal + * + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2 of the License, or + * (at your option) any later version. + * + */ +#ifndef __ARCH_ARM_PLAT_OMAP_INCLUDE_PLAT_L4_2XXX_H +#define __ARCH_ARM_PLAT_OMAP_INCLUDE_PLAT_L4_2XXX_H + +/* L4 CORE */ +/* Display Sub system (DSS) */ +#define OMAP2420_L4_CORE_FW_DSS_CORE_REGION 28 +#define OMAP2420_L4_CORE_FW_DSS_DISPC_REGION 29 +#define OMAP2420_L4_CORE_FW_DSS_RFBI_REGION 30 +#define OMAP2420_L4_CORE_FW_DSS_VENC_REGION 31 +#define OMAP2420_L4_CORE_FW_DSS_TA_REGION 32 + +#endif diff --git a/arch/arm/plat-omap/include/plat/l4_3xxx.h b/arch/arm/plat-omap/include/plat/l4_3xxx.h index 5e194937542..881a858b1ff 100644 --- a/arch/arm/plat-omap/include/plat/l4_3xxx.h +++ b/arch/arm/plat-omap/include/plat/l4_3xxx.h @@ -21,4 +21,14 @@ #define OMAP3_L4_CORE_FW_I2C3_REGION 73 #define OMAP3_L4_CORE_FW_I2C3_TA_REGION 74 +/* Display Sub system (DSS) */ +#define OMAP3_L4_CORE_FW_DSS_PROT_GROUP 2 + +#define OMAP3_L4_CORE_FW_DSS_DSI_REGION 104 +#define OMAP3ES1_L4_CORE_FW_DSS_CORE_REGION 3 +#define OMAP3_L4_CORE_FW_DSS_CORE_REGION 4 +#define OMAP3_L4_CORE_FW_DSS_DISPC_REGION 4 +#define OMAP3_L4_CORE_FW_DSS_RFBI_REGION 5 +#define OMAP3_L4_CORE_FW_DSS_VENC_REGION 6 +#define OMAP3_L4_CORE_FW_DSS_TA_REGION 7 #endif diff --git a/arch/arm/plat-omap/include/plat/mcbsp.h b/arch/arm/plat-omap/include/plat/mcbsp.h index b87d83ccd54..f8f690ab299 100644 --- a/arch/arm/plat-omap/include/plat/mcbsp.h +++ b/arch/arm/plat-omap/include/plat/mcbsp.h @@ -37,6 +37,10 @@ static struct platform_device omap_mcbsp##port_nr = { \ .id = OMAP_MCBSP##port_nr, \ } +#define MCBSP_CONFIG_TYPE2 0x2 +#define MCBSP_CONFIG_TYPE3 0x3 +#define MCBSP_CONFIG_TYPE4 0x4 + #define OMAP7XX_MCBSP1_BASE 0xfffb1000 #define OMAP7XX_MCBSP2_BASE 0xfffb1800 @@ -48,32 +52,14 @@ static struct platform_device omap_mcbsp##port_nr = { \ #define OMAP1610_MCBSP2_BASE 0xfffb1000 #define OMAP1610_MCBSP3_BASE 0xe1017000 -#define OMAP24XX_MCBSP1_BASE 0x48074000 -#define OMAP24XX_MCBSP2_BASE 0x48076000 -#define OMAP2430_MCBSP3_BASE 0x4808c000 -#define OMAP2430_MCBSP4_BASE 0x4808e000 -#define OMAP2430_MCBSP5_BASE 0x48096000 - -#define OMAP34XX_MCBSP1_BASE 0x48074000 -#define OMAP34XX_MCBSP2_BASE 0x49022000 -#define OMAP34XX_MCBSP2_ST_BASE 0x49028000 -#define OMAP34XX_MCBSP3_BASE 0x49024000 -#define OMAP34XX_MCBSP3_ST_BASE 0x4902A000 -#define OMAP34XX_MCBSP3_BASE 0x49024000 -#define OMAP34XX_MCBSP4_BASE 0x49026000 -#define OMAP34XX_MCBSP5_BASE 0x48096000 - -#define OMAP44XX_MCBSP1_BASE 0x49022000 -#define OMAP44XX_MCBSP2_BASE 0x49024000 -#define OMAP44XX_MCBSP3_BASE 0x49026000 -#define OMAP44XX_MCBSP4_BASE 0x48096000 - -#if defined(CONFIG_ARCH_OMAP15XX) || defined(CONFIG_ARCH_OMAP16XX) || defined(CONFIG_ARCH_OMAP730) || defined(CONFIG_ARCH_OMAP850) +#ifdef CONFIG_ARCH_OMAP1 #define OMAP_MCBSP_REG_DRR2 0x00 #define OMAP_MCBSP_REG_DRR1 0x02 #define OMAP_MCBSP_REG_DXR2 0x04 #define OMAP_MCBSP_REG_DXR1 0x06 +#define OMAP_MCBSP_REG_DRR 0x02 +#define OMAP_MCBSP_REG_DXR 0x06 #define OMAP_MCBSP_REG_SPCR2 0x08 #define OMAP_MCBSP_REG_SPCR1 0x0a #define OMAP_MCBSP_REG_RCR2 0x0c @@ -106,13 +92,6 @@ static struct platform_device omap_mcbsp##port_nr = { \ #define OMAP_MCBSP_REG_XCCR 0x00 #define OMAP_MCBSP_REG_RCCR 0x00 -#define AUDIO_MCBSP_DATAWRITE (OMAP1510_MCBSP1_BASE + OMAP_MCBSP_REG_DXR1) -#define AUDIO_MCBSP_DATAREAD (OMAP1510_MCBSP1_BASE + OMAP_MCBSP_REG_DRR1) - -#define AUDIO_MCBSP OMAP_MCBSP1 -#define AUDIO_DMA_TX OMAP_DMA_MCBSP1_TX -#define AUDIO_DMA_RX OMAP_DMA_MCBSP1_RX - #else #define OMAP_MCBSP_REG_DRR2 0x00 @@ -168,13 +147,6 @@ static struct platform_device omap_mcbsp##port_nr = { \ #define OMAP_ST_REG_SFIRCR 0x28 #define OMAP_ST_REG_SSELCR 0x2C -#define AUDIO_MCBSP_DATAWRITE (OMAP24XX_MCBSP2_BASE + OMAP_MCBSP_REG_DXR1) -#define AUDIO_MCBSP_DATAREAD (OMAP24XX_MCBSP2_BASE + OMAP_MCBSP_REG_DRR1) - -#define AUDIO_MCBSP OMAP_MCBSP2 -#define AUDIO_DMA_TX OMAP24XX_DMA_MCBSP2_TX -#define AUDIO_DMA_RX OMAP24XX_DMA_MCBSP2_RX - #endif /************************** McBSP SPCR1 bit definitions ***********************/ @@ -428,8 +400,9 @@ struct omap_mcbsp_platform_data { #ifdef CONFIG_ARCH_OMAP3 /* Sidetone block for McBSP 2 and 3 */ unsigned long phys_base_st; - u16 buffer_size; #endif + u16 buffer_size; + unsigned int mcbsp_config_type; }; struct omap_mcbsp_st_data { @@ -445,6 +418,7 @@ struct omap_mcbsp_st_data { struct omap_mcbsp { struct device *dev; unsigned long phys_base; + unsigned long phys_dma_base; void __iomem *io_base; u8 id; u8 free; @@ -471,7 +445,6 @@ struct omap_mcbsp { /* Protect the field .free, while checking if the mcbsp is in use */ spinlock_t lock; struct omap_mcbsp_platform_data *pdata; - struct clk *iclk; struct clk *fclk; #ifdef CONFIG_ARCH_OMAP3 struct omap_mcbsp_st_data *st_data; @@ -480,7 +453,17 @@ struct omap_mcbsp { u16 max_rx_thres; #endif void *reg_cache; + unsigned int mcbsp_config_type; }; + +/** + * omap_mcbsp_dev_attr - OMAP McBSP device attributes for omap_hwmod + * @sidetone: name of the sidetone device + */ +struct omap_mcbsp_dev_attr { + const char *sidetone; +}; + extern struct omap_mcbsp **mcbsp_ptr; extern int omap_mcbsp_count, omap_mcbsp_cache_size; @@ -488,8 +471,8 @@ extern int omap_mcbsp_count, omap_mcbsp_cache_size; #define id_to_mcbsp_ptr(id) mcbsp_ptr[id]; int omap_mcbsp_init(void); -void omap_mcbsp_register_board_cfg(struct omap_mcbsp_platform_data *config, - int size); +void omap_mcbsp_register_board_cfg(struct resource *res, int res_count, + struct omap_mcbsp_platform_data *config, int size); void omap_mcbsp_config(unsigned int id, const struct omap_mcbsp_reg_cfg * config); #ifdef CONFIG_ARCH_OMAP3 void omap_mcbsp_set_tx_threshold(unsigned int id, u16 threshold); @@ -539,6 +522,9 @@ int omap_mcbsp_set_io_type(unsigned int id, omap_mcbsp_io_type_t io_type); void omap2_mcbsp1_mux_clkr_src(u8 mux); void omap2_mcbsp1_mux_fsr_src(u8 mux); +int omap_mcbsp_dma_ch_params(unsigned int id, unsigned int stream); +int omap_mcbsp_dma_reg_params(unsigned int id, unsigned int stream); + #ifdef CONFIG_ARCH_OMAP3 /* Sidetone specific API */ int omap_st_set_chgain(unsigned int id, int channel, s16 chgain); diff --git a/arch/arm/plat-omap/include/plat/mcspi.h b/arch/arm/plat-omap/include/plat/mcspi.h index 1254e4945b6..3d51b18131c 100644 --- a/arch/arm/plat-omap/include/plat/mcspi.h +++ b/arch/arm/plat-omap/include/plat/mcspi.h @@ -1,8 +1,19 @@ #ifndef _OMAP2_MCSPI_H #define _OMAP2_MCSPI_H +#define OMAP2_MCSPI_REV 0 +#define OMAP3_MCSPI_REV 1 +#define OMAP4_MCSPI_REV 2 + +#define OMAP4_MCSPI_REG_OFFSET 0x100 + struct omap2_mcspi_platform_config { unsigned short num_cs; + unsigned int regs_offset; +}; + +struct omap2_mcspi_dev_attr { + unsigned short num_chipselect; }; struct omap2_mcspi_device_config { diff --git a/arch/arm/plat-omap/include/plat/mmc.h b/arch/arm/plat-omap/include/plat/mmc.h index f57f36abb07..f38fef9f131 100644 --- a/arch/arm/plat-omap/include/plat/mmc.h +++ b/arch/arm/plat-omap/include/plat/mmc.h @@ -24,25 +24,19 @@ #define OMAP1_MMC2_BASE 0xfffb7c00 /* omap16xx only */ #define OMAP24XX_NR_MMC 2 -#define OMAP34XX_NR_MMC 3 -#define OMAP44XX_NR_MMC 5 #define OMAP2420_MMC_SIZE OMAP1_MMC_SIZE -#define OMAP3_HSMMC_SIZE 0x200 -#define OMAP4_HSMMC_SIZE 0x1000 #define OMAP2_MMC1_BASE 0x4809c000 -#define OMAP2_MMC2_BASE 0x480b4000 -#define OMAP3_MMC3_BASE 0x480ad000 -#define OMAP4_MMC4_BASE 0x480d1000 -#define OMAP4_MMC5_BASE 0x480d5000 + #define OMAP4_MMC_REG_OFFSET 0x100 -#define HSMMC5 (1 << 4) -#define HSMMC4 (1 << 3) -#define HSMMC3 (1 << 2) -#define HSMMC2 (1 << 1) -#define HSMMC1 (1 << 0) #define OMAP_MMC_MAX_SLOTS 2 +#define OMAP_HSMMC_SUPPORTS_DUAL_VOLT BIT(1) + +struct omap_mmc_dev_attr { + u8 flags; +}; + struct omap_mmc_platform_data { /* back-link to device */ struct device *dev; @@ -71,6 +65,9 @@ struct omap_mmc_platform_data { u64 dma_mask; + /* Integrating attributes from the omap_hwmod layer */ + u8 controller_flags; + /* Register offset deviation */ u16 reg_offset; @@ -159,8 +156,7 @@ extern void omap_mmc_notify_cover_event(struct device *dev, int slot, defined(CONFIG_MMC_OMAP_HS) || defined(CONFIG_MMC_OMAP_HS_MODULE) void omap1_init_mmc(struct omap_mmc_platform_data **mmc_data, int nr_controllers); -void omap2_init_mmc(struct omap_mmc_platform_data **mmc_data, - int nr_controllers); +void omap242x_init_mmc(struct omap_mmc_platform_data **mmc_data); int omap_mmc_add(const char *name, int id, unsigned long base, unsigned long size, unsigned int irq, struct omap_mmc_platform_data *data); @@ -169,8 +165,7 @@ static inline void omap1_init_mmc(struct omap_mmc_platform_data **mmc_data, int nr_controllers) { } -static inline void omap2_init_mmc(struct omap_mmc_platform_data **mmc_data, - int nr_controllers) +static inline void omap242x_init_mmc(struct omap_mmc_platform_data **mmc_data) { } static inline int omap_mmc_add(const char *name, int id, unsigned long base, diff --git a/arch/arm/plat-omap/include/plat/multi.h b/arch/arm/plat-omap/include/plat/multi.h index ffd909fa528..999ffba2690 100644 --- a/arch/arm/plat-omap/include/plat/multi.h +++ b/arch/arm/plat-omap/include/plat/multi.h @@ -66,7 +66,7 @@ # error "OMAP1 and OMAP2PLUS can't be selected at the same time" # endif #endif -#ifdef CONFIG_ARCH_OMAP2420 +#ifdef CONFIG_SOC_OMAP2420 # ifdef OMAP_NAME # undef MULTI_OMAP2 # define MULTI_OMAP2 @@ -74,7 +74,7 @@ # define OMAP_NAME omap2420 # endif #endif -#ifdef CONFIG_ARCH_OMAP2430 +#ifdef CONFIG_SOC_OMAP2430 # ifdef OMAP_NAME # undef MULTI_OMAP2 # define MULTI_OMAP2 diff --git a/arch/arm/plat-omap/include/plat/nand.h b/arch/arm/plat-omap/include/plat/nand.h index 6562cd082bb..d86d1ecf006 100644 --- a/arch/arm/plat-omap/include/plat/nand.h +++ b/arch/arm/plat-omap/include/plat/nand.h @@ -8,8 +8,16 @@ * published by the Free Software Foundation. */ +#include <plat/gpmc.h> #include <linux/mtd/partitions.h> +enum nand_io { + NAND_OMAP_PREFETCH_POLLED = 0, /* prefetch polled mode, default */ + NAND_OMAP_POLLED, /* polled mode, without prefetch */ + NAND_OMAP_PREFETCH_DMA, /* prefetch enabled sDMA mode */ + NAND_OMAP_PREFETCH_IRQ /* prefetch enabled irq mode */ +}; + struct omap_nand_platform_data { unsigned int options; int cs; @@ -20,8 +28,11 @@ struct omap_nand_platform_data { int (*nand_setup)(void); int (*dev_ready)(struct omap_nand_platform_data *); int dma_channel; + int gpmc_irq; + enum nand_io xfer_type; unsigned long phys_base; int devsize; + enum omap_ecc ecc_opt; }; /* minimum size for IO mapping */ diff --git a/arch/arm/plat-omap/include/plat/omap_hwmod.h b/arch/arm/plat-omap/include/plat/omap_hwmod.h index 1eee85a8abb..1adea9c6298 100644 --- a/arch/arm/plat-omap/include/plat/omap_hwmod.h +++ b/arch/arm/plat-omap/include/plat/omap_hwmod.h @@ -1,7 +1,7 @@ /* * omap_hwmod macros, structures * - * Copyright (C) 2009-2010 Nokia Corporation + * Copyright (C) 2009-2011 Nokia Corporation * Paul Walmsley * * Created in collaboration with (alphabetical order): Benoît Cousson, @@ -30,11 +30,11 @@ #define __ARCH_ARM_PLAT_OMAP_INCLUDE_MACH_OMAP_HWMOD_H #include <linux/kernel.h> +#include <linux/init.h> #include <linux/list.h> #include <linux/ioport.h> #include <linux/spinlock.h> #include <plat/cpu.h> -#include <plat/voltage.h> struct omap_device; @@ -90,6 +90,9 @@ extern struct omap_hwmod_sysc_fields omap_hwmod_sysc_type2; struct omap_hwmod_mux_info { int nr_pads; struct omap_device_pad *pads; + int nr_pads_dynamic; + struct omap_device_pad **pads_dynamic; + bool enabled; }; /** @@ -124,6 +127,7 @@ struct omap_hwmod_dma_info { * struct omap_hwmod_rst_info - IPs reset lines use by hwmod * @name: name of the reset line (module local name) * @rst_shift: Offset of the reset bit + * @st_shift: Offset of the reset status bit (OMAP2/3 only) * * @name should be something short, e.g., "cpu0" or "rst". It is defined * locally to the hwmod. @@ -131,6 +135,7 @@ struct omap_hwmod_dma_info { struct omap_hwmod_rst_info { const char *name; u8 rst_shift; + u8 st_shift; }; /** @@ -178,7 +183,8 @@ struct omap_hwmod_omap2_firewall { #define ADDR_TYPE_RT (1 << 1) /** - * struct omap_hwmod_addr_space - MPU address space handled by the hwmod + * struct omap_hwmod_addr_space - address space handled by the hwmod + * @name: name of the address space * @pa_start: starting physical address * @pa_end: ending physical address * @flags: (see omap_hwmod_addr_space.flags macros above) @@ -187,6 +193,7 @@ struct omap_hwmod_omap2_firewall { * structure. GPMC is one example. */ struct omap_hwmod_addr_space { + const char *name; u32 pa_start; u32 pa_end; u8 flags; @@ -370,9 +377,11 @@ struct omap_hwmod_omap4_prcm { * of standby, rather than relying on module smart-standby * HWMOD_INIT_NO_RESET: don't reset this module at boot - important for * SDRAM controller, etc. XXX probably belongs outside the main hwmod file + * XXX Should be HWMOD_SETUP_NO_RESET * HWMOD_INIT_NO_IDLE: don't idle this module at boot - important for SDRAM * controller, etc. XXX probably belongs outside the main hwmod file - * HWMOD_NO_AUTOIDLE: disable module autoidle (OCP_SYSCONFIG.AUTOIDLE) + * XXX Should be HWMOD_SETUP_NO_IDLE + * HWMOD_NO_OCP_AUTOIDLE: disable module autoidle (OCP_SYSCONFIG.AUTOIDLE) * when module is enabled, rather than the default, which is to * enable autoidle * HWMOD_SET_DEFAULT_CLOCKACT: program CLOCKACTIVITY bits at startup @@ -535,11 +544,12 @@ struct omap_hwmod { const struct omap_chip_id omap_chip; }; -int omap_hwmod_init(struct omap_hwmod **ohs); +int omap_hwmod_register(struct omap_hwmod **ohs); struct omap_hwmod *omap_hwmod_lookup(const char *name); int omap_hwmod_for_each(int (*fn)(struct omap_hwmod *oh, void *data), void *data); -int omap_hwmod_late_init(void); + +int __init omap_hwmod_setup_one(const char *name); int omap_hwmod_enable(struct omap_hwmod *oh); int _omap_hwmod_enable(struct omap_hwmod *oh); @@ -555,6 +565,7 @@ int omap_hwmod_enable_clocks(struct omap_hwmod *oh); int omap_hwmod_disable_clocks(struct omap_hwmod *oh); int omap_hwmod_set_slave_idlemode(struct omap_hwmod *oh, u8 idlemode); +int omap_hwmod_set_ocp_autoidle(struct omap_hwmod *oh, u8 autoidle); int omap_hwmod_reset(struct omap_hwmod *oh); void omap_hwmod_ocp_barrier(struct omap_hwmod *oh); @@ -589,6 +600,8 @@ int omap_hwmod_for_each_by_class(const char *classname, int omap_hwmod_set_postsetup_state(struct omap_hwmod *oh, u8 state); u32 omap_hwmod_get_context_loss_count(struct omap_hwmod *oh); +int omap_hwmod_no_setup_reset(struct omap_hwmod *oh); + /* * Chip variant-specific hwmod init routines - XXX should be converted * to use initcalls once the initial boot ordering is straightened out diff --git a/arch/arm/plat-omap/include/plat/onenand.h b/arch/arm/plat-omap/include/plat/onenand.h index affe87e9ece..cbe897ca7f9 100644 --- a/arch/arm/plat-omap/include/plat/onenand.h +++ b/arch/arm/plat-omap/include/plat/onenand.h @@ -15,12 +15,20 @@ #define ONENAND_SYNC_READ (1 << 0) #define ONENAND_SYNC_READWRITE (1 << 1) +struct onenand_freq_info { + u16 maf_id; + u16 dev_id; + u16 ver_id; +}; + struct omap_onenand_platform_data { int cs; int gpio_irq; struct mtd_partition *parts; int nr_parts; - int (*onenand_setup)(void __iomem *, int freq); + int (*onenand_setup)(void __iomem *, int *freq_ptr); + int (*get_freq)(const struct onenand_freq_info *freq_info, + bool *clk_dep); int dma_channel; u8 flags; u8 regulator_can_sleep; diff --git a/arch/arm/plat-omap/include/plat/prcm.h b/arch/arm/plat-omap/include/plat/prcm.h index 2fdf8c80d39..267f43bb2a4 100644 --- a/arch/arm/plat-omap/include/plat/prcm.h +++ b/arch/arm/plat-omap/include/plat/prcm.h @@ -28,7 +28,6 @@ #define __ASM_ARM_ARCH_OMAP_PRCM_H u32 omap_prcm_get_reset_sources(void); -void omap_prcm_arch_reset(char mode, const char *cmd); int omap2_cm_wait_idlest(void __iomem *reg, u32 mask, u8 idlest, const char *name); diff --git a/arch/arm/plat-omap/include/plat/sdrc.h b/arch/arm/plat-omap/include/plat/sdrc.h index efd87c8dda6..925b12b500d 100644 --- a/arch/arm/plat-omap/include/plat/sdrc.h +++ b/arch/arm/plat-omap/include/plat/sdrc.h @@ -124,8 +124,14 @@ struct omap_sdrc_params { u32 mr; }; -void __init omap2_sdrc_init(struct omap_sdrc_params *sdrc_cs0, +#if defined(CONFIG_ARCH_OMAP2) || defined(CONFIG_ARCH_OMAP3) +void omap2_sdrc_init(struct omap_sdrc_params *sdrc_cs0, struct omap_sdrc_params *sdrc_cs1); +#else +static inline void __init omap2_sdrc_init(struct omap_sdrc_params *sdrc_cs0, + struct omap_sdrc_params *sdrc_cs1) {}; +#endif + int omap2_sdrc_get_params(unsigned long r, struct omap_sdrc_params **sdrc_cs0, struct omap_sdrc_params **sdrc_cs1); diff --git a/arch/arm/plat-omap/include/plat/serial.h b/arch/arm/plat-omap/include/plat/serial.h index 8ff605c83ac..2723f9166ea 100644 --- a/arch/arm/plat-omap/include/plat/serial.h +++ b/arch/arm/plat-omap/include/plat/serial.h @@ -51,6 +51,11 @@ #define OMAP4_UART3_BASE 0x48020000 #define OMAP4_UART4_BASE 0x4806e000 +/* TI816X serial ports */ +#define TI816X_UART1_BASE 0x48020000 +#define TI816X_UART2_BASE 0x48022000 +#define TI816X_UART3_BASE 0x48024000 + /* External port on Zoom2/3 */ #define ZOOM_UART_BASE 0x10000000 #define ZOOM_UART_VIRT 0xfa400000 @@ -81,6 +86,9 @@ #define OMAP4UART2 OMAP2UART2 #define OMAP4UART3 43 #define OMAP4UART4 44 +#define TI816XUART1 81 +#define TI816XUART2 82 +#define TI816XUART3 83 #define ZOOM_UART 95 /* Only on zoom2/3 */ /* This is only used by 8250.c for omap1510 */ @@ -96,7 +104,6 @@ struct omap_board_data; -extern void __init omap_serial_early_init(void); extern void omap_serial_init(void); extern void omap_serial_init_port(struct omap_board_data *bdata); extern int omap_uart_can_sleep(void); diff --git a/arch/arm/plat-omap/include/plat/system.h b/arch/arm/plat-omap/include/plat/system.h index d0a119f735b..c5fa9e92900 100644 --- a/arch/arm/plat-omap/include/plat/system.h +++ b/arch/arm/plat-omap/include/plat/system.h @@ -4,48 +4,14 @@ */ #ifndef __ASM_ARCH_SYSTEM_H #define __ASM_ARCH_SYSTEM_H -#include <linux/clk.h> -#include <asm/mach-types.h> -#include <mach/hardware.h> - -#include <plat/prcm.h> - -#ifndef CONFIG_MACH_VOICEBLUE -#define voiceblue_reset() do {} while (0) -#else -extern void voiceblue_reset(void); -#endif +#include <asm/proc-fns.h> static inline void arch_idle(void) { cpu_do_idle(); } -static inline void omap1_arch_reset(char mode, const char *cmd) -{ - /* - * Workaround for 5912/1611b bug mentioned in sprz209d.pdf p. 28 - * "Global Software Reset Affects Traffic Controller Frequency". - */ - if (cpu_is_omap5912()) { - omap_writew(omap_readw(DPLL_CTL) & ~(1 << 4), - DPLL_CTL); - omap_writew(0x8, ARM_RSTCT1); - } - - if (machine_is_voiceblue()) - voiceblue_reset(); - else - omap_writew(1, ARM_RSTCT1); -} - -static inline void arch_reset(char mode, const char *cmd) -{ - if (!cpu_class_is_omap2()) - omap1_arch_reset(mode, cmd); - else - omap_prcm_arch_reset(mode, cmd); -} +extern void (*arch_reset)(char, const char *); #endif diff --git a/arch/arm/plat-omap/include/plat/ti816x.h b/arch/arm/plat-omap/include/plat/ti816x.h new file mode 100644 index 00000000000..50510f5dda1 --- /dev/null +++ b/arch/arm/plat-omap/include/plat/ti816x.h @@ -0,0 +1,27 @@ +/* + * This file contains the address data for various TI816X modules. + * + * Copyright (C) 2010 Texas Instruments, Inc. - http://www.ti.com/ + * + * This program is free software; you can redistribute it and/or + * modify it under the terms of the GNU General Public License as + * published by the Free Software Foundation version 2. + * + * This program is distributed "as is" WITHOUT ANY WARRANTY of any + * kind, whether express or implied; without even the implied warranty + * of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + */ + +#ifndef __ASM_ARCH_TI816X_H +#define __ASM_ARCH_TI816X_H + +#define L4_SLOW_TI816X_BASE 0x48000000 + +#define TI816X_SCM_BASE 0x48140000 +#define TI816X_CTRL_BASE TI816X_SCM_BASE +#define TI816X_PRCM_BASE 0x48180000 + +#define TI816X_ARM_INTC_BASE 0x48200000 + +#endif /* __ASM_ARCH_TI816X_H */ diff --git a/arch/arm/plat-omap/include/plat/uncompress.h b/arch/arm/plat-omap/include/plat/uncompress.h index ad98b85cae2..30b891c4a93 100644 --- a/arch/arm/plat-omap/include/plat/uncompress.h +++ b/arch/arm/plat-omap/include/plat/uncompress.h @@ -93,6 +93,10 @@ static inline void flush(void) #define DEBUG_LL_ZOOM(mach) \ _DEBUG_LL_ENTRY(mach, ZOOM_UART_BASE, ZOOM_PORT_SHIFT, ZOOM_UART) +#define DEBUG_LL_TI816X(p, mach) \ + _DEBUG_LL_ENTRY(mach, TI816X_UART##p##_BASE, OMAP_PORT_SHIFT, \ + TI816XUART##p) + static inline void __arch_decomp_setup(unsigned long arch_id) { int port = 0; @@ -166,6 +170,9 @@ static inline void __arch_decomp_setup(unsigned long arch_id) DEBUG_LL_ZOOM(omap_zoom2); DEBUG_LL_ZOOM(omap_zoom3); + /* TI8168 base boards using UART3 */ + DEBUG_LL_TI816X(3, ti8168evm); + } while (0); } diff --git a/arch/arm/plat-omap/include/plat/usb.h b/arch/arm/plat-omap/include/plat/usb.h index fe449f1a1c1..02b96c8f6a1 100644 --- a/arch/arm/plat-omap/include/plat/usb.h +++ b/arch/arm/plat-omap/include/plat/usb.h @@ -110,6 +110,11 @@ extern int omap4430_phy_exit(struct device *dev); extern int omap4430_phy_suspend(struct device *dev, int suspend); #endif +extern void am35x_musb_reset(void); +extern void am35x_musb_phy_power(u8 on); +extern void am35x_musb_clear_irq(void); +extern void am35x_musb_set_mode(u8 musb_mode); + /* * FIXME correct answer depends on hmc_mode, * as does (on omap1) any nonzero value for config->otg port number diff --git a/arch/arm/plat-omap/io.c b/arch/arm/plat-omap/io.c index f1295fafcd3..f1ecfa9fc61 100644 --- a/arch/arm/plat-omap/io.c +++ b/arch/arm/plat-omap/io.c @@ -85,7 +85,10 @@ void __iomem *omap_ioremap(unsigned long p, size_t size, unsigned int type) } #endif #ifdef CONFIG_ARCH_OMAP3 - if (cpu_is_omap34xx()) { + if (cpu_is_ti816x()) { + if (BETWEEN(p, L4_34XX_PHYS, L4_34XX_SIZE)) + return XLATE(p, L4_34XX_PHYS, L4_34XX_VIRT); + } else if (cpu_is_omap34xx()) { if (BETWEEN(p, L3_34XX_PHYS, L3_34XX_SIZE)) return XLATE(p, L3_34XX_PHYS, L3_34XX_VIRT); if (BETWEEN(p, L4_34XX_PHYS, L4_34XX_SIZE)) diff --git a/arch/arm/plat-omap/iommu.c b/arch/arm/plat-omap/iommu.c index b1107c08da5..8a51fd58f65 100644 --- a/arch/arm/plat-omap/iommu.c +++ b/arch/arm/plat-omap/iommu.c @@ -104,6 +104,9 @@ static int iommu_enable(struct iommu *obj) if (!obj) return -EINVAL; + if (!arch_iommu) + return -ENODEV; + clk_enable(obj->clk); err = arch_iommu->enable(obj); @@ -780,25 +783,19 @@ static void iopgtable_clear_entry_all(struct iommu *obj) */ static irqreturn_t iommu_fault_handler(int irq, void *data) { - u32 stat, da; + u32 da, errs; u32 *iopgd, *iopte; - int err = -EIO; struct iommu *obj = data; if (!obj->refcount) return IRQ_NONE; - /* Dynamic loading TLB or PTE */ - if (obj->isr) - err = obj->isr(obj); - - if (!err) - return IRQ_HANDLED; - clk_enable(obj->clk); - stat = iommu_report_fault(obj, &da); + errs = iommu_report_fault(obj, &da); clk_disable(obj->clk); - if (!stat) + + /* Fault callback or TLB/PTE Dynamic loading */ + if (obj->isr && !obj->isr(obj, da, errs, obj->isr_priv)) return IRQ_HANDLED; iommu_disable(obj); @@ -806,15 +803,16 @@ static irqreturn_t iommu_fault_handler(int irq, void *data) iopgd = iopgd_offset(obj, da); if (!iopgd_is_table(*iopgd)) { - dev_err(obj->dev, "%s: da:%08x pgd:%p *pgd:%08x\n", __func__, - da, iopgd, *iopgd); + dev_err(obj->dev, "%s: errs:0x%08x da:0x%08x pgd:0x%p " + "*pgd:px%08x\n", obj->name, errs, da, iopgd, *iopgd); return IRQ_NONE; } iopte = iopte_offset(iopgd, da); - dev_err(obj->dev, "%s: da:%08x pgd:%p *pgd:%08x pte:%p *pte:%08x\n", - __func__, da, iopgd, *iopgd, iopte, *iopte); + dev_err(obj->dev, "%s: errs:0x%08x da:0x%08x pgd:0x%p *pgd:0x%08x " + "pte:0x%p *pte:0x%08x\n", obj->name, errs, da, iopgd, *iopgd, + iopte, *iopte); return IRQ_NONE; } @@ -917,6 +915,33 @@ void iommu_put(struct iommu *obj) } EXPORT_SYMBOL_GPL(iommu_put); +int iommu_set_isr(const char *name, + int (*isr)(struct iommu *obj, u32 da, u32 iommu_errs, + void *priv), + void *isr_priv) +{ + struct device *dev; + struct iommu *obj; + + dev = driver_find_device(&omap_iommu_driver.driver, NULL, (void *)name, + device_match_by_alias); + if (!dev) + return -ENODEV; + + obj = to_iommu(dev); + mutex_lock(&obj->iommu_lock); + if (obj->refcount != 0) { + mutex_unlock(&obj->iommu_lock); + return -EBUSY; + } + obj->isr = isr; + obj->isr_priv = isr_priv; + mutex_unlock(&obj->iommu_lock); + + return 0; +} +EXPORT_SYMBOL_GPL(iommu_set_isr); + /* * OMAP Device MMU(IOMMU) detection */ @@ -957,11 +982,6 @@ static int __devinit omap_iommu_probe(struct platform_device *pdev) err = -ENODEV; goto err_mem; } - obj->regbase = ioremap(res->start, resource_size(res)); - if (!obj->regbase) { - err = -ENOMEM; - goto err_mem; - } res = request_mem_region(res->start, resource_size(res), dev_name(&pdev->dev)); @@ -970,6 +990,12 @@ static int __devinit omap_iommu_probe(struct platform_device *pdev) goto err_mem; } + obj->regbase = ioremap(res->start, resource_size(res)); + if (!obj->regbase) { + err = -ENOMEM; + goto err_ioremap; + } + irq = platform_get_irq(pdev, 0); if (irq < 0) { err = -ENODEV; @@ -998,8 +1024,9 @@ static int __devinit omap_iommu_probe(struct platform_device *pdev) err_pgd: free_irq(irq, obj); err_irq: - release_mem_region(res->start, resource_size(res)); iounmap(obj->regbase); +err_ioremap: + release_mem_region(res->start, resource_size(res)); err_mem: clk_put(obj->clk); err_clk: diff --git a/arch/arm/plat-omap/iovmm.c b/arch/arm/plat-omap/iovmm.c index 6dc1296c8c7..51ef43e8def 100644 --- a/arch/arm/plat-omap/iovmm.c +++ b/arch/arm/plat-omap/iovmm.c @@ -271,20 +271,21 @@ static struct iovm_struct *alloc_iovm_area(struct iommu *obj, u32 da, size_t bytes, u32 flags) { struct iovm_struct *new, *tmp; - u32 start, prev_end, alignement; + u32 start, prev_end, alignment; if (!obj || !bytes) return ERR_PTR(-EINVAL); start = da; - alignement = PAGE_SIZE; + alignment = PAGE_SIZE; - if (flags & IOVMF_DA_ANON) { - start = obj->da_start; + if (~flags & IOVMF_DA_FIXED) { + /* Don't map address 0 */ + start = obj->da_start ? obj->da_start : alignment; if (flags & IOVMF_LINEAR) - alignement = iopgsz_max(bytes); - start = roundup(start, alignement); + alignment = iopgsz_max(bytes); + start = roundup(start, alignment); } else if (start < obj->da_start || start > obj->da_end || obj->da_end - start < bytes) { return ERR_PTR(-EINVAL); @@ -303,8 +304,8 @@ static struct iovm_struct *alloc_iovm_area(struct iommu *obj, u32 da, if (tmp->da_start > start && (tmp->da_start - start) >= bytes) goto found; - if (tmp->da_end >= start && flags & IOVMF_DA_ANON) - start = roundup(tmp->da_end + 1, alignement); + if (tmp->da_end >= start && ~flags & IOVMF_DA_FIXED) + start = roundup(tmp->da_end + 1, alignment); prev_end = tmp->da_end; } @@ -650,7 +651,6 @@ u32 iommu_vmap(struct iommu *obj, u32 da, const struct sg_table *sgt, flags &= IOVMF_HW_MASK; flags |= IOVMF_DISCONT; flags |= IOVMF_MMIO; - flags |= (da ? IOVMF_DA_FIXED : IOVMF_DA_ANON); da = __iommu_vmap(obj, da, sgt, va, bytes, flags); if (IS_ERR_VALUE(da)) @@ -690,7 +690,7 @@ EXPORT_SYMBOL_GPL(iommu_vunmap); * @flags: iovma and page property * * Allocate @bytes linearly and creates 1-n-1 mapping and returns - * @da again, which might be adjusted if 'IOVMF_DA_ANON' is set. + * @da again, which might be adjusted if 'IOVMF_DA_FIXED' is not set. */ u32 iommu_vmalloc(struct iommu *obj, u32 da, size_t bytes, u32 flags) { @@ -709,7 +709,6 @@ u32 iommu_vmalloc(struct iommu *obj, u32 da, size_t bytes, u32 flags) flags &= IOVMF_HW_MASK; flags |= IOVMF_DISCONT; flags |= IOVMF_ALLOC; - flags |= (da ? IOVMF_DA_FIXED : IOVMF_DA_ANON); sgt = sgtable_alloc(bytes, flags, da, 0); if (IS_ERR(sgt)) { @@ -780,7 +779,7 @@ static u32 __iommu_kmap(struct iommu *obj, u32 da, u32 pa, void *va, * @flags: iovma and page property * * Creates 1-1-1 mapping and returns @da again, which can be - * adjusted if 'IOVMF_DA_ANON' is set. + * adjusted if 'IOVMF_DA_FIXED' is not set. */ u32 iommu_kmap(struct iommu *obj, u32 da, u32 pa, size_t bytes, u32 flags) @@ -799,7 +798,6 @@ u32 iommu_kmap(struct iommu *obj, u32 da, u32 pa, size_t bytes, flags &= IOVMF_HW_MASK; flags |= IOVMF_LINEAR; flags |= IOVMF_MMIO; - flags |= (da ? IOVMF_DA_FIXED : IOVMF_DA_ANON); da = __iommu_kmap(obj, da, pa, va, bytes, flags); if (IS_ERR_VALUE(da)) @@ -838,7 +836,7 @@ EXPORT_SYMBOL_GPL(iommu_kunmap); * @flags: iovma and page property * * Allocate @bytes linearly and creates 1-1-1 mapping and returns - * @da again, which might be adjusted if 'IOVMF_DA_ANON' is set. + * @da again, which might be adjusted if 'IOVMF_DA_FIXED' is not set. */ u32 iommu_kmalloc(struct iommu *obj, u32 da, size_t bytes, u32 flags) { @@ -858,7 +856,6 @@ u32 iommu_kmalloc(struct iommu *obj, u32 da, size_t bytes, u32 flags) flags &= IOVMF_HW_MASK; flags |= IOVMF_LINEAR; flags |= IOVMF_ALLOC; - flags |= (da ? IOVMF_DA_FIXED : IOVMF_DA_ANON); da = __iommu_kmap(obj, da, pa, va, bytes, flags); if (IS_ERR_VALUE(da)) diff --git a/arch/arm/plat-omap/mcbsp.c b/arch/arm/plat-omap/mcbsp.c index b5a6e178a7f..d598d9fd65a 100644 --- a/arch/arm/plat-omap/mcbsp.c +++ b/arch/arm/plat-omap/mcbsp.c @@ -27,6 +27,8 @@ #include <plat/dma.h> #include <plat/mcbsp.h> +#include <plat/omap_device.h> +#include <linux/pm_runtime.h> /* XXX These "sideways" includes are a sign that something is wrong */ #include "../mach-omap2/cm2xxx_3xxx.h" @@ -227,10 +229,83 @@ void omap_mcbsp_config(unsigned int id, const struct omap_mcbsp_reg_cfg *config) } EXPORT_SYMBOL(omap_mcbsp_config); +/** + * omap_mcbsp_dma_params - returns the dma channel number + * @id - mcbsp id + * @stream - indicates the direction of data flow (rx or tx) + * + * Returns the dma channel number for the rx channel or tx channel + * based on the value of @stream for the requested mcbsp given by @id + */ +int omap_mcbsp_dma_ch_params(unsigned int id, unsigned int stream) +{ + struct omap_mcbsp *mcbsp; + + if (!omap_mcbsp_check_valid_id(id)) { + printk(KERN_ERR "%s: Invalid id (%d)\n", __func__, id + 1); + return -ENODEV; + } + mcbsp = id_to_mcbsp_ptr(id); + + if (stream) + return mcbsp->dma_rx_sync; + else + return mcbsp->dma_tx_sync; +} +EXPORT_SYMBOL(omap_mcbsp_dma_ch_params); + +/** + * omap_mcbsp_dma_reg_params - returns the address of mcbsp data register + * @id - mcbsp id + * @stream - indicates the direction of data flow (rx or tx) + * + * Returns the address of mcbsp data transmit register or data receive register + * to be used by DMA for transferring/receiving data based on the value of + * @stream for the requested mcbsp given by @id + */ +int omap_mcbsp_dma_reg_params(unsigned int id, unsigned int stream) +{ + struct omap_mcbsp *mcbsp; + int data_reg; + + if (!omap_mcbsp_check_valid_id(id)) { + printk(KERN_ERR "%s: Invalid id (%d)\n", __func__, id + 1); + return -ENODEV; + } + mcbsp = id_to_mcbsp_ptr(id); + + data_reg = mcbsp->phys_dma_base; + + if (mcbsp->mcbsp_config_type < MCBSP_CONFIG_TYPE2) { + if (stream) + data_reg += OMAP_MCBSP_REG_DRR1; + else + data_reg += OMAP_MCBSP_REG_DXR1; + } else { + if (stream) + data_reg += OMAP_MCBSP_REG_DRR; + else + data_reg += OMAP_MCBSP_REG_DXR; + } + + return data_reg; +} +EXPORT_SYMBOL(omap_mcbsp_dma_reg_params); + #ifdef CONFIG_ARCH_OMAP3 +static struct omap_device *find_omap_device_by_dev(struct device *dev) +{ + struct platform_device *pdev = container_of(dev, + struct platform_device, dev); + return container_of(pdev, struct omap_device, pdev); +} + static void omap_st_on(struct omap_mcbsp *mcbsp) { unsigned int w; + struct omap_device *od; + + od = find_omap_device_by_dev(mcbsp->dev); /* * Sidetone uses McBSP ICLK - which must not idle when sidetones @@ -244,9 +319,6 @@ static void omap_st_on(struct omap_mcbsp *mcbsp) w = MCBSP_READ(mcbsp, SSELCR); MCBSP_WRITE(mcbsp, SSELCR, w | SIDETONEEN); - w = MCBSP_ST_READ(mcbsp, SYSCONFIG); - MCBSP_ST_WRITE(mcbsp, SYSCONFIG, w & ~(ST_AUTOIDLE)); - /* Enable Sidetone from Sidetone Core */ w = MCBSP_ST_READ(mcbsp, SSELCR); MCBSP_ST_WRITE(mcbsp, SSELCR, w | ST_SIDETONEEN); @@ -255,13 +327,13 @@ static void omap_st_on(struct omap_mcbsp *mcbsp) static void omap_st_off(struct omap_mcbsp *mcbsp) { unsigned int w; + struct omap_device *od; + + od = find_omap_device_by_dev(mcbsp->dev); w = MCBSP_ST_READ(mcbsp, SSELCR); MCBSP_ST_WRITE(mcbsp, SSELCR, w & ~(ST_SIDETONEEN)); - w = MCBSP_ST_READ(mcbsp, SYSCONFIG); - MCBSP_ST_WRITE(mcbsp, SYSCONFIG, w | ST_AUTOIDLE); - w = MCBSP_READ(mcbsp, SSELCR); MCBSP_WRITE(mcbsp, SSELCR, w & ~(SIDETONEEN)); @@ -273,9 +345,9 @@ static void omap_st_off(struct omap_mcbsp *mcbsp) static void omap_st_fir_write(struct omap_mcbsp *mcbsp, s16 *fir) { u16 val, i; + struct omap_device *od; - val = MCBSP_ST_READ(mcbsp, SYSCONFIG); - MCBSP_ST_WRITE(mcbsp, SYSCONFIG, val & ~(ST_AUTOIDLE)); + od = find_omap_device_by_dev(mcbsp->dev); val = MCBSP_ST_READ(mcbsp, SSELCR); @@ -303,9 +375,9 @@ static void omap_st_chgain(struct omap_mcbsp *mcbsp) { u16 w; struct omap_mcbsp_st_data *st_data = mcbsp->st_data; + struct omap_device *od; - w = MCBSP_ST_READ(mcbsp, SYSCONFIG); - MCBSP_ST_WRITE(mcbsp, SYSCONFIG, w & ~(ST_AUTOIDLE)); + od = find_omap_device_by_dev(mcbsp->dev); w = MCBSP_ST_READ(mcbsp, SSELCR); @@ -648,48 +720,33 @@ EXPORT_SYMBOL(omap_mcbsp_get_dma_op_mode); static inline void omap34xx_mcbsp_request(struct omap_mcbsp *mcbsp) { + struct omap_device *od; + + od = find_omap_device_by_dev(mcbsp->dev); /* * Enable wakup behavior, smart idle and all wakeups * REVISIT: some wakeups may be unnecessary */ if (cpu_is_omap34xx() || cpu_is_omap44xx()) { - u16 syscon; - - syscon = MCBSP_READ(mcbsp, SYSCON); - syscon &= ~(ENAWAKEUP | SIDLEMODE(0x03) | CLOCKACTIVITY(0x03)); - - if (mcbsp->dma_op_mode == MCBSP_DMA_MODE_THRESHOLD) { - syscon |= (ENAWAKEUP | SIDLEMODE(0x02) | - CLOCKACTIVITY(0x02)); - MCBSP_WRITE(mcbsp, WAKEUPEN, XRDYEN | RRDYEN); - } else { - syscon |= SIDLEMODE(0x01); - } - - MCBSP_WRITE(mcbsp, SYSCON, syscon); + MCBSP_WRITE(mcbsp, WAKEUPEN, XRDYEN | RRDYEN); } } static inline void omap34xx_mcbsp_free(struct omap_mcbsp *mcbsp) { + struct omap_device *od; + + od = find_omap_device_by_dev(mcbsp->dev); + /* * Disable wakup behavior, smart idle and all wakeups */ if (cpu_is_omap34xx() || cpu_is_omap44xx()) { - u16 syscon; - - syscon = MCBSP_READ(mcbsp, SYSCON); - syscon &= ~(ENAWAKEUP | SIDLEMODE(0x03) | CLOCKACTIVITY(0x03)); /* * HW bug workaround - If no_idle mode is taken, we need to * go to smart_idle before going to always_idle, or the * device will not hit retention anymore. */ - syscon |= SIDLEMODE(0x02); - MCBSP_WRITE(mcbsp, SYSCON, syscon); - - syscon &= ~(SIDLEMODE(0x03)); - MCBSP_WRITE(mcbsp, SYSCON, syscon); MCBSP_WRITE(mcbsp, WAKEUPEN, 0); } @@ -764,8 +821,7 @@ int omap_mcbsp_request(unsigned int id) if (mcbsp->pdata && mcbsp->pdata->ops && mcbsp->pdata->ops->request) mcbsp->pdata->ops->request(id); - clk_enable(mcbsp->iclk); - clk_enable(mcbsp->fclk); + pm_runtime_get_sync(mcbsp->dev); /* Do procedure specific to omap34xx arch, if applicable */ omap34xx_mcbsp_request(mcbsp); @@ -813,8 +869,7 @@ err_clk_disable: /* Do procedure specific to omap34xx arch, if applicable */ omap34xx_mcbsp_free(mcbsp); - clk_disable(mcbsp->fclk); - clk_disable(mcbsp->iclk); + pm_runtime_put_sync(mcbsp->dev); spin_lock(&mcbsp->lock); mcbsp->free = true; @@ -844,8 +899,7 @@ void omap_mcbsp_free(unsigned int id) /* Do procedure specific to omap34xx arch, if applicable */ omap34xx_mcbsp_free(mcbsp); - clk_disable(mcbsp->fclk); - clk_disable(mcbsp->iclk); + pm_runtime_put_sync(mcbsp->dev); if (mcbsp->io_type == OMAP_MCBSP_IRQ_IO) { /* Free IRQs */ @@ -1649,7 +1703,8 @@ static const struct attribute_group sidetone_attr_group = { static int __devinit omap_st_add(struct omap_mcbsp *mcbsp) { - struct omap_mcbsp_platform_data *pdata = mcbsp->pdata; + struct platform_device *pdev; + struct resource *res; struct omap_mcbsp_st_data *st_data; int err; @@ -1659,7 +1714,10 @@ static int __devinit omap_st_add(struct omap_mcbsp *mcbsp) goto err1; } - st_data->io_base_st = ioremap(pdata->phys_base_st, SZ_4K); + pdev = container_of(mcbsp->dev, struct platform_device, dev); + + res = platform_get_resource_byname(pdev, IORESOURCE_MEM, "sidetone"); + st_data->io_base_st = ioremap(res->start, resource_size(res)); if (!st_data->io_base_st) { err = -ENOMEM; goto err2; @@ -1748,6 +1806,7 @@ static int __devinit omap_mcbsp_probe(struct platform_device *pdev) struct omap_mcbsp_platform_data *pdata = pdev->dev.platform_data; struct omap_mcbsp *mcbsp; int id = pdev->id - 1; + struct resource *res; int ret = 0; if (!pdata) { @@ -1777,47 +1836,78 @@ static int __devinit omap_mcbsp_probe(struct platform_device *pdev) mcbsp->dma_tx_lch = -1; mcbsp->dma_rx_lch = -1; - mcbsp->phys_base = pdata->phys_base; - mcbsp->io_base = ioremap(pdata->phys_base, SZ_4K); + res = platform_get_resource_byname(pdev, IORESOURCE_MEM, "mpu"); + if (!res) { + res = platform_get_resource(pdev, IORESOURCE_MEM, 0); + if (!res) { + dev_err(&pdev->dev, "%s:mcbsp%d has invalid memory" + "resource\n", __func__, pdev->id); + ret = -ENOMEM; + goto exit; + } + } + mcbsp->phys_base = res->start; + omap_mcbsp_cache_size = resource_size(res); + mcbsp->io_base = ioremap(res->start, resource_size(res)); if (!mcbsp->io_base) { ret = -ENOMEM; goto err_ioremap; } + res = platform_get_resource_byname(pdev, IORESOURCE_MEM, "dma"); + if (!res) + mcbsp->phys_dma_base = mcbsp->phys_base; + else + mcbsp->phys_dma_base = res->start; + /* Default I/O is IRQ based */ mcbsp->io_type = OMAP_MCBSP_IRQ_IO; - mcbsp->tx_irq = pdata->tx_irq; - mcbsp->rx_irq = pdata->rx_irq; - mcbsp->dma_rx_sync = pdata->dma_rx_sync; - mcbsp->dma_tx_sync = pdata->dma_tx_sync; - mcbsp->iclk = clk_get(&pdev->dev, "ick"); - if (IS_ERR(mcbsp->iclk)) { - ret = PTR_ERR(mcbsp->iclk); - dev_err(&pdev->dev, "unable to get ick: %d\n", ret); - goto err_iclk; + mcbsp->tx_irq = platform_get_irq_byname(pdev, "tx"); + mcbsp->rx_irq = platform_get_irq_byname(pdev, "rx"); + + /* From OMAP4 there will be a single irq line */ + if (mcbsp->tx_irq == -ENXIO) + mcbsp->tx_irq = platform_get_irq(pdev, 0); + + res = platform_get_resource_byname(pdev, IORESOURCE_DMA, "rx"); + if (!res) { + dev_err(&pdev->dev, "%s:mcbsp%d has invalid rx DMA channel\n", + __func__, pdev->id); + ret = -ENODEV; + goto err_res; + } + mcbsp->dma_rx_sync = res->start; + + res = platform_get_resource_byname(pdev, IORESOURCE_DMA, "tx"); + if (!res) { + dev_err(&pdev->dev, "%s:mcbsp%d has invalid tx DMA channel\n", + __func__, pdev->id); + ret = -ENODEV; + goto err_res; } + mcbsp->dma_tx_sync = res->start; mcbsp->fclk = clk_get(&pdev->dev, "fck"); if (IS_ERR(mcbsp->fclk)) { ret = PTR_ERR(mcbsp->fclk); dev_err(&pdev->dev, "unable to get fck: %d\n", ret); - goto err_fclk; + goto err_res; } mcbsp->pdata = pdata; mcbsp->dev = &pdev->dev; mcbsp_ptr[id] = mcbsp; + mcbsp->mcbsp_config_type = pdata->mcbsp_config_type; platform_set_drvdata(pdev, mcbsp); + pm_runtime_enable(mcbsp->dev); /* Initialize mcbsp properties for OMAP34XX if needed / applicable */ omap34xx_device_init(mcbsp); return 0; -err_fclk: - clk_put(mcbsp->iclk); -err_iclk: +err_res: iounmap(mcbsp->io_base); err_ioremap: kfree(mcbsp); @@ -1839,7 +1929,6 @@ static int __devexit omap_mcbsp_remove(struct platform_device *pdev) omap34xx_device_exit(mcbsp); clk_put(mcbsp->fclk); - clk_put(mcbsp->iclk); iounmap(mcbsp->io_base); kfree(mcbsp); diff --git a/arch/arm/plat-omap/omap_device.c b/arch/arm/plat-omap/omap_device.c index 57adb270767..9bbda9acb73 100644 --- a/arch/arm/plat-omap/omap_device.c +++ b/arch/arm/plat-omap/omap_device.c @@ -83,9 +83,11 @@ #include <linux/err.h> #include <linux/io.h> #include <linux/clk.h> +#include <linux/clkdev.h> #include <plat/omap_device.h> #include <plat/omap_hwmod.h> +#include <plat/clock.h> /* These parameters are passed to _omap_device_{de,}activate() */ #define USE_WAKEUP_LAT 0 @@ -239,12 +241,12 @@ static inline struct omap_device *_find_by_pdev(struct platform_device *pdev) } /** - * _add_optional_clock_alias - Add clock alias for hwmod optional clocks + * _add_optional_clock_clkdev - Add clkdev entry for hwmod optional clocks * @od: struct omap_device *od * * For every optional clock present per hwmod per omap_device, this function - * adds an entry in the clocks list of the form <dev-id=dev_name, con-id=role> - * if an entry is already present in it with the form <dev-id=NULL, con-id=role> + * adds an entry in the clkdev table of the form <dev-id=dev_name, con-id=role> + * if it does not exist already. * * The function is called from inside omap_device_build_ss(), after * omap_device_register. @@ -254,25 +256,39 @@ static inline struct omap_device *_find_by_pdev(struct platform_device *pdev) * * No return value. */ -static void _add_optional_clock_alias(struct omap_device *od, +static void _add_optional_clock_clkdev(struct omap_device *od, struct omap_hwmod *oh) { int i; for (i = 0; i < oh->opt_clks_cnt; i++) { struct omap_hwmod_opt_clk *oc; - int r; + struct clk *r; + struct clk_lookup *l; oc = &oh->opt_clks[i]; if (!oc->_clk) continue; - r = clk_add_alias(oc->role, dev_name(&od->pdev.dev), - (char *)oc->clk, &od->pdev.dev); - if (r) - pr_err("omap_device: %s: clk_add_alias for %s failed\n", + r = clk_get_sys(dev_name(&od->pdev.dev), oc->role); + if (!IS_ERR(r)) + continue; /* clkdev entry exists */ + + r = omap_clk_get_by_name((char *)oc->clk); + if (IS_ERR(r)) { + pr_err("omap_device: %s: omap_clk_get_by_name for %s failed\n", + dev_name(&od->pdev.dev), oc->clk); + continue; + } + + l = clkdev_alloc(r, oc->role, dev_name(&od->pdev.dev)); + if (!l) { + pr_err("omap_device: %s: clkdev_alloc for %s failed\n", dev_name(&od->pdev.dev), oc->role); + return; + } + clkdev_add(l); } } @@ -480,7 +496,7 @@ struct omap_device *omap_device_build_ss(const char *pdev_name, int pdev_id, for (i = 0; i < oh_cnt; i++) { hwmods[i]->od = od; - _add_optional_clock_alias(od, hwmods[i]); + _add_optional_clock_clkdev(od, hwmods[i]); } if (ret) diff --git a/arch/arm/plat-omap/sram.c b/arch/arm/plat-omap/sram.c index 68fcc7dc56e..a3f50b34a90 100644 --- a/arch/arm/plat-omap/sram.c +++ b/arch/arm/plat-omap/sram.c @@ -316,7 +316,7 @@ u32 omap2_set_prcm(u32 dpll_ctrl_val, u32 sdrc_rfr_val, int bypass) } #endif -#ifdef CONFIG_ARCH_OMAP2420 +#ifdef CONFIG_SOC_OMAP2420 static int __init omap242x_sram_init(void) { _omap2_sram_ddr_init = omap_sram_push(omap242x_sram_ddr_init, @@ -337,7 +337,7 @@ static inline int omap242x_sram_init(void) } #endif -#ifdef CONFIG_ARCH_OMAP2430 +#ifdef CONFIG_SOC_OMAP2430 static int __init omap243x_sram_init(void) { _omap2_sram_ddr_init = omap_sram_push(omap243x_sram_ddr_init, @@ -409,20 +409,6 @@ static inline int omap34xx_sram_init(void) } #endif -#ifdef CONFIG_ARCH_OMAP4 -static int __init omap44xx_sram_init(void) -{ - printk(KERN_ERR "FIXME: %s not implemented\n", __func__); - - return -ENODEV; -} -#else -static inline int omap44xx_sram_init(void) -{ - return 0; -} -#endif - int __init omap_sram_init(void) { omap_detect_sram(); @@ -436,8 +422,6 @@ int __init omap_sram_init(void) omap243x_sram_init(); else if (cpu_is_omap34xx()) omap34xx_sram_init(); - else if (cpu_is_omap44xx()) - omap44xx_sram_init(); return 0; } diff --git a/drivers/Kconfig b/drivers/Kconfig index 9bfb71ff3a6..177c7d15693 100644 --- a/drivers/Kconfig +++ b/drivers/Kconfig @@ -117,4 +117,6 @@ source "drivers/staging/Kconfig" source "drivers/platform/Kconfig" source "drivers/clk/Kconfig" + +source "drivers/hwspinlock/Kconfig" endmenu diff --git a/drivers/Makefile b/drivers/Makefile index b423bb16c3a..3f135b6fb01 100644 --- a/drivers/Makefile +++ b/drivers/Makefile @@ -117,3 +117,5 @@ obj-y += platform/ obj-y += ieee802154/ #common clk code obj-y += clk/ + +obj-$(CONFIG_HWSPINLOCK) += hwspinlock/ diff --git a/drivers/hwspinlock/Kconfig b/drivers/hwspinlock/Kconfig new file mode 100644 index 00000000000..eb4af28f856 --- /dev/null +++ b/drivers/hwspinlock/Kconfig @@ -0,0 +1,22 @@ +# +# Generic HWSPINLOCK framework +# + +config HWSPINLOCK + tristate "Generic Hardware Spinlock framework" + help + Say y here to support the generic hardware spinlock framework. + You only need to enable this if you have hardware spinlock module + on your system (usually only relevant if your system has remote slave + coprocessors). + + If unsure, say N. + +config HWSPINLOCK_OMAP + tristate "OMAP Hardware Spinlock device" + depends on HWSPINLOCK && ARCH_OMAP4 + help + Say y here to support the OMAP Hardware Spinlock device (firstly + introduced in OMAP4). + + If unsure, say N. diff --git a/drivers/hwspinlock/Makefile b/drivers/hwspinlock/Makefile new file mode 100644 index 00000000000..5729a3f7ed3 --- /dev/null +++ b/drivers/hwspinlock/Makefile @@ -0,0 +1,6 @@ +# +# Generic Hardware Spinlock framework +# + +obj-$(CONFIG_HWSPINLOCK) += hwspinlock_core.o +obj-$(CONFIG_HWSPINLOCK_OMAP) += omap_hwspinlock.o diff --git a/drivers/hwspinlock/hwspinlock_core.c b/drivers/hwspinlock/hwspinlock_core.c new file mode 100644 index 00000000000..43a62714b4f --- /dev/null +++ b/drivers/hwspinlock/hwspinlock_core.c @@ -0,0 +1,548 @@ +/* + * Hardware spinlock framework + * + * Copyright (C) 2010 Texas Instruments Incorporated - http://www.ti.com + * + * Contact: Ohad Ben-Cohen <ohad@wizery.com> + * + * This program is free software; you can redistribute it and/or modify it + * under the terms of the GNU General Public License version 2 as published + * by the Free Software Foundation. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + */ + +#define pr_fmt(fmt) "%s: " fmt, __func__ + +#include <linux/kernel.h> +#include <linux/module.h> +#include <linux/spinlock.h> +#include <linux/types.h> +#include <linux/err.h> +#include <linux/jiffies.h> +#include <linux/radix-tree.h> +#include <linux/hwspinlock.h> +#include <linux/pm_runtime.h> + +#include "hwspinlock_internal.h" + +/* radix tree tags */ +#define HWSPINLOCK_UNUSED (0) /* tags an hwspinlock as unused */ + +/* + * A radix tree is used to maintain the available hwspinlock instances. + * The tree associates hwspinlock pointers with their integer key id, + * and provides easy-to-use API which makes the hwspinlock core code simple + * and easy to read. + * + * Radix trees are quick on lookups, and reasonably efficient in terms of + * storage, especially with high density usages such as this framework + * requires (a continuous range of integer keys, beginning with zero, is + * used as the ID's of the hwspinlock instances). + * + * The radix tree API supports tagging items in the tree, which this + * framework uses to mark unused hwspinlock instances (see the + * HWSPINLOCK_UNUSED tag above). As a result, the process of querying the + * tree, looking for an unused hwspinlock instance, is now reduced to a + * single radix tree API call. + */ +static RADIX_TREE(hwspinlock_tree, GFP_KERNEL); + +/* + * Synchronization of access to the tree is achieved using this spinlock, + * as the radix-tree API requires that users provide all synchronisation. + */ +static DEFINE_SPINLOCK(hwspinlock_tree_lock); + +/** + * __hwspin_trylock() - attempt to lock a specific hwspinlock + * @hwlock: an hwspinlock which we want to trylock + * @mode: controls whether local interrupts are disabled or not + * @flags: a pointer where the caller's interrupt state will be saved at (if + * requested) + * + * This function attempts to lock an hwspinlock, and will immediately + * fail if the hwspinlock is already taken. + * + * Upon a successful return from this function, preemption (and possibly + * interrupts) is disabled, so the caller must not sleep, and is advised to + * release the hwspinlock as soon as possible. This is required in order to + * minimize remote cores polling on the hardware interconnect. + * + * The user decides whether local interrupts are disabled or not, and if yes, + * whether he wants their previous state to be saved. It is up to the user + * to choose the appropriate @mode of operation, exactly the same way users + * should decide between spin_trylock, spin_trylock_irq and + * spin_trylock_irqsave. + * + * Returns 0 if we successfully locked the hwspinlock or -EBUSY if + * the hwspinlock was already taken. + * This function will never sleep. + */ +int __hwspin_trylock(struct hwspinlock *hwlock, int mode, unsigned long *flags) +{ + int ret; + + BUG_ON(!hwlock); + BUG_ON(!flags && mode == HWLOCK_IRQSTATE); + + /* + * This spin_lock{_irq, _irqsave} serves three purposes: + * + * 1. Disable preemption, in order to minimize the period of time + * in which the hwspinlock is taken. This is important in order + * to minimize the possible polling on the hardware interconnect + * by a remote user of this lock. + * 2. Make the hwspinlock SMP-safe (so we can take it from + * additional contexts on the local host). + * 3. Ensure that in_atomic/might_sleep checks catch potential + * problems with hwspinlock usage (e.g. scheduler checks like + * 'scheduling while atomic' etc.) + */ + if (mode == HWLOCK_IRQSTATE) + ret = spin_trylock_irqsave(&hwlock->lock, *flags); + else if (mode == HWLOCK_IRQ) + ret = spin_trylock_irq(&hwlock->lock); + else + ret = spin_trylock(&hwlock->lock); + + /* is lock already taken by another context on the local cpu ? */ + if (!ret) + return -EBUSY; + + /* try to take the hwspinlock device */ + ret = hwlock->ops->trylock(hwlock); + + /* if hwlock is already taken, undo spin_trylock_* and exit */ + if (!ret) { + if (mode == HWLOCK_IRQSTATE) + spin_unlock_irqrestore(&hwlock->lock, *flags); + else if (mode == HWLOCK_IRQ) + spin_unlock_irq(&hwlock->lock); + else + spin_unlock(&hwlock->lock); + + return -EBUSY; + } + + /* + * We can be sure the other core's memory operations + * are observable to us only _after_ we successfully take + * the hwspinlock, and we must make sure that subsequent memory + * operations (both reads and writes) will not be reordered before + * we actually took the hwspinlock. + * + * Note: the implicit memory barrier of the spinlock above is too + * early, so we need this additional explicit memory barrier. + */ + mb(); + + return 0; +} +EXPORT_SYMBOL_GPL(__hwspin_trylock); + +/** + * __hwspin_lock_timeout() - lock an hwspinlock with timeout limit + * @hwlock: the hwspinlock to be locked + * @timeout: timeout value in msecs + * @mode: mode which controls whether local interrupts are disabled or not + * @flags: a pointer to where the caller's interrupt state will be saved at (if + * requested) + * + * This function locks the given @hwlock. If the @hwlock + * is already taken, the function will busy loop waiting for it to + * be released, but give up after @timeout msecs have elapsed. + * + * Upon a successful return from this function, preemption is disabled + * (and possibly local interrupts, too), so the caller must not sleep, + * and is advised to release the hwspinlock as soon as possible. + * This is required in order to minimize remote cores polling on the + * hardware interconnect. + * + * The user decides whether local interrupts are disabled or not, and if yes, + * whether he wants their previous state to be saved. It is up to the user + * to choose the appropriate @mode of operation, exactly the same way users + * should decide between spin_lock, spin_lock_irq and spin_lock_irqsave. + * + * Returns 0 when the @hwlock was successfully taken, and an appropriate + * error code otherwise (most notably -ETIMEDOUT if the @hwlock is still + * busy after @timeout msecs). The function will never sleep. + */ +int __hwspin_lock_timeout(struct hwspinlock *hwlock, unsigned int to, + int mode, unsigned long *flags) +{ + int ret; + unsigned long expire; + + expire = msecs_to_jiffies(to) + jiffies; + + for (;;) { + /* Try to take the hwspinlock */ + ret = __hwspin_trylock(hwlock, mode, flags); + if (ret != -EBUSY) + break; + + /* + * The lock is already taken, let's check if the user wants + * us to try again + */ + if (time_is_before_eq_jiffies(expire)) + return -ETIMEDOUT; + + /* + * Allow platform-specific relax handlers to prevent + * hogging the interconnect (no sleeping, though) + */ + if (hwlock->ops->relax) + hwlock->ops->relax(hwlock); + } + + return ret; +} +EXPORT_SYMBOL_GPL(__hwspin_lock_timeout); + +/** + * __hwspin_unlock() - unlock a specific hwspinlock + * @hwlock: a previously-acquired hwspinlock which we want to unlock + * @mode: controls whether local interrupts needs to be restored or not + * @flags: previous caller's interrupt state to restore (if requested) + * + * This function will unlock a specific hwspinlock, enable preemption and + * (possibly) enable interrupts or restore their previous state. + * @hwlock must be already locked before calling this function: it is a bug + * to call unlock on a @hwlock that is already unlocked. + * + * The user decides whether local interrupts should be enabled or not, and + * if yes, whether he wants their previous state to be restored. It is up + * to the user to choose the appropriate @mode of operation, exactly the + * same way users decide between spin_unlock, spin_unlock_irq and + * spin_unlock_irqrestore. + * + * The function will never sleep. + */ +void __hwspin_unlock(struct hwspinlock *hwlock, int mode, unsigned long *flags) +{ + BUG_ON(!hwlock); + BUG_ON(!flags && mode == HWLOCK_IRQSTATE); + + /* + * We must make sure that memory operations (both reads and writes), + * done before unlocking the hwspinlock, will not be reordered + * after the lock is released. + * + * That's the purpose of this explicit memory barrier. + * + * Note: the memory barrier induced by the spin_unlock below is too + * late; the other core is going to access memory soon after it will + * take the hwspinlock, and by then we want to be sure our memory + * operations are already observable. + */ + mb(); + + hwlock->ops->unlock(hwlock); + + /* Undo the spin_trylock{_irq, _irqsave} called while locking */ + if (mode == HWLOCK_IRQSTATE) + spin_unlock_irqrestore(&hwlock->lock, *flags); + else if (mode == HWLOCK_IRQ) + spin_unlock_irq(&hwlock->lock); + else + spin_unlock(&hwlock->lock); +} +EXPORT_SYMBOL_GPL(__hwspin_unlock); + +/** + * hwspin_lock_register() - register a new hw spinlock + * @hwlock: hwspinlock to register. + * + * This function should be called from the underlying platform-specific + * implementation, to register a new hwspinlock instance. + * + * Can be called from an atomic context (will not sleep) but not from + * within interrupt context. + * + * Returns 0 on success, or an appropriate error code on failure + */ +int hwspin_lock_register(struct hwspinlock *hwlock) +{ + struct hwspinlock *tmp; + int ret; + + if (!hwlock || !hwlock->ops || + !hwlock->ops->trylock || !hwlock->ops->unlock) { + pr_err("invalid parameters\n"); + return -EINVAL; + } + + spin_lock_init(&hwlock->lock); + + spin_lock(&hwspinlock_tree_lock); + + ret = radix_tree_insert(&hwspinlock_tree, hwlock->id, hwlock); + if (ret) + goto out; + + /* mark this hwspinlock as available */ + tmp = radix_tree_tag_set(&hwspinlock_tree, hwlock->id, + HWSPINLOCK_UNUSED); + + /* self-sanity check which should never fail */ + WARN_ON(tmp != hwlock); + +out: + spin_unlock(&hwspinlock_tree_lock); + return ret; +} +EXPORT_SYMBOL_GPL(hwspin_lock_register); + +/** + * hwspin_lock_unregister() - unregister an hw spinlock + * @id: index of the specific hwspinlock to unregister + * + * This function should be called from the underlying platform-specific + * implementation, to unregister an existing (and unused) hwspinlock. + * + * Can be called from an atomic context (will not sleep) but not from + * within interrupt context. + * + * Returns the address of hwspinlock @id on success, or NULL on failure + */ +struct hwspinlock *hwspin_lock_unregister(unsigned int id) +{ + struct hwspinlock *hwlock = NULL; + int ret; + + spin_lock(&hwspinlock_tree_lock); + + /* make sure the hwspinlock is not in use (tag is set) */ + ret = radix_tree_tag_get(&hwspinlock_tree, id, HWSPINLOCK_UNUSED); + if (ret == 0) { + pr_err("hwspinlock %d still in use (or not present)\n", id); + goto out; + } + + hwlock = radix_tree_delete(&hwspinlock_tree, id); + if (!hwlock) { + pr_err("failed to delete hwspinlock %d\n", id); + goto out; + } + +out: + spin_unlock(&hwspinlock_tree_lock); + return hwlock; +} +EXPORT_SYMBOL_GPL(hwspin_lock_unregister); + +/** + * __hwspin_lock_request() - tag an hwspinlock as used and power it up + * + * This is an internal function that prepares an hwspinlock instance + * before it is given to the user. The function assumes that + * hwspinlock_tree_lock is taken. + * + * Returns 0 or positive to indicate success, and a negative value to + * indicate an error (with the appropriate error code) + */ +static int __hwspin_lock_request(struct hwspinlock *hwlock) +{ + struct hwspinlock *tmp; + int ret; + + /* prevent underlying implementation from being removed */ + if (!try_module_get(hwlock->owner)) { + dev_err(hwlock->dev, "%s: can't get owner\n", __func__); + return -EINVAL; + } + + /* notify PM core that power is now needed */ + ret = pm_runtime_get_sync(hwlock->dev); + if (ret < 0) { + dev_err(hwlock->dev, "%s: can't power on device\n", __func__); + return ret; + } + + /* mark hwspinlock as used, should not fail */ + tmp = radix_tree_tag_clear(&hwspinlock_tree, hwlock->id, + HWSPINLOCK_UNUSED); + + /* self-sanity check that should never fail */ + WARN_ON(tmp != hwlock); + + return ret; +} + +/** + * hwspin_lock_get_id() - retrieve id number of a given hwspinlock + * @hwlock: a valid hwspinlock instance + * + * Returns the id number of a given @hwlock, or -EINVAL if @hwlock is invalid. + */ +int hwspin_lock_get_id(struct hwspinlock *hwlock) +{ + if (!hwlock) { + pr_err("invalid hwlock\n"); + return -EINVAL; + } + + return hwlock->id; +} +EXPORT_SYMBOL_GPL(hwspin_lock_get_id); + +/** + * hwspin_lock_request() - request an hwspinlock + * + * This function should be called by users of the hwspinlock device, + * in order to dynamically assign them an unused hwspinlock. + * Usually the user of this lock will then have to communicate the lock's id + * to the remote core before it can be used for synchronization (to get the + * id of a given hwlock, use hwspin_lock_get_id()). + * + * Can be called from an atomic context (will not sleep) but not from + * within interrupt context (simply because there is no use case for + * that yet). + * + * Returns the address of the assigned hwspinlock, or NULL on error + */ +struct hwspinlock *hwspin_lock_request(void) +{ + struct hwspinlock *hwlock; + int ret; + + spin_lock(&hwspinlock_tree_lock); + + /* look for an unused lock */ + ret = radix_tree_gang_lookup_tag(&hwspinlock_tree, (void **)&hwlock, + 0, 1, HWSPINLOCK_UNUSED); + if (ret == 0) { + pr_warn("a free hwspinlock is not available\n"); + hwlock = NULL; + goto out; + } + + /* sanity check that should never fail */ + WARN_ON(ret > 1); + + /* mark as used and power up */ + ret = __hwspin_lock_request(hwlock); + if (ret < 0) + hwlock = NULL; + +out: + spin_unlock(&hwspinlock_tree_lock); + return hwlock; +} +EXPORT_SYMBOL_GPL(hwspin_lock_request); + +/** + * hwspin_lock_request_specific() - request for a specific hwspinlock + * @id: index of the specific hwspinlock that is requested + * + * This function should be called by users of the hwspinlock module, + * in order to assign them a specific hwspinlock. + * Usually early board code will be calling this function in order to + * reserve specific hwspinlock ids for predefined purposes. + * + * Can be called from an atomic context (will not sleep) but not from + * within interrupt context (simply because there is no use case for + * that yet). + * + * Returns the address of the assigned hwspinlock, or NULL on error + */ +struct hwspinlock *hwspin_lock_request_specific(unsigned int id) +{ + struct hwspinlock *hwlock; + int ret; + + spin_lock(&hwspinlock_tree_lock); + + /* make sure this hwspinlock exists */ + hwlock = radix_tree_lookup(&hwspinlock_tree, id); + if (!hwlock) { + pr_warn("hwspinlock %u does not exist\n", id); + goto out; + } + + /* sanity check (this shouldn't happen) */ + WARN_ON(hwlock->id != id); + + /* make sure this hwspinlock is unused */ + ret = radix_tree_tag_get(&hwspinlock_tree, id, HWSPINLOCK_UNUSED); + if (ret == 0) { + pr_warn("hwspinlock %u is already in use\n", id); + hwlock = NULL; + goto out; + } + + /* mark as used and power up */ + ret = __hwspin_lock_request(hwlock); + if (ret < 0) + hwlock = NULL; + +out: + spin_unlock(&hwspinlock_tree_lock); + return hwlock; +} +EXPORT_SYMBOL_GPL(hwspin_lock_request_specific); + +/** + * hwspin_lock_free() - free a specific hwspinlock + * @hwlock: the specific hwspinlock to free + * + * This function mark @hwlock as free again. + * Should only be called with an @hwlock that was retrieved from + * an earlier call to omap_hwspin_lock_request{_specific}. + * + * Can be called from an atomic context (will not sleep) but not from + * within interrupt context (simply because there is no use case for + * that yet). + * + * Returns 0 on success, or an appropriate error code on failure + */ +int hwspin_lock_free(struct hwspinlock *hwlock) +{ + struct hwspinlock *tmp; + int ret; + + if (!hwlock) { + pr_err("invalid hwlock\n"); + return -EINVAL; + } + + spin_lock(&hwspinlock_tree_lock); + + /* make sure the hwspinlock is used */ + ret = radix_tree_tag_get(&hwspinlock_tree, hwlock->id, + HWSPINLOCK_UNUSED); + if (ret == 1) { + dev_err(hwlock->dev, "%s: hwlock is already free\n", __func__); + dump_stack(); + ret = -EINVAL; + goto out; + } + + /* notify the underlying device that power is not needed */ + ret = pm_runtime_put(hwlock->dev); + if (ret < 0) + goto out; + + /* mark this hwspinlock as available */ + tmp = radix_tree_tag_set(&hwspinlock_tree, hwlock->id, + HWSPINLOCK_UNUSED); + + /* sanity check (this shouldn't happen) */ + WARN_ON(tmp != hwlock); + + module_put(hwlock->owner); + +out: + spin_unlock(&hwspinlock_tree_lock); + return ret; +} +EXPORT_SYMBOL_GPL(hwspin_lock_free); + +MODULE_LICENSE("GPL v2"); +MODULE_DESCRIPTION("Hardware spinlock interface"); +MODULE_AUTHOR("Ohad Ben-Cohen <ohad@wizery.com>"); diff --git a/drivers/hwspinlock/hwspinlock_internal.h b/drivers/hwspinlock/hwspinlock_internal.h new file mode 100644 index 00000000000..69935e6b93e --- /dev/null +++ b/drivers/hwspinlock/hwspinlock_internal.h @@ -0,0 +1,61 @@ +/* + * Hardware spinlocks internal header + * + * Copyright (C) 2010 Texas Instruments Incorporated - http://www.ti.com + * + * Contact: Ohad Ben-Cohen <ohad@wizery.com> + * + * This program is free software; you can redistribute it and/or modify it + * under the terms of the GNU General Public License version 2 as published + * by the Free Software Foundation. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + */ + +#ifndef __HWSPINLOCK_HWSPINLOCK_H +#define __HWSPINLOCK_HWSPINLOCK_H + +#include <linux/spinlock.h> +#include <linux/device.h> + +/** + * struct hwspinlock_ops - platform-specific hwspinlock handlers + * + * @trylock: make a single attempt to take the lock. returns 0 on + * failure and true on success. may _not_ sleep. + * @unlock: release the lock. always succeed. may _not_ sleep. + * @relax: optional, platform-specific relax handler, called by hwspinlock + * core while spinning on a lock, between two successive + * invocations of @trylock. may _not_ sleep. + */ +struct hwspinlock_ops { + int (*trylock)(struct hwspinlock *lock); + void (*unlock)(struct hwspinlock *lock); + void (*relax)(struct hwspinlock *lock); +}; + +/** + * struct hwspinlock - this struct represents a single hwspinlock instance + * + * @dev: underlying device, will be used to invoke runtime PM api + * @ops: platform-specific hwspinlock handlers + * @id: a global, unique, system-wide, index of the lock. + * @lock: initialized and used by hwspinlock core + * @owner: underlying implementation module, used to maintain module ref count + * + * Note: currently simplicity was opted for, but later we can squeeze some + * memory bytes by grouping the dev, ops and owner members in a single + * per-platform struct, and have all hwspinlocks point at it. + */ +struct hwspinlock { + struct device *dev; + const struct hwspinlock_ops *ops; + int id; + spinlock_t lock; + struct module *owner; +}; + +#endif /* __HWSPINLOCK_HWSPINLOCK_H */ diff --git a/drivers/hwspinlock/omap_hwspinlock.c b/drivers/hwspinlock/omap_hwspinlock.c new file mode 100644 index 00000000000..a8f02734c02 --- /dev/null +++ b/drivers/hwspinlock/omap_hwspinlock.c @@ -0,0 +1,231 @@ +/* + * OMAP hardware spinlock driver + * + * Copyright (C) 2010 Texas Instruments Incorporated - http://www.ti.com + * + * Contact: Simon Que <sque@ti.com> + * Hari Kanigeri <h-kanigeri2@ti.com> + * Ohad Ben-Cohen <ohad@wizery.com> + * + * This program is free software; you can redistribute it and/or + * modify it under the terms of the GNU General Public License + * version 2 as published by the Free Software Foundation. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * General Public License for more details. + */ + +#include <linux/kernel.h> +#include <linux/module.h> +#include <linux/device.h> +#include <linux/delay.h> +#include <linux/io.h> +#include <linux/bitops.h> +#include <linux/pm_runtime.h> +#include <linux/slab.h> +#include <linux/spinlock.h> +#include <linux/hwspinlock.h> +#include <linux/platform_device.h> + +#include "hwspinlock_internal.h" + +/* Spinlock register offsets */ +#define SYSSTATUS_OFFSET 0x0014 +#define LOCK_BASE_OFFSET 0x0800 + +#define SPINLOCK_NUMLOCKS_BIT_OFFSET (24) + +/* Possible values of SPINLOCK_LOCK_REG */ +#define SPINLOCK_NOTTAKEN (0) /* free */ +#define SPINLOCK_TAKEN (1) /* locked */ + +#define to_omap_hwspinlock(lock) \ + container_of(lock, struct omap_hwspinlock, lock) + +struct omap_hwspinlock { + struct hwspinlock lock; + void __iomem *addr; +}; + +struct omap_hwspinlock_state { + int num_locks; /* Total number of locks in system */ + void __iomem *io_base; /* Mapped base address */ +}; + +static int omap_hwspinlock_trylock(struct hwspinlock *lock) +{ + struct omap_hwspinlock *omap_lock = to_omap_hwspinlock(lock); + + /* attempt to acquire the lock by reading its value */ + return (SPINLOCK_NOTTAKEN == readl(omap_lock->addr)); +} + +static void omap_hwspinlock_unlock(struct hwspinlock *lock) +{ + struct omap_hwspinlock *omap_lock = to_omap_hwspinlock(lock); + + /* release the lock by writing 0 to it */ + writel(SPINLOCK_NOTTAKEN, omap_lock->addr); +} + +/* + * relax the OMAP interconnect while spinning on it. + * + * The specs recommended that the retry delay time will be + * just over half of the time that a requester would be + * expected to hold the lock. + * + * The number below is taken from an hardware specs example, + * obviously it is somewhat arbitrary. + */ +static void omap_hwspinlock_relax(struct hwspinlock *lock) +{ + ndelay(50); +} + +static const struct hwspinlock_ops omap_hwspinlock_ops = { + .trylock = omap_hwspinlock_trylock, + .unlock = omap_hwspinlock_unlock, + .relax = omap_hwspinlock_relax, +}; + +static int __devinit omap_hwspinlock_probe(struct platform_device *pdev) +{ + struct omap_hwspinlock *omap_lock; + struct omap_hwspinlock_state *state; + struct hwspinlock *lock; + struct resource *res; + void __iomem *io_base; + int i, ret; + + res = platform_get_resource(pdev, IORESOURCE_MEM, 0); + if (!res) + return -ENODEV; + + state = kzalloc(sizeof(*state), GFP_KERNEL); + if (!state) + return -ENOMEM; + + io_base = ioremap(res->start, resource_size(res)); + if (!io_base) { + ret = -ENOMEM; + goto free_state; + } + + /* Determine number of locks */ + i = readl(io_base + SYSSTATUS_OFFSET); + i >>= SPINLOCK_NUMLOCKS_BIT_OFFSET; + + /* one of the four lsb's must be set, and nothing else */ + if (hweight_long(i & 0xf) != 1 || i > 8) { + ret = -EINVAL; + goto iounmap_base; + } + + state->num_locks = i * 32; + state->io_base = io_base; + + platform_set_drvdata(pdev, state); + + /* + * runtime PM will make sure the clock of this module is + * enabled iff at least one lock is requested + */ + pm_runtime_enable(&pdev->dev); + + for (i = 0; i < state->num_locks; i++) { + omap_lock = kzalloc(sizeof(*omap_lock), GFP_KERNEL); + if (!omap_lock) { + ret = -ENOMEM; + goto free_locks; + } + + omap_lock->lock.dev = &pdev->dev; + omap_lock->lock.owner = THIS_MODULE; + omap_lock->lock.id = i; + omap_lock->lock.ops = &omap_hwspinlock_ops; + omap_lock->addr = io_base + LOCK_BASE_OFFSET + sizeof(u32) * i; + + ret = hwspin_lock_register(&omap_lock->lock); + if (ret) { + kfree(omap_lock); + goto free_locks; + } + } + + return 0; + +free_locks: + while (--i >= 0) { + lock = hwspin_lock_unregister(i); + /* this should't happen, but let's give our best effort */ + if (!lock) { + dev_err(&pdev->dev, "%s: cleanups failed\n", __func__); + continue; + } + omap_lock = to_omap_hwspinlock(lock); + kfree(omap_lock); + } + pm_runtime_disable(&pdev->dev); +iounmap_base: + iounmap(io_base); +free_state: + kfree(state); + return ret; +} + +static int omap_hwspinlock_remove(struct platform_device *pdev) +{ + struct omap_hwspinlock_state *state = platform_get_drvdata(pdev); + struct hwspinlock *lock; + struct omap_hwspinlock *omap_lock; + int i; + + for (i = 0; i < state->num_locks; i++) { + lock = hwspin_lock_unregister(i); + /* this shouldn't happen at this point. if it does, at least + * don't continue with the remove */ + if (!lock) { + dev_err(&pdev->dev, "%s: failed on %d\n", __func__, i); + return -EBUSY; + } + + omap_lock = to_omap_hwspinlock(lock); + kfree(omap_lock); + } + + pm_runtime_disable(&pdev->dev); + iounmap(state->io_base); + kfree(state); + + return 0; +} + +static struct platform_driver omap_hwspinlock_driver = { + .probe = omap_hwspinlock_probe, + .remove = omap_hwspinlock_remove, + .driver = { + .name = "omap_hwspinlock", + }, +}; + +static int __init omap_hwspinlock_init(void) +{ + return platform_driver_register(&omap_hwspinlock_driver); +} +/* board init code might need to reserve hwspinlocks for predefined purposes */ +postcore_initcall(omap_hwspinlock_init); + +static void __exit omap_hwspinlock_exit(void) +{ + platform_driver_unregister(&omap_hwspinlock_driver); +} +module_exit(omap_hwspinlock_exit); + +MODULE_LICENSE("GPL v2"); +MODULE_DESCRIPTION("Hardware spinlock driver for OMAP"); +MODULE_AUTHOR("Simon Que <sque@ti.com>"); +MODULE_AUTHOR("Hari Kanigeri <h-kanigeri2@ti.com>"); +MODULE_AUTHOR("Ohad Ben-Cohen <ohad@wizery.com>"); diff --git a/drivers/mmc/host/Kconfig b/drivers/mmc/host/Kconfig index afe8c6fa166..54f91321749 100644 --- a/drivers/mmc/host/Kconfig +++ b/drivers/mmc/host/Kconfig @@ -225,7 +225,7 @@ config MMC_OMAP config MMC_OMAP_HS tristate "TI OMAP High Speed Multimedia Card Interface support" - depends on ARCH_OMAP2430 || ARCH_OMAP3 || ARCH_OMAP4 + depends on SOC_OMAP2430 || ARCH_OMAP3 || ARCH_OMAP4 help This selects the TI OMAP High Speed Multimedia card Interface. If you have an OMAP2430 or OMAP3 board or OMAP4 board with a diff --git a/drivers/mmc/host/omap_hsmmc.c b/drivers/mmc/host/omap_hsmmc.c index 078fdf11af0..158c0ee53b2 100644 --- a/drivers/mmc/host/omap_hsmmc.c +++ b/drivers/mmc/host/omap_hsmmc.c @@ -118,7 +118,7 @@ #define MMC_TIMEOUT_MS 20 #define OMAP_MMC_MASTER_CLOCK 96000000 -#define DRIVER_NAME "mmci-omap-hs" +#define DRIVER_NAME "omap_hsmmc" /* Timeouts for entering power saving states on inactivity, msec */ #define OMAP_MMC_DISABLED_TIMEOUT 100 @@ -260,7 +260,7 @@ static int omap_hsmmc_1_set_power(struct device *dev, int slot, int power_on, return ret; } -static int omap_hsmmc_23_set_power(struct device *dev, int slot, int power_on, +static int omap_hsmmc_235_set_power(struct device *dev, int slot, int power_on, int vdd) { struct omap_hsmmc_host *host = @@ -316,6 +316,12 @@ static int omap_hsmmc_23_set_power(struct device *dev, int slot, int power_on, return ret; } +static int omap_hsmmc_4_set_power(struct device *dev, int slot, int power_on, + int vdd) +{ + return 0; +} + static int omap_hsmmc_1_set_sleep(struct device *dev, int slot, int sleep, int vdd, int cardsleep) { @@ -326,7 +332,7 @@ static int omap_hsmmc_1_set_sleep(struct device *dev, int slot, int sleep, return regulator_set_mode(host->vcc, mode); } -static int omap_hsmmc_23_set_sleep(struct device *dev, int slot, int sleep, +static int omap_hsmmc_235_set_sleep(struct device *dev, int slot, int sleep, int vdd, int cardsleep) { struct omap_hsmmc_host *host = @@ -365,6 +371,12 @@ static int omap_hsmmc_23_set_sleep(struct device *dev, int slot, int sleep, return regulator_enable(host->vcc_aux); } +static int omap_hsmmc_4_set_sleep(struct device *dev, int slot, int sleep, + int vdd, int cardsleep) +{ + return 0; +} + static int omap_hsmmc_reg_get(struct omap_hsmmc_host *host) { struct regulator *reg; @@ -379,10 +391,14 @@ static int omap_hsmmc_reg_get(struct omap_hsmmc_host *host) break; case OMAP_MMC2_DEVID: case OMAP_MMC3_DEVID: + case OMAP_MMC5_DEVID: /* Off-chip level shifting, or none */ - mmc_slot(host).set_power = omap_hsmmc_23_set_power; - mmc_slot(host).set_sleep = omap_hsmmc_23_set_sleep; + mmc_slot(host).set_power = omap_hsmmc_235_set_power; + mmc_slot(host).set_sleep = omap_hsmmc_235_set_sleep; break; + case OMAP_MMC4_DEVID: + mmc_slot(host).set_power = omap_hsmmc_4_set_power; + mmc_slot(host).set_sleep = omap_hsmmc_4_set_sleep; default: pr_err("MMC%d configuration not supported!\n", host->id); return -EINVAL; @@ -1555,7 +1571,7 @@ static void omap_hsmmc_set_ios(struct mmc_host *mmc, struct mmc_ios *ios) break; } - if (host->id == OMAP_MMC1_DEVID) { + if (host->pdata->controller_flags & OMAP_HSMMC_SUPPORTS_DUAL_VOLT) { /* Only MMC1 can interface at 3V without some flavor * of external transceiver; but they all handle 1.8V. */ @@ -1647,7 +1663,7 @@ static void omap_hsmmc_conf_bus_power(struct omap_hsmmc_host *host) u32 hctl, capa, value; /* Only MMC1 supports 3.0V */ - if (host->id == OMAP_MMC1_DEVID) { + if (host->pdata->controller_flags & OMAP_HSMMC_SUPPORTS_DUAL_VOLT) { hctl = SDVS30; capa = VS30 | VS18; } else { @@ -2101,14 +2117,14 @@ static int __init omap_hsmmc_probe(struct platform_device *pdev) /* we start off in DISABLED state */ host->dpm_state = DISABLED; - if (mmc_host_enable(host->mmc) != 0) { + if (clk_enable(host->iclk) != 0) { clk_put(host->iclk); clk_put(host->fclk); goto err1; } - if (clk_enable(host->iclk) != 0) { - mmc_host_disable(host->mmc); + if (mmc_host_enable(host->mmc) != 0) { + clk_disable(host->iclk); clk_put(host->iclk); clk_put(host->fclk); goto err1; diff --git a/drivers/mtd/nand/Kconfig b/drivers/mtd/nand/Kconfig index 450afc5df0b..4f6c06f1632 100644 --- a/drivers/mtd/nand/Kconfig +++ b/drivers/mtd/nand/Kconfig @@ -106,23 +106,6 @@ config MTD_NAND_OMAP2 help Support for NAND flash on Texas Instruments OMAP2 and OMAP3 platforms. -config MTD_NAND_OMAP_PREFETCH - bool "GPMC prefetch support for NAND Flash device" - depends on MTD_NAND_OMAP2 - default y - help - The NAND device can be accessed for Read/Write using GPMC PREFETCH engine - to improve the performance. - -config MTD_NAND_OMAP_PREFETCH_DMA - depends on MTD_NAND_OMAP_PREFETCH - bool "DMA mode" - default n - help - The GPMC PREFETCH engine can be configured eigther in MPU interrupt mode - or in DMA interrupt mode. - Say y for DMA mode or MPU mode will be used - config MTD_NAND_IDS tristate diff --git a/drivers/mtd/nand/omap2.c b/drivers/mtd/nand/omap2.c index 28af71c6183..7b8f1fffc52 100644 --- a/drivers/mtd/nand/omap2.c +++ b/drivers/mtd/nand/omap2.c @@ -11,6 +11,7 @@ #include <linux/platform_device.h> #include <linux/dma-mapping.h> #include <linux/delay.h> +#include <linux/interrupt.h> #include <linux/jiffies.h> #include <linux/sched.h> #include <linux/mtd/mtd.h> @@ -24,6 +25,7 @@ #include <plat/nand.h> #define DRIVER_NAME "omap2-nand" +#define OMAP_NAND_TIMEOUT_MS 5000 #define NAND_Ecc_P1e (1 << 0) #define NAND_Ecc_P2e (1 << 1) @@ -96,26 +98,19 @@ static const char *part_probes[] = { "cmdlinepart", NULL }; #endif -#ifdef CONFIG_MTD_NAND_OMAP_PREFETCH -static int use_prefetch = 1; - -/* "modprobe ... use_prefetch=0" etc */ -module_param(use_prefetch, bool, 0); -MODULE_PARM_DESC(use_prefetch, "enable/disable use of PREFETCH"); - -#ifdef CONFIG_MTD_NAND_OMAP_PREFETCH_DMA -static int use_dma = 1; +/* oob info generated runtime depending on ecc algorithm and layout selected */ +static struct nand_ecclayout omap_oobinfo; +/* Define some generic bad / good block scan pattern which are used + * while scanning a device for factory marked good / bad blocks + */ +static uint8_t scan_ff_pattern[] = { 0xff }; +static struct nand_bbt_descr bb_descrip_flashbased = { + .options = NAND_BBT_SCANEMPTY | NAND_BBT_SCANALLPAGES, + .offs = 0, + .len = 1, + .pattern = scan_ff_pattern, +}; -/* "modprobe ... use_dma=0" etc */ -module_param(use_dma, bool, 0); -MODULE_PARM_DESC(use_dma, "enable/disable use of DMA"); -#else -static const int use_dma; -#endif -#else -const int use_prefetch; -static const int use_dma; -#endif struct omap_nand_info { struct nand_hw_control controller; @@ -129,6 +124,13 @@ struct omap_nand_info { unsigned long phys_base; struct completion comp; int dma_ch; + int gpmc_irq; + enum { + OMAP_NAND_IO_READ = 0, /* read */ + OMAP_NAND_IO_WRITE, /* write */ + } iomode; + u_char *buf; + int buf_len; }; /** @@ -256,7 +258,8 @@ static void omap_read_buf_pref(struct mtd_info *mtd, u_char *buf, int len) } /* configure and start prefetch transfer */ - ret = gpmc_prefetch_enable(info->gpmc_cs, 0x0, len, 0x0); + ret = gpmc_prefetch_enable(info->gpmc_cs, + PREFETCH_FIFOTHRESHOLD_MAX, 0x0, len, 0x0); if (ret) { /* PFPW engine is busy, use cpu copy method */ if (info->nand.options & NAND_BUSWIDTH_16) @@ -288,9 +291,10 @@ static void omap_write_buf_pref(struct mtd_info *mtd, { struct omap_nand_info *info = container_of(mtd, struct omap_nand_info, mtd); - uint32_t pref_count = 0, w_count = 0; + uint32_t w_count = 0; int i = 0, ret = 0; u16 *p; + unsigned long tim, limit; /* take care of subpage writes */ if (len % 2 != 0) { @@ -300,7 +304,8 @@ static void omap_write_buf_pref(struct mtd_info *mtd, } /* configure and start prefetch transfer */ - ret = gpmc_prefetch_enable(info->gpmc_cs, 0x0, len, 0x1); + ret = gpmc_prefetch_enable(info->gpmc_cs, + PREFETCH_FIFOTHRESHOLD_MAX, 0x0, len, 0x1); if (ret) { /* PFPW engine is busy, use cpu copy method */ if (info->nand.options & NAND_BUSWIDTH_16) @@ -316,15 +321,17 @@ static void omap_write_buf_pref(struct mtd_info *mtd, iowrite16(*p++, info->nand.IO_ADDR_W); } /* wait for data to flushed-out before reset the prefetch */ - do { - pref_count = gpmc_read_status(GPMC_PREFETCH_COUNT); - } while (pref_count); + tim = 0; + limit = (loops_per_jiffy * + msecs_to_jiffies(OMAP_NAND_TIMEOUT_MS)); + while (gpmc_read_status(GPMC_PREFETCH_COUNT) && (tim++ < limit)) + cpu_relax(); + /* disable and stop the PFPW engine */ gpmc_prefetch_reset(info->gpmc_cs); } } -#ifdef CONFIG_MTD_NAND_OMAP_PREFETCH_DMA /* * omap_nand_dma_cb: callback on the completion of dma transfer * @lch: logical channel @@ -348,14 +355,15 @@ static inline int omap_nand_dma_transfer(struct mtd_info *mtd, void *addr, { struct omap_nand_info *info = container_of(mtd, struct omap_nand_info, mtd); - uint32_t prefetch_status = 0; enum dma_data_direction dir = is_write ? DMA_TO_DEVICE : DMA_FROM_DEVICE; dma_addr_t dma_addr; int ret; + unsigned long tim, limit; - /* The fifo depth is 64 bytes. We have a sync at each frame and frame - * length is 64 bytes. + /* The fifo depth is 64 bytes max. + * But configure the FIFO-threahold to 32 to get a sync at each frame + * and frame length is 32 bytes. */ int buf_len = len >> 6; @@ -396,9 +404,10 @@ static inline int omap_nand_dma_transfer(struct mtd_info *mtd, void *addr, OMAP24XX_DMA_GPMC, OMAP_DMA_SRC_SYNC); } /* configure and start prefetch transfer */ - ret = gpmc_prefetch_enable(info->gpmc_cs, 0x1, len, is_write); + ret = gpmc_prefetch_enable(info->gpmc_cs, + PREFETCH_FIFOTHRESHOLD_MAX, 0x1, len, is_write); if (ret) - /* PFPW engine is busy, use cpu copy methode */ + /* PFPW engine is busy, use cpu copy method */ goto out_copy; init_completion(&info->comp); @@ -407,10 +416,11 @@ static inline int omap_nand_dma_transfer(struct mtd_info *mtd, void *addr, /* setup and start DMA using dma_addr */ wait_for_completion(&info->comp); + tim = 0; + limit = (loops_per_jiffy * msecs_to_jiffies(OMAP_NAND_TIMEOUT_MS)); + while (gpmc_read_status(GPMC_PREFETCH_COUNT) && (tim++ < limit)) + cpu_relax(); - do { - prefetch_status = gpmc_read_status(GPMC_PREFETCH_COUNT); - } while (prefetch_status); /* disable and stop the PFPW engine */ gpmc_prefetch_reset(info->gpmc_cs); @@ -426,14 +436,6 @@ out_copy: : omap_write_buf8(mtd, (u_char *) addr, len); return 0; } -#else -static void omap_nand_dma_cb(int lch, u16 ch_status, void *data) {} -static inline int omap_nand_dma_transfer(struct mtd_info *mtd, void *addr, - unsigned int len, int is_write) -{ - return 0; -} -#endif /** * omap_read_buf_dma_pref - read data from NAND controller into buffer @@ -466,6 +468,157 @@ static void omap_write_buf_dma_pref(struct mtd_info *mtd, omap_nand_dma_transfer(mtd, (u_char *) buf, len, 0x1); } +/* + * omap_nand_irq - GMPC irq handler + * @this_irq: gpmc irq number + * @dev: omap_nand_info structure pointer is passed here + */ +static irqreturn_t omap_nand_irq(int this_irq, void *dev) +{ + struct omap_nand_info *info = (struct omap_nand_info *) dev; + u32 bytes; + u32 irq_stat; + + irq_stat = gpmc_read_status(GPMC_GET_IRQ_STATUS); + bytes = gpmc_read_status(GPMC_PREFETCH_FIFO_CNT); + bytes = bytes & 0xFFFC; /* io in multiple of 4 bytes */ + if (info->iomode == OMAP_NAND_IO_WRITE) { /* checks for write io */ + if (irq_stat & 0x2) + goto done; + + if (info->buf_len && (info->buf_len < bytes)) + bytes = info->buf_len; + else if (!info->buf_len) + bytes = 0; + iowrite32_rep(info->nand.IO_ADDR_W, + (u32 *)info->buf, bytes >> 2); + info->buf = info->buf + bytes; + info->buf_len -= bytes; + + } else { + ioread32_rep(info->nand.IO_ADDR_R, + (u32 *)info->buf, bytes >> 2); + info->buf = info->buf + bytes; + + if (irq_stat & 0x2) + goto done; + } + gpmc_cs_configure(info->gpmc_cs, GPMC_SET_IRQ_STATUS, irq_stat); + + return IRQ_HANDLED; + +done: + complete(&info->comp); + /* disable irq */ + gpmc_cs_configure(info->gpmc_cs, GPMC_ENABLE_IRQ, 0); + + /* clear status */ + gpmc_cs_configure(info->gpmc_cs, GPMC_SET_IRQ_STATUS, irq_stat); + + return IRQ_HANDLED; +} + +/* + * omap_read_buf_irq_pref - read data from NAND controller into buffer + * @mtd: MTD device structure + * @buf: buffer to store date + * @len: number of bytes to read + */ +static void omap_read_buf_irq_pref(struct mtd_info *mtd, u_char *buf, int len) +{ + struct omap_nand_info *info = container_of(mtd, + struct omap_nand_info, mtd); + int ret = 0; + + if (len <= mtd->oobsize) { + omap_read_buf_pref(mtd, buf, len); + return; + } + + info->iomode = OMAP_NAND_IO_READ; + info->buf = buf; + init_completion(&info->comp); + + /* configure and start prefetch transfer */ + ret = gpmc_prefetch_enable(info->gpmc_cs, + PREFETCH_FIFOTHRESHOLD_MAX/2, 0x0, len, 0x0); + if (ret) + /* PFPW engine is busy, use cpu copy method */ + goto out_copy; + + info->buf_len = len; + /* enable irq */ + gpmc_cs_configure(info->gpmc_cs, GPMC_ENABLE_IRQ, + (GPMC_IRQ_FIFOEVENTENABLE | GPMC_IRQ_COUNT_EVENT)); + + /* waiting for read to complete */ + wait_for_completion(&info->comp); + + /* disable and stop the PFPW engine */ + gpmc_prefetch_reset(info->gpmc_cs); + return; + +out_copy: + if (info->nand.options & NAND_BUSWIDTH_16) + omap_read_buf16(mtd, buf, len); + else + omap_read_buf8(mtd, buf, len); +} + +/* + * omap_write_buf_irq_pref - write buffer to NAND controller + * @mtd: MTD device structure + * @buf: data buffer + * @len: number of bytes to write + */ +static void omap_write_buf_irq_pref(struct mtd_info *mtd, + const u_char *buf, int len) +{ + struct omap_nand_info *info = container_of(mtd, + struct omap_nand_info, mtd); + int ret = 0; + unsigned long tim, limit; + + if (len <= mtd->oobsize) { + omap_write_buf_pref(mtd, buf, len); + return; + } + + info->iomode = OMAP_NAND_IO_WRITE; + info->buf = (u_char *) buf; + init_completion(&info->comp); + + /* configure and start prefetch transfer : size=24 */ + ret = gpmc_prefetch_enable(info->gpmc_cs, + (PREFETCH_FIFOTHRESHOLD_MAX * 3) / 8, 0x0, len, 0x1); + if (ret) + /* PFPW engine is busy, use cpu copy method */ + goto out_copy; + + info->buf_len = len; + /* enable irq */ + gpmc_cs_configure(info->gpmc_cs, GPMC_ENABLE_IRQ, + (GPMC_IRQ_FIFOEVENTENABLE | GPMC_IRQ_COUNT_EVENT)); + + /* waiting for write to complete */ + wait_for_completion(&info->comp); + /* wait for data to flushed-out before reset the prefetch */ + tim = 0; + limit = (loops_per_jiffy * msecs_to_jiffies(OMAP_NAND_TIMEOUT_MS)); + while (gpmc_read_status(GPMC_PREFETCH_COUNT) && (tim++ < limit)) + cpu_relax(); + + /* disable and stop the PFPW engine */ + gpmc_prefetch_reset(info->gpmc_cs); + return; + +out_copy: + if (info->nand.options & NAND_BUSWIDTH_16) + omap_write_buf16(mtd, buf, len); + else + omap_write_buf8(mtd, buf, len); +} + /** * omap_verify_buf - Verify chip data against buffer * @mtd: MTD device structure @@ -487,8 +640,6 @@ static int omap_verify_buf(struct mtd_info *mtd, const u_char * buf, int len) return 0; } -#ifdef CONFIG_MTD_NAND_OMAP_HWECC - /** * gen_true_ecc - This function will generate true ECC value * @ecc_buf: buffer to store ecc code @@ -708,8 +859,6 @@ static void omap_enable_hwecc(struct mtd_info *mtd, int mode) gpmc_enable_hwecc(info->gpmc_cs, mode, dev_width, info->nand.ecc.size); } -#endif - /** * omap_wait - wait until the command is done * @mtd: MTD device structure @@ -779,6 +928,7 @@ static int __devinit omap_nand_probe(struct platform_device *pdev) struct omap_nand_info *info; struct omap_nand_platform_data *pdata; int err; + int i, offset; pdata = pdev->dev.platform_data; if (pdata == NULL) { @@ -804,7 +954,7 @@ static int __devinit omap_nand_probe(struct platform_device *pdev) info->mtd.name = dev_name(&pdev->dev); info->mtd.owner = THIS_MODULE; - info->nand.options |= pdata->devsize ? NAND_BUSWIDTH_16 : 0; + info->nand.options = pdata->devsize; info->nand.options |= NAND_SKIP_BBTSCAN; /* NAND write protect off */ @@ -842,28 +992,13 @@ static int __devinit omap_nand_probe(struct platform_device *pdev) info->nand.chip_delay = 50; } - if (use_prefetch) { - + switch (pdata->xfer_type) { + case NAND_OMAP_PREFETCH_POLLED: info->nand.read_buf = omap_read_buf_pref; info->nand.write_buf = omap_write_buf_pref; - if (use_dma) { - err = omap_request_dma(OMAP24XX_DMA_GPMC, "NAND", - omap_nand_dma_cb, &info->comp, &info->dma_ch); - if (err < 0) { - info->dma_ch = -1; - printk(KERN_WARNING "DMA request failed." - " Non-dma data transfer mode\n"); - } else { - omap_set_dma_dest_burst_mode(info->dma_ch, - OMAP_DMA_DATA_BURST_16); - omap_set_dma_src_burst_mode(info->dma_ch, - OMAP_DMA_DATA_BURST_16); - - info->nand.read_buf = omap_read_buf_dma_pref; - info->nand.write_buf = omap_write_buf_dma_pref; - } - } - } else { + break; + + case NAND_OMAP_POLLED: if (info->nand.options & NAND_BUSWIDTH_16) { info->nand.read_buf = omap_read_buf16; info->nand.write_buf = omap_write_buf16; @@ -871,20 +1006,61 @@ static int __devinit omap_nand_probe(struct platform_device *pdev) info->nand.read_buf = omap_read_buf8; info->nand.write_buf = omap_write_buf8; } + break; + + case NAND_OMAP_PREFETCH_DMA: + err = omap_request_dma(OMAP24XX_DMA_GPMC, "NAND", + omap_nand_dma_cb, &info->comp, &info->dma_ch); + if (err < 0) { + info->dma_ch = -1; + dev_err(&pdev->dev, "DMA request failed!\n"); + goto out_release_mem_region; + } else { + omap_set_dma_dest_burst_mode(info->dma_ch, + OMAP_DMA_DATA_BURST_16); + omap_set_dma_src_burst_mode(info->dma_ch, + OMAP_DMA_DATA_BURST_16); + + info->nand.read_buf = omap_read_buf_dma_pref; + info->nand.write_buf = omap_write_buf_dma_pref; + } + break; + + case NAND_OMAP_PREFETCH_IRQ: + err = request_irq(pdata->gpmc_irq, + omap_nand_irq, IRQF_SHARED, "gpmc-nand", info); + if (err) { + dev_err(&pdev->dev, "requesting irq(%d) error:%d", + pdata->gpmc_irq, err); + goto out_release_mem_region; + } else { + info->gpmc_irq = pdata->gpmc_irq; + info->nand.read_buf = omap_read_buf_irq_pref; + info->nand.write_buf = omap_write_buf_irq_pref; + } + break; + + default: + dev_err(&pdev->dev, + "xfer_type(%d) not supported!\n", pdata->xfer_type); + err = -EINVAL; + goto out_release_mem_region; } - info->nand.verify_buf = omap_verify_buf; -#ifdef CONFIG_MTD_NAND_OMAP_HWECC - info->nand.ecc.bytes = 3; - info->nand.ecc.size = 512; - info->nand.ecc.calculate = omap_calculate_ecc; - info->nand.ecc.hwctl = omap_enable_hwecc; - info->nand.ecc.correct = omap_correct_data; - info->nand.ecc.mode = NAND_ECC_HW; + info->nand.verify_buf = omap_verify_buf; -#else - info->nand.ecc.mode = NAND_ECC_SOFT; -#endif + /* selsect the ecc type */ + if (pdata->ecc_opt == OMAP_ECC_HAMMING_CODE_DEFAULT) + info->nand.ecc.mode = NAND_ECC_SOFT; + else if ((pdata->ecc_opt == OMAP_ECC_HAMMING_CODE_HW) || + (pdata->ecc_opt == OMAP_ECC_HAMMING_CODE_HW_ROMCODE)) { + info->nand.ecc.bytes = 3; + info->nand.ecc.size = 512; + info->nand.ecc.calculate = omap_calculate_ecc; + info->nand.ecc.hwctl = omap_enable_hwecc; + info->nand.ecc.correct = omap_correct_data; + info->nand.ecc.mode = NAND_ECC_HW; + } /* DIP switches on some boards change between 8 and 16 bit * bus widths for flash. Try the other width if the first try fails. @@ -897,6 +1073,26 @@ static int __devinit omap_nand_probe(struct platform_device *pdev) } } + /* rom code layout */ + if (pdata->ecc_opt == OMAP_ECC_HAMMING_CODE_HW_ROMCODE) { + + if (info->nand.options & NAND_BUSWIDTH_16) + offset = 2; + else { + offset = 1; + info->nand.badblock_pattern = &bb_descrip_flashbased; + } + omap_oobinfo.eccbytes = 3 * (info->mtd.oobsize/16); + for (i = 0; i < omap_oobinfo.eccbytes; i++) + omap_oobinfo.eccpos[i] = i+offset; + + omap_oobinfo.oobfree->offset = offset + omap_oobinfo.eccbytes; + omap_oobinfo.oobfree->length = info->mtd.oobsize - + (offset + omap_oobinfo.eccbytes); + + info->nand.ecc.layout = &omap_oobinfo; + } + #ifdef CONFIG_MTD_PARTITIONS err = parse_mtd_partitions(&info->mtd, part_probes, &info->parts, 0); if (err > 0) @@ -926,9 +1122,12 @@ static int omap_nand_remove(struct platform_device *pdev) mtd); platform_set_drvdata(pdev, NULL); - if (use_dma) + if (info->dma_ch != -1) omap_free_dma(info->dma_ch); + if (info->gpmc_irq) + free_irq(info->gpmc_irq, info); + /* Release NAND device, its internal structures and partitions */ nand_release(&info->mtd); iounmap(info->nand.IO_ADDR_R); @@ -947,16 +1146,8 @@ static struct platform_driver omap_nand_driver = { static int __init omap_nand_init(void) { - printk(KERN_INFO "%s driver initializing\n", DRIVER_NAME); + pr_info("%s driver initializing\n", DRIVER_NAME); - /* This check is required if driver is being - * loaded run time as a module - */ - if ((1 == use_dma) && (0 == use_prefetch)) { - printk(KERN_INFO"Wrong parameters: 'use_dma' can not be 1 " - "without use_prefetch'. Prefetch will not be" - " used in either mode (mpu or dma)\n"); - } return platform_driver_register(&omap_nand_driver); } diff --git a/drivers/mtd/onenand/omap2.c b/drivers/mtd/onenand/omap2.c index c849cacf4b2..14a49abe057 100644 --- a/drivers/mtd/onenand/omap2.c +++ b/drivers/mtd/onenand/omap2.c @@ -63,7 +63,7 @@ struct omap2_onenand { struct completion dma_done; int dma_channel; int freq; - int (*setup)(void __iomem *base, int freq); + int (*setup)(void __iomem *base, int *freq_ptr); struct regulator *regulator; }; @@ -148,11 +148,9 @@ static int omap2_onenand_wait(struct mtd_info *mtd, int state) wait_err("controller error", state, ctrl, intr); return -EIO; } - if ((intr & intr_flags) != intr_flags) { - wait_err("timeout", state, ctrl, intr); - return -EIO; - } - return 0; + if ((intr & intr_flags) == intr_flags) + return 0; + /* Continue in wait for interrupt branch */ } if (state != FL_READING) { @@ -581,7 +579,7 @@ static int __adjust_timing(struct device *dev, void *data) /* DMA is not in use so this is all that is needed */ /* Revisit for OMAP3! */ - ret = c->setup(c->onenand.base, c->freq); + ret = c->setup(c->onenand.base, &c->freq); return ret; } @@ -673,7 +671,7 @@ static int __devinit omap2_onenand_probe(struct platform_device *pdev) } if (pdata->onenand_setup != NULL) { - r = pdata->onenand_setup(c->onenand.base, c->freq); + r = pdata->onenand_setup(c->onenand.base, &c->freq); if (r < 0) { dev_err(&pdev->dev, "Onenand platform setup failed: " "%d\n", r); @@ -718,8 +716,8 @@ static int __devinit omap2_onenand_probe(struct platform_device *pdev) } dev_info(&pdev->dev, "initializing on CS%d, phys base 0x%08lx, virtual " - "base %p\n", c->gpmc_cs, c->phys_base, - c->onenand.base); + "base %p, freq %d MHz\n", c->gpmc_cs, c->phys_base, + c->onenand.base, c->freq); c->pdev = pdev; c->mtd.name = dev_name(&pdev->dev); @@ -754,24 +752,6 @@ static int __devinit omap2_onenand_probe(struct platform_device *pdev) if ((r = onenand_scan(&c->mtd, 1)) < 0) goto err_release_regulator; - switch ((c->onenand.version_id >> 4) & 0xf) { - case 0: - c->freq = 40; - break; - case 1: - c->freq = 54; - break; - case 2: - c->freq = 66; - break; - case 3: - c->freq = 83; - break; - case 4: - c->freq = 104; - break; - } - #ifdef CONFIG_MTD_PARTITIONS r = parse_mtd_partitions(&c->mtd, part_probes, &c->parts, 0); if (r > 0) diff --git a/drivers/spi/omap2_mcspi.c b/drivers/spi/omap2_mcspi.c index abb1ffbf3d2..36501adc125 100644 --- a/drivers/spi/omap2_mcspi.c +++ b/drivers/spi/omap2_mcspi.c @@ -3,7 +3,7 @@ * * Copyright (C) 2005, 2006 Nokia Corporation * Author: Samuel Ortiz <samuel.ortiz@nokia.com> and - * Juha Yrjölä <juha.yrjola@nokia.com> + * Juha Yrj�l� <juha.yrjola@nokia.com> * * This program is free software; you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -33,6 +33,7 @@ #include <linux/clk.h> #include <linux/io.h> #include <linux/slab.h> +#include <linux/pm_runtime.h> #include <linux/spi/spi.h> @@ -46,7 +47,6 @@ #define OMAP2_MCSPI_MAX_CTRL 4 #define OMAP2_MCSPI_REVISION 0x00 -#define OMAP2_MCSPI_SYSCONFIG 0x10 #define OMAP2_MCSPI_SYSSTATUS 0x14 #define OMAP2_MCSPI_IRQSTATUS 0x18 #define OMAP2_MCSPI_IRQENABLE 0x1c @@ -63,13 +63,6 @@ /* per-register bitmasks: */ -#define OMAP2_MCSPI_SYSCONFIG_SMARTIDLE BIT(4) -#define OMAP2_MCSPI_SYSCONFIG_ENAWAKEUP BIT(2) -#define OMAP2_MCSPI_SYSCONFIG_AUTOIDLE BIT(0) -#define OMAP2_MCSPI_SYSCONFIG_SOFTRESET BIT(1) - -#define OMAP2_MCSPI_SYSSTATUS_RESETDONE BIT(0) - #define OMAP2_MCSPI_MODULCTRL_SINGLE BIT(0) #define OMAP2_MCSPI_MODULCTRL_MS BIT(2) #define OMAP2_MCSPI_MODULCTRL_STEST BIT(3) @@ -122,13 +115,12 @@ struct omap2_mcspi { spinlock_t lock; struct list_head msg_queue; struct spi_master *master; - struct clk *ick; - struct clk *fck; /* Virtual base address of the controller */ void __iomem *base; unsigned long phys; /* SPI1 has 4 channels, while SPI2 has 2 */ struct omap2_mcspi_dma *dma_channels; + struct device *dev; }; struct omap2_mcspi_cs { @@ -144,7 +136,6 @@ struct omap2_mcspi_cs { * corresponding registers are modified. */ struct omap2_mcspi_regs { - u32 sysconfig; u32 modulctrl; u32 wakeupenable; struct list_head cs; @@ -268,9 +259,6 @@ static void omap2_mcspi_restore_ctx(struct omap2_mcspi *mcspi) mcspi_write_reg(spi_cntrl, OMAP2_MCSPI_MODULCTRL, omap2_mcspi_ctx[spi_cntrl->bus_num - 1].modulctrl); - mcspi_write_reg(spi_cntrl, OMAP2_MCSPI_SYSCONFIG, - omap2_mcspi_ctx[spi_cntrl->bus_num - 1].sysconfig); - mcspi_write_reg(spi_cntrl, OMAP2_MCSPI_WAKEUPENABLE, omap2_mcspi_ctx[spi_cntrl->bus_num - 1].wakeupenable); @@ -280,20 +268,12 @@ static void omap2_mcspi_restore_ctx(struct omap2_mcspi *mcspi) } static void omap2_mcspi_disable_clocks(struct omap2_mcspi *mcspi) { - clk_disable(mcspi->ick); - clk_disable(mcspi->fck); + pm_runtime_put_sync(mcspi->dev); } static int omap2_mcspi_enable_clocks(struct omap2_mcspi *mcspi) { - if (clk_enable(mcspi->ick)) - return -ENODEV; - if (clk_enable(mcspi->fck)) - return -ENODEV; - - omap2_mcspi_restore_ctx(mcspi); - - return 0; + return pm_runtime_get_sync(mcspi->dev); } static int mcspi_wait_for_reg_bit(void __iomem *reg, unsigned long bit) @@ -819,8 +799,9 @@ static int omap2_mcspi_setup(struct spi_device *spi) return ret; } - if (omap2_mcspi_enable_clocks(mcspi)) - return -ENODEV; + ret = omap2_mcspi_enable_clocks(mcspi); + if (ret < 0) + return ret; ret = omap2_mcspi_setup_transfer(spi, NULL); omap2_mcspi_disable_clocks(mcspi); @@ -863,10 +844,11 @@ static void omap2_mcspi_work(struct work_struct *work) struct omap2_mcspi *mcspi; mcspi = container_of(work, struct omap2_mcspi, work); - spin_lock_irq(&mcspi->lock); - if (omap2_mcspi_enable_clocks(mcspi)) - goto out; + if (omap2_mcspi_enable_clocks(mcspi) < 0) + return; + + spin_lock_irq(&mcspi->lock); /* We only enable one channel at a time -- the one whose message is * at the head of the queue -- although this controller would gladly @@ -979,10 +961,9 @@ static void omap2_mcspi_work(struct work_struct *work) spin_lock_irq(&mcspi->lock); } - omap2_mcspi_disable_clocks(mcspi); - -out: spin_unlock_irq(&mcspi->lock); + + omap2_mcspi_disable_clocks(mcspi); } static int omap2_mcspi_transfer(struct spi_device *spi, struct spi_message *m) @@ -1058,25 +1039,15 @@ static int omap2_mcspi_transfer(struct spi_device *spi, struct spi_message *m) return 0; } -static int __init omap2_mcspi_reset(struct omap2_mcspi *mcspi) +static int __init omap2_mcspi_master_setup(struct omap2_mcspi *mcspi) { struct spi_master *master = mcspi->master; u32 tmp; + int ret = 0; - if (omap2_mcspi_enable_clocks(mcspi)) - return -1; - - mcspi_write_reg(master, OMAP2_MCSPI_SYSCONFIG, - OMAP2_MCSPI_SYSCONFIG_SOFTRESET); - do { - tmp = mcspi_read_reg(master, OMAP2_MCSPI_SYSSTATUS); - } while (!(tmp & OMAP2_MCSPI_SYSSTATUS_RESETDONE)); - - tmp = OMAP2_MCSPI_SYSCONFIG_AUTOIDLE | - OMAP2_MCSPI_SYSCONFIG_ENAWAKEUP | - OMAP2_MCSPI_SYSCONFIG_SMARTIDLE; - mcspi_write_reg(master, OMAP2_MCSPI_SYSCONFIG, tmp); - omap2_mcspi_ctx[master->bus_num - 1].sysconfig = tmp; + ret = omap2_mcspi_enable_clocks(mcspi); + if (ret < 0) + return ret; tmp = OMAP2_MCSPI_WAKEUPENABLE_WKEN; mcspi_write_reg(master, OMAP2_MCSPI_WAKEUPENABLE, tmp); @@ -1087,91 +1058,26 @@ static int __init omap2_mcspi_reset(struct omap2_mcspi *mcspi) return 0; } -static u8 __initdata spi1_rxdma_id [] = { - OMAP24XX_DMA_SPI1_RX0, - OMAP24XX_DMA_SPI1_RX1, - OMAP24XX_DMA_SPI1_RX2, - OMAP24XX_DMA_SPI1_RX3, -}; - -static u8 __initdata spi1_txdma_id [] = { - OMAP24XX_DMA_SPI1_TX0, - OMAP24XX_DMA_SPI1_TX1, - OMAP24XX_DMA_SPI1_TX2, - OMAP24XX_DMA_SPI1_TX3, -}; - -static u8 __initdata spi2_rxdma_id[] = { - OMAP24XX_DMA_SPI2_RX0, - OMAP24XX_DMA_SPI2_RX1, -}; - -static u8 __initdata spi2_txdma_id[] = { - OMAP24XX_DMA_SPI2_TX0, - OMAP24XX_DMA_SPI2_TX1, -}; - -#if defined(CONFIG_ARCH_OMAP2430) || defined(CONFIG_ARCH_OMAP3) \ - || defined(CONFIG_ARCH_OMAP4) -static u8 __initdata spi3_rxdma_id[] = { - OMAP24XX_DMA_SPI3_RX0, - OMAP24XX_DMA_SPI3_RX1, -}; +static int omap_mcspi_runtime_resume(struct device *dev) +{ + struct omap2_mcspi *mcspi; + struct spi_master *master; -static u8 __initdata spi3_txdma_id[] = { - OMAP24XX_DMA_SPI3_TX0, - OMAP24XX_DMA_SPI3_TX1, -}; -#endif + master = dev_get_drvdata(dev); + mcspi = spi_master_get_devdata(master); + omap2_mcspi_restore_ctx(mcspi); -#if defined(CONFIG_ARCH_OMAP3) || defined(CONFIG_ARCH_OMAP4) -static u8 __initdata spi4_rxdma_id[] = { - OMAP34XX_DMA_SPI4_RX0, -}; + return 0; +} -static u8 __initdata spi4_txdma_id[] = { - OMAP34XX_DMA_SPI4_TX0, -}; -#endif static int __init omap2_mcspi_probe(struct platform_device *pdev) { struct spi_master *master; + struct omap2_mcspi_platform_config *pdata = pdev->dev.platform_data; struct omap2_mcspi *mcspi; struct resource *r; int status = 0, i; - const u8 *rxdma_id, *txdma_id; - unsigned num_chipselect; - - switch (pdev->id) { - case 1: - rxdma_id = spi1_rxdma_id; - txdma_id = spi1_txdma_id; - num_chipselect = 4; - break; - case 2: - rxdma_id = spi2_rxdma_id; - txdma_id = spi2_txdma_id; - num_chipselect = 2; - break; -#if defined(CONFIG_ARCH_OMAP2430) || defined(CONFIG_ARCH_OMAP3) \ - || defined(CONFIG_ARCH_OMAP4) - case 3: - rxdma_id = spi3_rxdma_id; - txdma_id = spi3_txdma_id; - num_chipselect = 2; - break; -#endif -#if defined(CONFIG_ARCH_OMAP3) || defined(CONFIG_ARCH_OMAP4) - case 4: - rxdma_id = spi4_rxdma_id; - txdma_id = spi4_txdma_id; - num_chipselect = 1; - break; -#endif - default: - return -EINVAL; - } master = spi_alloc_master(&pdev->dev, sizeof *mcspi); if (master == NULL) { @@ -1188,7 +1094,7 @@ static int __init omap2_mcspi_probe(struct platform_device *pdev) master->setup = omap2_mcspi_setup; master->transfer = omap2_mcspi_transfer; master->cleanup = omap2_mcspi_cleanup; - master->num_chipselect = num_chipselect; + master->num_chipselect = pdata->num_cs; dev_set_drvdata(&pdev->dev, master); @@ -1206,49 +1112,62 @@ static int __init omap2_mcspi_probe(struct platform_device *pdev) goto err1; } + r->start += pdata->regs_offset; + r->end += pdata->regs_offset; mcspi->phys = r->start; mcspi->base = ioremap(r->start, r->end - r->start + 1); if (!mcspi->base) { dev_dbg(&pdev->dev, "can't ioremap MCSPI\n"); status = -ENOMEM; - goto err1aa; + goto err2; } + mcspi->dev = &pdev->dev; INIT_WORK(&mcspi->work, omap2_mcspi_work); spin_lock_init(&mcspi->lock); INIT_LIST_HEAD(&mcspi->msg_queue); INIT_LIST_HEAD(&omap2_mcspi_ctx[master->bus_num - 1].cs); - mcspi->ick = clk_get(&pdev->dev, "ick"); - if (IS_ERR(mcspi->ick)) { - dev_dbg(&pdev->dev, "can't get mcspi_ick\n"); - status = PTR_ERR(mcspi->ick); - goto err1a; - } - mcspi->fck = clk_get(&pdev->dev, "fck"); - if (IS_ERR(mcspi->fck)) { - dev_dbg(&pdev->dev, "can't get mcspi_fck\n"); - status = PTR_ERR(mcspi->fck); - goto err2; - } - mcspi->dma_channels = kcalloc(master->num_chipselect, sizeof(struct omap2_mcspi_dma), GFP_KERNEL); if (mcspi->dma_channels == NULL) - goto err3; + goto err2; + + for (i = 0; i < master->num_chipselect; i++) { + char dma_ch_name[14]; + struct resource *dma_res; + + sprintf(dma_ch_name, "rx%d", i); + dma_res = platform_get_resource_byname(pdev, IORESOURCE_DMA, + dma_ch_name); + if (!dma_res) { + dev_dbg(&pdev->dev, "cannot get DMA RX channel\n"); + status = -ENODEV; + break; + } - for (i = 0; i < num_chipselect; i++) { mcspi->dma_channels[i].dma_rx_channel = -1; - mcspi->dma_channels[i].dma_rx_sync_dev = rxdma_id[i]; + mcspi->dma_channels[i].dma_rx_sync_dev = dma_res->start; + sprintf(dma_ch_name, "tx%d", i); + dma_res = platform_get_resource_byname(pdev, IORESOURCE_DMA, + dma_ch_name); + if (!dma_res) { + dev_dbg(&pdev->dev, "cannot get DMA TX channel\n"); + status = -ENODEV; + break; + } + mcspi->dma_channels[i].dma_tx_channel = -1; - mcspi->dma_channels[i].dma_tx_sync_dev = txdma_id[i]; + mcspi->dma_channels[i].dma_tx_sync_dev = dma_res->start; } - if (omap2_mcspi_reset(mcspi) < 0) - goto err4; + pm_runtime_enable(&pdev->dev); + + if (status || omap2_mcspi_master_setup(mcspi) < 0) + goto err3; status = spi_register_master(master); if (status < 0) @@ -1257,17 +1176,13 @@ static int __init omap2_mcspi_probe(struct platform_device *pdev) return status; err4: - kfree(mcspi->dma_channels); + spi_master_put(master); err3: - clk_put(mcspi->fck); + kfree(mcspi->dma_channels); err2: - clk_put(mcspi->ick); -err1a: - iounmap(mcspi->base); -err1aa: release_mem_region(r->start, (r->end - r->start) + 1); + iounmap(mcspi->base); err1: - spi_master_put(master); return status; } @@ -1283,9 +1198,7 @@ static int __exit omap2_mcspi_remove(struct platform_device *pdev) mcspi = spi_master_get_devdata(master); dma_channels = mcspi->dma_channels; - clk_put(mcspi->fck); - clk_put(mcspi->ick); - + omap2_mcspi_disable_clocks(mcspi); r = platform_get_resource(pdev, IORESOURCE_MEM, 0); release_mem_region(r->start, (r->end - r->start) + 1); @@ -1336,6 +1249,7 @@ static int omap2_mcspi_resume(struct device *dev) static const struct dev_pm_ops omap2_mcspi_pm_ops = { .resume = omap2_mcspi_resume, + .runtime_resume = omap_mcspi_runtime_resume, }; static struct platform_driver omap2_mcspi_driver = { diff --git a/drivers/usb/musb/musb_core.c b/drivers/usb/musb/musb_core.c index a914010d9d1..630ae7f3cd4 100644 --- a/drivers/usb/musb/musb_core.c +++ b/drivers/usb/musb/musb_core.c @@ -1530,7 +1530,7 @@ static int __init musb_core_init(u16 musb_type, struct musb *musb) /*-------------------------------------------------------------------------*/ -#if defined(CONFIG_ARCH_OMAP2430) || defined(CONFIG_ARCH_OMAP3430) || \ +#if defined(CONFIG_SOC_OMAP2430) || defined(CONFIG_SOC_OMAP3430) || \ defined(CONFIG_ARCH_OMAP4) || defined(CONFIG_ARCH_U8500) || \ defined(CONFIG_ARCH_U5500) diff --git a/drivers/usb/musb/musb_core.h b/drivers/usb/musb/musb_core.h index 4f0dd2ed396..4bd9e2145ee 100644 --- a/drivers/usb/musb/musb_core.h +++ b/drivers/usb/musb/musb_core.h @@ -212,8 +212,8 @@ enum musb_g_ep0_state { * directly with the "flat" model, or after setting up an index register. */ -#if defined(CONFIG_ARCH_DAVINCI) || defined(CONFIG_ARCH_OMAP2430) \ - || defined(CONFIG_ARCH_OMAP3430) || defined(CONFIG_BLACKFIN) \ +#if defined(CONFIG_ARCH_DAVINCI) || defined(CONFIG_SOC_OMAP2430) \ + || defined(CONFIG_SOC_OMAP3430) || defined(CONFIG_BLACKFIN) \ || defined(CONFIG_ARCH_OMAP4) /* REVISIT indexed access seemed to * misbehave (on DaVinci) for at least peripheral IN ... diff --git a/drivers/usb/musb/musbhsdma.h b/drivers/usb/musb/musbhsdma.h index 21056c924c7..320fd4afb93 100644 --- a/drivers/usb/musb/musbhsdma.h +++ b/drivers/usb/musb/musbhsdma.h @@ -31,7 +31,7 @@ * */ -#if defined(CONFIG_ARCH_OMAP2430) || defined(CONFIG_ARCH_OMAP3430) +#if defined(CONFIG_SOC_OMAP2430) || defined(CONFIG_SOC_OMAP3430) #include "omap2430.h" #endif diff --git a/drivers/usb/otg/isp1301_omap.c b/drivers/usb/otg/isp1301_omap.c index e00fa1b22ec..8c6fdef61d1 100644 --- a/drivers/usb/otg/isp1301_omap.c +++ b/drivers/usb/otg/isp1301_omap.c @@ -1510,7 +1510,7 @@ isp1301_start_hnp(struct otg_transceiver *dev) /*-------------------------------------------------------------------------*/ -static int __init +static int __devinit isp1301_probe(struct i2c_client *i2c, const struct i2c_device_id *id) { int status; diff --git a/drivers/w1/masters/Kconfig b/drivers/w1/masters/Kconfig index 80b3b123dd7..7c608c5ccf8 100644 --- a/drivers/w1/masters/Kconfig +++ b/drivers/w1/masters/Kconfig @@ -60,7 +60,7 @@ config W1_MASTER_GPIO config HDQ_MASTER_OMAP tristate "OMAP HDQ driver" - depends on ARCH_OMAP2430 || ARCH_OMAP3 + depends on SOC_OMAP2430 || ARCH_OMAP3 help Say Y here if you want support for the 1-wire or HDQ Interface on an OMAP processor. diff --git a/drivers/watchdog/omap_wdt.c b/drivers/watchdog/omap_wdt.c index 3dd4971160e..2b4acb86c19 100644 --- a/drivers/watchdog/omap_wdt.c +++ b/drivers/watchdog/omap_wdt.c @@ -124,6 +124,8 @@ static void omap_wdt_set_timeout(struct omap_wdt_dev *wdev) u32 pre_margin = GET_WLDR_VAL(timer_margin); void __iomem *base = wdev->base; + pm_runtime_get_sync(wdev->dev); + /* just count up at 32 KHz */ while (__raw_readl(base + OMAP_WATCHDOG_WPS) & 0x04) cpu_relax(); @@ -131,6 +133,8 @@ static void omap_wdt_set_timeout(struct omap_wdt_dev *wdev) __raw_writel(pre_margin, base + OMAP_WATCHDOG_LDR); while (__raw_readl(base + OMAP_WATCHDOG_WPS) & 0x04) cpu_relax(); + + pm_runtime_put_sync(wdev->dev); } /* @@ -160,6 +164,8 @@ static int omap_wdt_open(struct inode *inode, struct file *file) omap_wdt_ping(wdev); /* trigger loading of new timeout value */ omap_wdt_enable(wdev); + pm_runtime_put_sync(wdev->dev); + return nonseekable_open(inode, file); } @@ -171,6 +177,7 @@ static int omap_wdt_release(struct inode *inode, struct file *file) * Shut off the timer unless NOWAYOUT is defined. */ #ifndef CONFIG_WATCHDOG_NOWAYOUT + pm_runtime_get_sync(wdev->dev); omap_wdt_disable(wdev); @@ -190,9 +197,11 @@ static ssize_t omap_wdt_write(struct file *file, const char __user *data, /* Refresh LOAD_TIME. */ if (len) { + pm_runtime_get_sync(wdev->dev); spin_lock(&wdt_lock); omap_wdt_ping(wdev); spin_unlock(&wdt_lock); + pm_runtime_put_sync(wdev->dev); } return len; } @@ -224,15 +233,18 @@ static long omap_wdt_ioctl(struct file *file, unsigned int cmd, return put_user(omap_prcm_get_reset_sources(), (int __user *)arg); case WDIOC_KEEPALIVE: + pm_runtime_get_sync(wdev->dev); spin_lock(&wdt_lock); omap_wdt_ping(wdev); spin_unlock(&wdt_lock); + pm_runtime_put_sync(wdev->dev); return 0; case WDIOC_SETTIMEOUT: if (get_user(new_margin, (int __user *)arg)) return -EFAULT; omap_wdt_adjust_timeout(new_margin); + pm_runtime_get_sync(wdev->dev); spin_lock(&wdt_lock); omap_wdt_disable(wdev); omap_wdt_set_timeout(wdev); @@ -240,6 +252,7 @@ static long omap_wdt_ioctl(struct file *file, unsigned int cmd, omap_wdt_ping(wdev); spin_unlock(&wdt_lock); + pm_runtime_put_sync(wdev->dev); /* Fall */ case WDIOC_GETTIMEOUT: return put_user(timer_margin, (int __user *)arg); @@ -345,8 +358,11 @@ static void omap_wdt_shutdown(struct platform_device *pdev) { struct omap_wdt_dev *wdev = platform_get_drvdata(pdev); - if (wdev->omap_wdt_users) + if (wdev->omap_wdt_users) { + pm_runtime_get_sync(wdev->dev); omap_wdt_disable(wdev); + pm_runtime_put_sync(wdev->dev); + } } static int __devexit omap_wdt_remove(struct platform_device *pdev) @@ -381,8 +397,11 @@ static int omap_wdt_suspend(struct platform_device *pdev, pm_message_t state) { struct omap_wdt_dev *wdev = platform_get_drvdata(pdev); - if (wdev->omap_wdt_users) + if (wdev->omap_wdt_users) { + pm_runtime_get_sync(wdev->dev); omap_wdt_disable(wdev); + pm_runtime_put_sync(wdev->dev); + } return 0; } @@ -392,8 +411,10 @@ static int omap_wdt_resume(struct platform_device *pdev) struct omap_wdt_dev *wdev = platform_get_drvdata(pdev); if (wdev->omap_wdt_users) { + pm_runtime_get_sync(wdev->dev); omap_wdt_enable(wdev); omap_wdt_ping(wdev); + pm_runtime_put_sync(wdev->dev); } return 0; diff --git a/include/linux/hwspinlock.h b/include/linux/hwspinlock.h new file mode 100644 index 00000000000..8390efc457e --- /dev/null +++ b/include/linux/hwspinlock.h @@ -0,0 +1,292 @@ +/* + * Hardware spinlock public header + * + * Copyright (C) 2010 Texas Instruments Incorporated - http://www.ti.com + * + * Contact: Ohad Ben-Cohen <ohad@wizery.com> + * + * This program is free software; you can redistribute it and/or modify it + * under the terms of the GNU General Public License version 2 as published + * by the Free Software Foundation. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + */ + +#ifndef __LINUX_HWSPINLOCK_H +#define __LINUX_HWSPINLOCK_H + +#include <linux/err.h> +#include <linux/sched.h> + +/* hwspinlock mode argument */ +#define HWLOCK_IRQSTATE 0x01 /* Disable interrupts, save state */ +#define HWLOCK_IRQ 0x02 /* Disable interrupts, don't save state */ + +struct hwspinlock; + +#if defined(CONFIG_HWSPINLOCK) || defined(CONFIG_HWSPINLOCK_MODULE) + +int hwspin_lock_register(struct hwspinlock *lock); +struct hwspinlock *hwspin_lock_unregister(unsigned int id); +struct hwspinlock *hwspin_lock_request(void); +struct hwspinlock *hwspin_lock_request_specific(unsigned int id); +int hwspin_lock_free(struct hwspinlock *hwlock); +int hwspin_lock_get_id(struct hwspinlock *hwlock); +int __hwspin_lock_timeout(struct hwspinlock *, unsigned int, int, + unsigned long *); +int __hwspin_trylock(struct hwspinlock *, int, unsigned long *); +void __hwspin_unlock(struct hwspinlock *, int, unsigned long *); + +#else /* !CONFIG_HWSPINLOCK */ + +/* + * We don't want these functions to fail if CONFIG_HWSPINLOCK is not + * enabled. We prefer to silently succeed in this case, and let the + * code path get compiled away. This way, if CONFIG_HWSPINLOCK is not + * required on a given setup, users will still work. + * + * The only exception is hwspin_lock_register/hwspin_lock_unregister, with which + * we _do_ want users to fail (no point in registering hwspinlock instances if + * the framework is not available). + * + * Note: ERR_PTR(-ENODEV) will still be considered a success for NULL-checking + * users. Others, which care, can still check this with IS_ERR. + */ +static inline struct hwspinlock *hwspin_lock_request(void) +{ + return ERR_PTR(-ENODEV); +} + +static inline struct hwspinlock *hwspin_lock_request_specific(unsigned int id) +{ + return ERR_PTR(-ENODEV); +} + +static inline int hwspin_lock_free(struct hwspinlock *hwlock) +{ + return 0; +} + +static inline +int __hwspin_lock_timeout(struct hwspinlock *hwlock, unsigned int to, + int mode, unsigned long *flags) +{ + return 0; +} + +static inline +int __hwspin_trylock(struct hwspinlock *hwlock, int mode, unsigned long *flags) +{ + return 0; +} + +static inline +void __hwspin_unlock(struct hwspinlock *hwlock, int mode, unsigned long *flags) +{ + return 0; +} + +static inline int hwspin_lock_get_id(struct hwspinlock *hwlock) +{ + return 0; +} + +static inline int hwspin_lock_register(struct hwspinlock *hwlock) +{ + return -ENODEV; +} + +static inline struct hwspinlock *hwspin_lock_unregister(unsigned int id) +{ + return NULL; +} + +#endif /* !CONFIG_HWSPINLOCK */ + +/** + * hwspin_trylock_irqsave() - try to lock an hwspinlock, disable interrupts + * @hwlock: an hwspinlock which we want to trylock + * @flags: a pointer to where the caller's interrupt state will be saved at + * + * This function attempts to lock the underlying hwspinlock, and will + * immediately fail if the hwspinlock is already locked. + * + * Upon a successful return from this function, preemption and local + * interrupts are disabled (previous interrupts state is saved at @flags), + * so the caller must not sleep, and is advised to release the hwspinlock + * as soon as possible. + * + * Returns 0 if we successfully locked the hwspinlock, -EBUSY if + * the hwspinlock was already taken, and -EINVAL if @hwlock is invalid. + */ +static inline +int hwspin_trylock_irqsave(struct hwspinlock *hwlock, unsigned long *flags) +{ + return __hwspin_trylock(hwlock, HWLOCK_IRQSTATE, flags); +} + +/** + * hwspin_trylock_irq() - try to lock an hwspinlock, disable interrupts + * @hwlock: an hwspinlock which we want to trylock + * + * This function attempts to lock the underlying hwspinlock, and will + * immediately fail if the hwspinlock is already locked. + * + * Upon a successful return from this function, preemption and local + * interrupts are disabled, so the caller must not sleep, and is advised + * to release the hwspinlock as soon as possible. + * + * Returns 0 if we successfully locked the hwspinlock, -EBUSY if + * the hwspinlock was already taken, and -EINVAL if @hwlock is invalid. + */ +static inline int hwspin_trylock_irq(struct hwspinlock *hwlock) +{ + return __hwspin_trylock(hwlock, HWLOCK_IRQ, NULL); +} + +/** + * hwspin_trylock() - attempt to lock a specific hwspinlock + * @hwlock: an hwspinlock which we want to trylock + * + * This function attempts to lock an hwspinlock, and will immediately fail + * if the hwspinlock is already taken. + * + * Upon a successful return from this function, preemption is disabled, + * so the caller must not sleep, and is advised to release the hwspinlock + * as soon as possible. This is required in order to minimize remote cores + * polling on the hardware interconnect. + * + * Returns 0 if we successfully locked the hwspinlock, -EBUSY if + * the hwspinlock was already taken, and -EINVAL if @hwlock is invalid. + */ +static inline int hwspin_trylock(struct hwspinlock *hwlock) +{ + return __hwspin_trylock(hwlock, 0, NULL); +} + +/** + * hwspin_lock_timeout_irqsave() - lock hwspinlock, with timeout, disable irqs + * @hwlock: the hwspinlock to be locked + * @to: timeout value in msecs + * @flags: a pointer to where the caller's interrupt state will be saved at + * + * This function locks the underlying @hwlock. If the @hwlock + * is already taken, the function will busy loop waiting for it to + * be released, but give up when @timeout msecs have elapsed. + * + * Upon a successful return from this function, preemption and local interrupts + * are disabled (plus previous interrupt state is saved), so the caller must + * not sleep, and is advised to release the hwspinlock as soon as possible. + * + * Returns 0 when the @hwlock was successfully taken, and an appropriate + * error code otherwise (most notably an -ETIMEDOUT if the @hwlock is still + * busy after @timeout msecs). The function will never sleep. + */ +static inline int hwspin_lock_timeout_irqsave(struct hwspinlock *hwlock, + unsigned int to, unsigned long *flags) +{ + return __hwspin_lock_timeout(hwlock, to, HWLOCK_IRQSTATE, flags); +} + +/** + * hwspin_lock_timeout_irq() - lock hwspinlock, with timeout, disable irqs + * @hwlock: the hwspinlock to be locked + * @to: timeout value in msecs + * + * This function locks the underlying @hwlock. If the @hwlock + * is already taken, the function will busy loop waiting for it to + * be released, but give up when @timeout msecs have elapsed. + * + * Upon a successful return from this function, preemption and local interrupts + * are disabled so the caller must not sleep, and is advised to release the + * hwspinlock as soon as possible. + * + * Returns 0 when the @hwlock was successfully taken, and an appropriate + * error code otherwise (most notably an -ETIMEDOUT if the @hwlock is still + * busy after @timeout msecs). The function will never sleep. + */ +static inline +int hwspin_lock_timeout_irq(struct hwspinlock *hwlock, unsigned int to) +{ + return __hwspin_lock_timeout(hwlock, to, HWLOCK_IRQ, NULL); +} + +/** + * hwspin_lock_timeout() - lock an hwspinlock with timeout limit + * @hwlock: the hwspinlock to be locked + * @to: timeout value in msecs + * + * This function locks the underlying @hwlock. If the @hwlock + * is already taken, the function will busy loop waiting for it to + * be released, but give up when @timeout msecs have elapsed. + * + * Upon a successful return from this function, preemption is disabled + * so the caller must not sleep, and is advised to release the hwspinlock + * as soon as possible. + * This is required in order to minimize remote cores polling on the + * hardware interconnect. + * + * Returns 0 when the @hwlock was successfully taken, and an appropriate + * error code otherwise (most notably an -ETIMEDOUT if the @hwlock is still + * busy after @timeout msecs). The function will never sleep. + */ +static inline +int hwspin_lock_timeout(struct hwspinlock *hwlock, unsigned int to) +{ + return __hwspin_lock_timeout(hwlock, to, 0, NULL); +} + +/** + * hwspin_unlock_irqrestore() - unlock hwspinlock, restore irq state + * @hwlock: a previously-acquired hwspinlock which we want to unlock + * @flags: previous caller's interrupt state to restore + * + * This function will unlock a specific hwspinlock, enable preemption and + * restore the previous state of the local interrupts. It should be used + * to undo, e.g., hwspin_trylock_irqsave(). + * + * @hwlock must be already locked before calling this function: it is a bug + * to call unlock on a @hwlock that is already unlocked. + */ +static inline void hwspin_unlock_irqrestore(struct hwspinlock *hwlock, + unsigned long *flags) +{ + __hwspin_unlock(hwlock, HWLOCK_IRQSTATE, flags); +} + +/** + * hwspin_unlock_irq() - unlock hwspinlock, enable interrupts + * @hwlock: a previously-acquired hwspinlock which we want to unlock + * + * This function will unlock a specific hwspinlock, enable preemption and + * enable local interrupts. Should be used to undo hwspin_lock_irq(). + * + * @hwlock must be already locked (e.g. by hwspin_trylock_irq()) before + * calling this function: it is a bug to call unlock on a @hwlock that is + * already unlocked. + */ +static inline void hwspin_unlock_irq(struct hwspinlock *hwlock) +{ + __hwspin_unlock(hwlock, HWLOCK_IRQ, NULL); +} + +/** + * hwspin_unlock() - unlock hwspinlock + * @hwlock: a previously-acquired hwspinlock which we want to unlock + * + * This function will unlock a specific hwspinlock and enable preemption + * back. + * + * @hwlock must be already locked (e.g. by hwspin_trylock()) before calling + * this function: it is a bug to call unlock on a @hwlock that is already + * unlocked. + */ +static inline void hwspin_unlock(struct hwspinlock *hwlock) +{ + __hwspin_unlock(hwlock, 0, NULL); +} + +#endif /* __LINUX_HWSPINLOCK_H */ diff --git a/include/linux/i2c/twl.h b/include/linux/i2c/twl.h index a4bd05b7bd2..58afd9d2c43 100644 --- a/include/linux/i2c/twl.h +++ b/include/linux/i2c/twl.h @@ -639,7 +639,6 @@ extern void twl4030_power_init(struct twl4030_power_data *triton2_scripts); extern int twl4030_remove_script(u8 flags); struct twl4030_codec_audio_data { - unsigned int audio_mclk; /* not used, will be removed */ unsigned int digimic_delay; /* in ms */ unsigned int ramp_delay_value; unsigned int offset_cncl_path; @@ -650,7 +649,6 @@ struct twl4030_codec_audio_data { }; struct twl4030_codec_vibra_data { - unsigned int audio_mclk; unsigned int coexist; }; diff --git a/include/linux/mtd/onenand_regs.h b/include/linux/mtd/onenand_regs.h index cd6f3b43119..d60130f88ee 100644 --- a/include/linux/mtd/onenand_regs.h +++ b/include/linux/mtd/onenand_regs.h @@ -168,6 +168,7 @@ #define ONENAND_SYS_CFG1_INT (1 << 6) #define ONENAND_SYS_CFG1_IOBE (1 << 5) #define ONENAND_SYS_CFG1_RDY_CONF (1 << 4) +#define ONENAND_SYS_CFG1_VHF (1 << 3) #define ONENAND_SYS_CFG1_HF (1 << 2) #define ONENAND_SYS_CFG1_SYNC_WRITE (1 << 1) diff --git a/sound/soc/omap/omap-mcbsp.c b/sound/soc/omap/omap-mcbsp.c index d203f4da18a..2175f09e57b 100644 --- a/sound/soc/omap/omap-mcbsp.c +++ b/sound/soc/omap/omap-mcbsp.c @@ -69,110 +69,6 @@ static struct omap_mcbsp_data mcbsp_data[NUM_LINKS]; */ static struct omap_pcm_dma_data omap_mcbsp_dai_dma_params[NUM_LINKS][2]; -#if defined(CONFIG_ARCH_OMAP15XX) || defined(CONFIG_ARCH_OMAP16XX) -static const int omap1_dma_reqs[][2] = { - { OMAP_DMA_MCBSP1_TX, OMAP_DMA_MCBSP1_RX }, - { OMAP_DMA_MCBSP2_TX, OMAP_DMA_MCBSP2_RX }, - { OMAP_DMA_MCBSP3_TX, OMAP_DMA_MCBSP3_RX }, -}; -static const unsigned long omap1_mcbsp_port[][2] = { - { OMAP1510_MCBSP1_BASE + OMAP_MCBSP_REG_DXR1, - OMAP1510_MCBSP1_BASE + OMAP_MCBSP_REG_DRR1 }, - { OMAP1510_MCBSP2_BASE + OMAP_MCBSP_REG_DXR1, - OMAP1510_MCBSP2_BASE + OMAP_MCBSP_REG_DRR1 }, - { OMAP1510_MCBSP3_BASE + OMAP_MCBSP_REG_DXR1, - OMAP1510_MCBSP3_BASE + OMAP_MCBSP_REG_DRR1 }, -}; -#else -static const int omap1_dma_reqs[][2] = {}; -static const unsigned long omap1_mcbsp_port[][2] = {}; -#endif - -#if defined(CONFIG_ARCH_OMAP2) || defined(CONFIG_ARCH_OMAP3) -static const int omap24xx_dma_reqs[][2] = { - { OMAP24XX_DMA_MCBSP1_TX, OMAP24XX_DMA_MCBSP1_RX }, - { OMAP24XX_DMA_MCBSP2_TX, OMAP24XX_DMA_MCBSP2_RX }, -#if defined(CONFIG_ARCH_OMAP2430) || defined(CONFIG_ARCH_OMAP3) - { OMAP24XX_DMA_MCBSP3_TX, OMAP24XX_DMA_MCBSP3_RX }, - { OMAP24XX_DMA_MCBSP4_TX, OMAP24XX_DMA_MCBSP4_RX }, - { OMAP24XX_DMA_MCBSP5_TX, OMAP24XX_DMA_MCBSP5_RX }, -#endif -}; -#else -static const int omap24xx_dma_reqs[][2] = {}; -#endif - -#if defined(CONFIG_ARCH_OMAP4) -static const int omap44xx_dma_reqs[][2] = { - { OMAP44XX_DMA_MCBSP1_TX, OMAP44XX_DMA_MCBSP1_RX }, - { OMAP44XX_DMA_MCBSP2_TX, OMAP44XX_DMA_MCBSP2_RX }, - { OMAP44XX_DMA_MCBSP3_TX, OMAP44XX_DMA_MCBSP3_RX }, - { OMAP44XX_DMA_MCBSP4_TX, OMAP44XX_DMA_MCBSP4_RX }, -}; -#else -static const int omap44xx_dma_reqs[][2] = {}; -#endif - -#if defined(CONFIG_ARCH_OMAP2420) -static const unsigned long omap2420_mcbsp_port[][2] = { - { OMAP24XX_MCBSP1_BASE + OMAP_MCBSP_REG_DXR1, - OMAP24XX_MCBSP1_BASE + OMAP_MCBSP_REG_DRR1 }, - { OMAP24XX_MCBSP2_BASE + OMAP_MCBSP_REG_DXR1, - OMAP24XX_MCBSP2_BASE + OMAP_MCBSP_REG_DRR1 }, -}; -#else -static const unsigned long omap2420_mcbsp_port[][2] = {}; -#endif - -#if defined(CONFIG_ARCH_OMAP2430) -static const unsigned long omap2430_mcbsp_port[][2] = { - { OMAP24XX_MCBSP1_BASE + OMAP_MCBSP_REG_DXR, - OMAP24XX_MCBSP1_BASE + OMAP_MCBSP_REG_DRR }, - { OMAP24XX_MCBSP2_BASE + OMAP_MCBSP_REG_DXR, - OMAP24XX_MCBSP2_BASE + OMAP_MCBSP_REG_DRR }, - { OMAP2430_MCBSP3_BASE + OMAP_MCBSP_REG_DXR, - OMAP2430_MCBSP3_BASE + OMAP_MCBSP_REG_DRR }, - { OMAP2430_MCBSP4_BASE + OMAP_MCBSP_REG_DXR, - OMAP2430_MCBSP4_BASE + OMAP_MCBSP_REG_DRR }, - { OMAP2430_MCBSP5_BASE + OMAP_MCBSP_REG_DXR, - OMAP2430_MCBSP5_BASE + OMAP_MCBSP_REG_DRR }, -}; -#else -static const unsigned long omap2430_mcbsp_port[][2] = {}; -#endif - -#if defined(CONFIG_ARCH_OMAP3) -static const unsigned long omap34xx_mcbsp_port[][2] = { - { OMAP34XX_MCBSP1_BASE + OMAP_MCBSP_REG_DXR, - OMAP34XX_MCBSP1_BASE + OMAP_MCBSP_REG_DRR }, - { OMAP34XX_MCBSP2_BASE + OMAP_MCBSP_REG_DXR, - OMAP34XX_MCBSP2_BASE + OMAP_MCBSP_REG_DRR }, - { OMAP34XX_MCBSP3_BASE + OMAP_MCBSP_REG_DXR, - OMAP34XX_MCBSP3_BASE + OMAP_MCBSP_REG_DRR }, - { OMAP34XX_MCBSP4_BASE + OMAP_MCBSP_REG_DXR, - OMAP34XX_MCBSP4_BASE + OMAP_MCBSP_REG_DRR }, - { OMAP34XX_MCBSP5_BASE + OMAP_MCBSP_REG_DXR, - OMAP34XX_MCBSP5_BASE + OMAP_MCBSP_REG_DRR }, -}; -#else -static const unsigned long omap34xx_mcbsp_port[][2] = {}; -#endif - -#if defined(CONFIG_ARCH_OMAP4) -static const unsigned long omap44xx_mcbsp_port[][2] = { - { OMAP44XX_MCBSP1_BASE + OMAP_MCBSP_REG_DXR, - OMAP44XX_MCBSP1_BASE + OMAP_MCBSP_REG_DRR }, - { OMAP44XX_MCBSP2_BASE + OMAP_MCBSP_REG_DXR, - OMAP44XX_MCBSP2_BASE + OMAP_MCBSP_REG_DRR }, - { OMAP44XX_MCBSP3_BASE + OMAP_MCBSP_REG_DXR, - OMAP44XX_MCBSP3_BASE + OMAP_MCBSP_REG_DRR }, - { OMAP44XX_MCBSP4_BASE + OMAP_MCBSP_REG_DXR, - OMAP44XX_MCBSP4_BASE + OMAP_MCBSP_REG_DRR }, -}; -#else -static const unsigned long omap44xx_mcbsp_port[][2] = {}; -#endif - static void omap_mcbsp_set_threshold(struct snd_pcm_substream *substream) { struct snd_soc_pcm_runtime *rtd = substream->private_data; @@ -346,24 +242,10 @@ static int omap_mcbsp_dai_hw_params(struct snd_pcm_substream *substream, unsigned int format, div, framesize, master; dma_data = &omap_mcbsp_dai_dma_params[cpu_dai->id][substream->stream]; - if (cpu_class_is_omap1()) { - dma = omap1_dma_reqs[bus_id][substream->stream]; - port = omap1_mcbsp_port[bus_id][substream->stream]; - } else if (cpu_is_omap2420()) { - dma = omap24xx_dma_reqs[bus_id][substream->stream]; - port = omap2420_mcbsp_port[bus_id][substream->stream]; - } else if (cpu_is_omap2430()) { - dma = omap24xx_dma_reqs[bus_id][substream->stream]; - port = omap2430_mcbsp_port[bus_id][substream->stream]; - } else if (cpu_is_omap343x()) { - dma = omap24xx_dma_reqs[bus_id][substream->stream]; - port = omap34xx_mcbsp_port[bus_id][substream->stream]; - } else if (cpu_is_omap44xx()) { - dma = omap44xx_dma_reqs[bus_id][substream->stream]; - port = omap44xx_mcbsp_port[bus_id][substream->stream]; - } else { - return -ENODEV; - } + + dma = omap_mcbsp_dma_ch_params(bus_id, substream->stream); + port = omap_mcbsp_dma_reg_params(bus_id, substream->stream); + switch (params_format(params)) { case SNDRV_PCM_FORMAT_S16_LE: dma_data->data_type = OMAP_DMA_DATA_TYPE_S16; diff --git a/sound/soc/omap/omap-mcbsp.h b/sound/soc/omap/omap-mcbsp.h index 110c106611d..37dc7211ed3 100644 --- a/sound/soc/omap/omap-mcbsp.h +++ b/sound/soc/omap/omap-mcbsp.h @@ -43,7 +43,7 @@ enum omap_mcbsp_div { OMAP_MCBSP_CLKGDV, /* Sample rate generator divider */ }; -#if defined(CONFIG_ARCH_OMAP2420) +#if defined(CONFIG_SOC_OMAP2420) #define NUM_LINKS 2 #endif #if defined(CONFIG_ARCH_OMAP15XX) || defined(CONFIG_ARCH_OMAP16XX) @@ -54,7 +54,7 @@ enum omap_mcbsp_div { #undef NUM_LINKS #define NUM_LINKS 4 #endif -#if defined(CONFIG_ARCH_OMAP2430) || defined(CONFIG_ARCH_OMAP3) +#if defined(CONFIG_ARCH_OMAP3) || defined(CONFIG_SOC_OMAP2430) #undef NUM_LINKS #define NUM_LINKS 5 #endif |