menuconfig I2C
tristate "I2C support"
depends on HAS_IOMEM
+ default y if MACH_OMAP_H3 || MACH_OMAP_OSK
---help---
I2C (pronounce: I-square-C) is a slow serial bus protocol used in
many micro controller applications and developed by Philips. SMBus,
obj-$(CONFIG_I2C_VOODOO3) += i2c-voodoo3.o
obj-$(CONFIG_SCx200_ACB) += scx200_acb.o
obj-$(CONFIG_SCx200_I2C) += scx200_i2c.o
+obj-$(CONFIG_I2C_OMAP) += i2c-omap.o
ifeq ($(CONFIG_I2C_DEBUG_BUS),y)
EXTRA_CFLAGS += -DDEBUG
#include <asm/io.h>
+/* Hack to enable zero length transfers and smbus quick until clean fix
+ is available */
+#define OMAP_HACK
+
/* timeout waiting for the controller to respond */
#define OMAP_I2C_TIMEOUT (msecs_to_jiffies(1000))
struct i2c_msg *msg, int stop)
{
struct omap_i2c_dev *dev = i2c_get_adapdata(adap);
+#ifdef OMAP_HACK
+ u8 zero_byte = 0;
+#endif
int r;
u16 w;
dev_dbg(dev->dev, "addr: 0x%04x, len: %d, flags: 0x%x, stop: %d\n",
msg->addr, msg->len, msg->flags, stop);
+#ifndef OMAP_HACK
if (msg->len == 0)
return -EINVAL;
dev->buf = msg->buf;
dev->buf_len = msg->len;
+#else
+
+ omap_i2c_write_reg(dev, OMAP_I2C_SA_REG, msg->addr);
+ /* REVISIT: Remove this hack when we can get I2C chips from board-*.c
+ * files
+ * Sigh, seems we can't do zero length transactions. Thus, we
+ * can't probe for devices w/o actually sending/receiving at least
+ * a single byte. So we'll set count to 1 for the zero length
+ * transaction case and hope we don't cause grief for some
+ * arbitrary device due to random byte write/read during
+ * probes.
+ */
+ if (msg->len == 0) {
+ dev->buf = &zero_byte;
+ dev->buf_len = 1;
+ } else {
+ dev->buf = msg->buf;
+ dev->buf_len = msg->len;
+ }
+#endif
+
omap_i2c_write_reg(dev, OMAP_I2C_CNT_REG, dev->buf_len);
init_completion(&dev->cmd_complete);
w |= OMAP_I2C_CON_STP;
omap_i2c_write_reg(dev, OMAP_I2C_CON_REG, w);
- r = wait_for_completion_interruptible_timeout(&dev->cmd_complete,
- OMAP_I2C_TIMEOUT);
+ r = wait_for_completion_timeout(&dev->cmd_complete,
+ OMAP_I2C_TIMEOUT);
dev->buf_len = 0;
if (r < 0)
return r;
static u32
omap_i2c_func(struct i2c_adapter *adap)
{
+#ifndef OMAP_HACK
return I2C_FUNC_I2C | (I2C_FUNC_SMBUS_EMUL & ~I2C_FUNC_SMBUS_QUICK);
+#else
+ return I2C_FUNC_I2C | I2C_FUNC_SMBUS_EMUL;
+#endif
}
static inline void
if (dev->buf_len) {
*dev->buf++ = w;
dev->buf_len--;
- if (dev->buf_len) {
- *dev->buf++ = w >> 8;
- dev->buf_len--;
+ /*
+ * Data reg in 2430 is 8 bit wide,
+ */
+ if (!cpu_is_omap2430()) {
+ if (dev->buf_len) {
+ *dev->buf++ = w >> 8;
+ dev->buf_len--;
+ }
}
} else
dev_err(dev->dev, "RRDY IRQ while no data"
if (dev->buf_len) {
w = *dev->buf++;
dev->buf_len--;
- if (dev->buf_len) {
- w |= *dev->buf++ << 8;
- dev->buf_len--;
+ /*
+ * Data reg in 2430 is 8 bit wide,
+ */
+ if (!cpu_is_omap2430()) {
+ if (dev->buf_len) {
+ w |= *dev->buf++ << 8;
+ dev->buf_len--;
+ }
}
} else
dev_err(dev->dev, "XRDY IRQ while no"
This driver can also be built as a module. If so, the module
will be called tps65010.
+config SENSORS_TLV320AIC23
+ tristate "Texas Instruments TLV320AIC23 Codec"
+ depends on I2C && I2C_OMAP
+ help
+ If you say yes here you get support for the I2C control
+ interface for Texas Instruments TLV320AIC23 audio codec.
+
+config GPIOEXPANDER_OMAP
+ bool "GPIO Expander PCF8574PWR for OMAP"
+ depends on I2C && (ARCH_OMAP16XX || ARCH_OMAP24XX)
+ help
+ If you say yes here you get support for I/O expander calls
+ to configure IrDA, Camera and audio devices.
+
+config MENELAUS
+ bool "Menelaus PM chip"
+ depends on I2C=y && ARCH_OMAP24XX
+ help
+ Say yes here if you have Menelaus chip on your board
+
+config TWL4030_CORE
+ bool "TI's TWL4030 companion chip Core Driver Support"
+ depends on I2C=y && ARCH_OMAP24XX
+ help
+ Say yes here if you have TWL4030 chip on your board
+
config SENSORS_M41T00
tristate "ST M41T00 RTC chip"
depends on PPC32
obj-$(CONFIG_SENSORS_PCF8591) += pcf8591.o
obj-$(CONFIG_ISP1301_OMAP) += isp1301_omap.o
obj-$(CONFIG_TPS65010) += tps65010.o
+obj-$(CONFIG_SENSORS_TLV320AIC23) += tlv320aic23.o
+obj-$(CONFIG_GPIOEXPANDER_OMAP) += gpio_expander_omap.o
+obj-$(CONFIG_MENELAUS) += menelaus.o
+obj-$(CONFIG_TWL4030_CORE) += twl4030_core.o
+obj-$(CONFIG_RTC_X1205_I2C) += x1205.o
ifeq ($(CONFIG_I2C_DEBUG_CHIP),y)
EXTRA_CFLAGS += -DDEBUG
--- /dev/null
+/*
+ * drivers/i2c/chips/gpio_expander_omap.c
+ *
+ * Copyright (C) 2004 Texas Instruments Inc
+ * Author:
+ *
+ * gpio expander is used to configure IrDA, camera and audio devices on omap 1710 processor.
+ *
+ * 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 <linux/i2c.h>
+#include <linux/errno.h>
+
+int read_gpio_expa(u8 * val, int addr);
+int write_gpio_expa(u8 val, int addr);
+
+int write_gpio_expa(u8 val, int addr)
+{
+ struct i2c_adapter *adap;
+ int err;
+ struct i2c_msg msg[1];
+ unsigned char data[1];
+
+ adap = i2c_get_adapter(0);
+ if (!adap)
+ return -ENODEV;
+ msg->addr = addr; /* I2C address of GPIO EXPA */
+ msg->flags = 0;
+ msg->len = 1;
+ msg->buf = data;
+ data[0] = val;
+ err = i2c_transfer(adap, msg, 1);
+ if (err >= 0)
+ return 0;
+ return err;
+}
+
+/* Read from I/O EXPANDER on the H3 board.
+ * The IO expanders need an independent I2C client driver.
+ */
+
+int read_gpio_expa(u8 * val, int addr)
+{
+ struct i2c_adapter *adap;
+ int err;
+ struct i2c_msg msg[1];
+ unsigned char data[1];
+
+ adap = i2c_get_adapter(0);
+ if (!adap)
+ return -ENODEV;
+ msg->addr = addr; /* I2C address of GPIO EXPA */
+ msg->flags = I2C_M_RD;
+ msg->len = 2;
+ msg->buf = data;
+ err = i2c_transfer(adap, msg, 1);
+ *val = data[0];
+
+ if (err >= 0)
+ return 0;
+ return err;
+}
+
+EXPORT_SYMBOL(read_gpio_expa);
+EXPORT_SYMBOL(write_gpio_expa);
+
#include <linux/workqueue.h>
#include <asm/irq.h>
+#include <asm/mach-types.h>
+
+#include <asm/arch/gpio.h>
#include <asm/arch/usb.h>
+#include <asm/arch/mux.h>
#ifndef DEBUG
#define DRIVER_VERSION "24 August 2004"
-#define DRIVER_NAME (isp1301_driver.name)
+#define DRIVER_NAME (isp1301_driver.driver.name)
MODULE_DESCRIPTION("ISP1301 USB OTG Transceiver Driver");
MODULE_LICENSE("GPL");
void (*i2c_release)(struct device *dev);
int irq;
+ int irq_type;
u32 last_otg_ctrl;
unsigned working:1;
/* use keventd context to change the state for us */
struct work_struct work;
-
+
unsigned long todo;
# define WORK_UPDATE_ISP 0 /* update ISP from OTG */
# define WORK_UPDATE_OTG 1 /* update OTG from ISP */
/*-------------------------------------------------------------------------*/
-#ifdef CONFIG_MACH_OMAP_H2
+#if defined(CONFIG_MACH_OMAP_H2) || \
+ defined(CONFIG_MACH_OMAP_H3)
/* board-specific PM hooks */
-#include <asm/arch/gpio.h>
-#include <asm/arch/mux.h>
-#include <asm/mach-types.h>
-
#if defined(CONFIG_TPS65010) || defined(CONFIG_TPS65010_MODULE)
}
-/* products will deliver OTG messages with LEDs, GUI, etc */
-static inline void notresponding(struct isp1301 *isp)
+#else
+
+static void enable_vbus_draw(struct isp1301 *isp, unsigned mA)
{
- printk(KERN_NOTICE "OTG device not responding.\n");
+ pr_debug("%s UNIMPL\n", __FUNCTION__);
}
+static void enable_vbus_source(struct isp1301 *isp)
+{
+ pr_debug("%s UNIMPL\n", __FUNCTION__);
+}
#endif
/*-------------------------------------------------------------------------*/
+/* products will deliver OTG messages with LEDs, GUI, etc */
+static inline void notresponding(struct isp1301 *isp)
+{
+ printk(KERN_NOTICE "OTG device not responding.\n");
+}
+
+/*-------------------------------------------------------------------------*/
+
/* only two addresses possible */
#define ISP_BASE 0x2c
static unsigned short normal_i2c[] = {
{
// isp1301_clear_bits(isp, ISP1301_MODE_CONTROL_2, MC2_GLOBAL_PWR_DN);
isp1301_clear_bits(isp, ISP1301_MODE_CONTROL_1, MC1_SUSPEND_REG);
-
+
/* do this only when cpu is driving transceiver,
* so host won't see a low speed device...
*/
static void update_otg1(struct isp1301 *isp, u8 int_src)
{
u32 otg_ctrl;
+ u8 int_id;
otg_ctrl = OTG_CTRL_REG
& OTG_CTRL_MASK
}
if (int_src & INTR_VBUS_VLD)
otg_ctrl |= OTG_VBUSVLD;
- if (int_src & INTR_ID_GND) { /* default-A */
+
+ int_id = isp1301_get_u8(isp, ISP1301_INTERRUPT_SOURCE);
+
+ if (int_id & INTR_ID_GND) { /* default-A */
if (isp->otg.state == OTG_STATE_B_IDLE
|| isp->otg.state == OTG_STATE_UNDEFINED) {
a_idle(isp, "init");
/* role is host */
} else {
if (!(otg_ctrl & OTG_ID)) {
- otg_ctrl &= OTG_CTRL_MASK & ~OTG_XCEIV_INPUTS;
+ otg_ctrl &= OTG_CTRL_MASK & ~OTG_XCEIV_INPUTS;
OTG_CTRL_REG = otg_ctrl | OTG_A_BUSREQ;
}
/* update the OTG controller state to match the isp1301; may
* trigger OPRT_CHG irqs for changes going to the isp1301.
*/
- update_otg1(isp, isp_stat);
+ update_otg1(isp, stat); // pass the actual interrupt latch status
update_otg2(isp, isp_bstat);
check_state(isp, __FUNCTION__);
#endif
}
static void
-isp1301_work(void *data)
+isp1301_work(struct work_struct *work)
{
- struct isp1301 *isp = data;
+ struct isp1301 *isp = container_of(work, struct isp1301, work);
int stop;
/* implicit lock: we're the only task using this device */
if (machine_is_omap_h2())
omap_free_gpio(2);
+ if (machine_is_omap_h3())
+ omap_free_gpio(14);
+
+ if (machine_is_omap_h4())
+ omap_free_gpio(125);
+
isp->timer.data = 0;
set_bit(WORK_STOP, &isp->todo);
del_timer_sync(&isp->timer);
* - DEVICE mode, for when there's a B/Mini-B (device) connector
*
* As a rule, you won't have an isp1301 chip unless it's there to
- * support the OTG mode. Other modes help testing USB controllers
+ * support the OTG mode. Other modes help testing USB controllers
* in isolation from (full) OTG support, or maybe so later board
* revisions can help to support those feature.
*/
* a few more interrupts than are strictly needed.
*/
isp1301_set_bits(isp, ISP1301_INTERRUPT_RISING,
- INTR_VBUS_VLD | INTR_SESS_VLD | INTR_ID_GND);
+ INTR_VBUS_VLD | INTR_SESS_VLD | INTR_ID_GND);
isp1301_set_bits(isp, ISP1301_INTERRUPT_FALLING,
- INTR_VBUS_VLD | INTR_SESS_VLD | INTR_ID_GND);
+ INTR_VBUS_VLD | INTR_SESS_VLD | INTR_ID_GND);
dev_info(&isp->client.dev, "ready for dual-role USB ...\n");
power_up(isp);
- if (machine_is_omap_h2())
+// XXX h4 too?
+ if (machine_is_omap_h2() || machine_is_omap_h3())
isp1301_set_bits(isp, ISP1301_MODE_CONTROL_1, MC1_DAT_SE0);
dev_info(&isp->client.dev, "A-Host sessions ok\n");
isp1301_set_bits(isp, ISP1301_INTERRUPT_RISING,
- INTR_ID_GND);
+ INTR_ID_GND);
isp1301_set_bits(isp, ISP1301_INTERRUPT_FALLING,
- INTR_ID_GND);
+ INTR_ID_GND);
/* If this has a Mini-AB connector, this mode is highly
* nonstandard ... but can be handy for testing, especially with
power_up(isp);
isp->otg.state = OTG_STATE_B_IDLE;
- if (machine_is_omap_h2())
+// XXX h4 too?
+ if (machine_is_omap_h2() || machine_is_omap_h3())
isp1301_set_bits(isp, ISP1301_MODE_CONTROL_1, MC1_DAT_SE0);
isp1301_set_bits(isp, ISP1301_INTERRUPT_RISING,
- INTR_SESS_VLD);
+ INTR_SESS_VLD | INTR_VBUS_VLD);
isp1301_set_bits(isp, ISP1301_INTERRUPT_FALLING,
- INTR_VBUS_VLD);
+ INTR_VBUS_VLD | INTR_SESS_VLD);
dev_info(&isp->client.dev, "B-Peripheral sessions ok\n");
dump_regs(isp, __FUNCTION__);
* So do this part as early as possible...
*/
switch (isp->otg.state) {
+ case OTG_STATE_B_PERIPHERAL:
+ isp->otg.state = OTG_STATE_B_WAIT_ACON;
+ isp1301_defer_work(isp, WORK_UPDATE_ISP);
+ break;
case OTG_STATE_B_HOST:
isp->otg.state = OTG_STATE_B_PERIPHERAL;
/* caller will suspend next */
if (!isp)
return 0;
- INIT_WORK(&isp->work, isp1301_work, isp);
+ INIT_WORK(&isp->work, isp1301_work);
init_timer(&isp->timer);
isp->timer.function = isp1301_timer;
isp->timer.data = (unsigned long) isp;
isp->irq = -1;
+ isp->irq_type = 0;
isp->client.addr = address;
i2c_set_clientdata(&isp->client, isp);
isp->client.adapter = bus;
}
#endif
- if (machine_is_omap_h2()) {
+// XXX h4 too?
+ if (machine_is_omap_h2() || machine_is_omap_h3()) {
/* full speed signaling by default */
isp1301_set_bits(isp, ISP1301_MODE_CONTROL_1,
MC1_SPEED_REG);
isp1301_set_bits(isp, ISP1301_MODE_CONTROL_2,
MC2_SPD_SUSP_CTRL);
+ }
+ if (machine_is_omap_h2()) {
/* IRQ wired at M14 */
omap_cfg_reg(M14_1510_GPIO2);
isp->irq = OMAP_GPIO_IRQ(2);
omap_request_gpio(2);
omap_set_gpio_direction(2, 1);
- omap_set_gpio_edge_ctrl(2, OMAP_GPIO_FALLING_EDGE);
+ isp->irq_type = IRQF_TRIGGER_FALLING;
+ }
+
+ if (machine_is_omap_h3()) {
+ /* IRQ wired at N21 */
+ omap_cfg_reg(N21_1710_GPIO14);
+ isp->irq = OMAP_GPIO_IRQ(14);
+ omap_request_gpio(14);
+ omap_set_gpio_direction(14, 1);
+ isp->irq_type = IRQF_TRIGGER_FALLING;
+ }
+
+ if (machine_is_omap_h4()) {
+ /* IRQ wired at P14 */
+ omap_cfg_reg(P14_24XX_GPIO125);
+ isp->irq = OMAP_GPIO_IRQ(125);
+ omap_request_gpio(125);
+ omap_set_gpio_direction(125, 1);
+ isp->irq_type = IRQF_TRIGGER_LOW;
}
status = request_irq(isp->irq, isp1301_irq,
- IRQF_SAMPLE_RANDOM, DRIVER_NAME, isp);
+ isp->irq_type, DRIVER_NAME, isp);
if (status < 0) {
dev_dbg(&i2c->dev, "can't get IRQ %d, err %d\n",
isp->irq, status);
--- /dev/null
+/*
+ * drivers/i2c/chips/menelaus.c
+ *
+ * Copyright (C) 2004 Texas Instruments, Inc.
+ *
+ * Some parts based tps65010.c:
+ * Copyright (C) 2004 Texas Instruments and
+ * Copyright (C) 2004-2005 David Brownell
+ *
+ * Some parts based on tlv320aic24.c:
+ * Copyright (C) by Kai Svahn <kai.svahn@nokia.com>
+ *
+ * Changes for interrupt handling and clean-up by
+ * Tony Lindgren <tony@atomide.com> and Imre Deak <imre.deak@nokia.com>
+ * Cleanup and generalized support for voltage setting by
+ * Juha Yrjola
+ * Added support for controlling VCORE and regulator sleep states,
+ * Amit Kucheria <amit.kucheria@nokia.com>
+ * Copyright (C) 2005, 2006 Nokia Corporation
+ *
+ * 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/module.h>
+#include <linux/i2c.h>
+#include <linux/interrupt.h>
+#include <linux/sched.h>
+#include <linux/mutex.h>
+#include <linux/workqueue.h>
+
+#include <asm/mach-types.h>
+#include <asm/mach/irq.h>
+
+#include <asm/arch/mux.h>
+#include <asm/arch/gpio.h>
+#include <asm/arch/menelaus.h>
+
+#define DEBUG
+
+#define DRIVER_NAME "menelaus"
+
+#define pr_err(fmt, arg...) printk(KERN_ERR DRIVER_NAME ": ", ## arg);
+
+#define MENELAUS_I2C_ADDRESS 0x72
+
+#define MENELAUS_REV 0x01
+#define MENELAUS_VCORE_CTRL1 0x02
+#define MENELAUS_VCORE_CTRL2 0x03
+#define MENELAUS_VCORE_CTRL3 0x04
+#define MENELAUS_VCORE_CTRL4 0x05
+#define MENELAUS_VCORE_CTRL5 0x06
+#define MENELAUS_DCDC_CTRL1 0x07
+#define MENELAUS_DCDC_CTRL2 0x08
+#define MENELAUS_DCDC_CTRL3 0x09
+#define MENELAUS_LDO_CTRL1 0x0A
+#define MENELAUS_LDO_CTRL2 0x0B
+#define MENELAUS_LDO_CTRL3 0x0C
+#define MENELAUS_LDO_CTRL4 0x0D
+#define MENELAUS_LDO_CTRL5 0x0E
+#define MENELAUS_LDO_CTRL6 0x0F
+#define MENELAUS_LDO_CTRL7 0x10
+#define MENELAUS_LDO_CTRL8 0x11
+#define MENELAUS_SLEEP_CTRL1 0x12
+#define MENELAUS_SLEEP_CTRL2 0x13
+#define MENELAUS_DEVICE_OFF 0x14
+#define MENELAUS_OSC_CTRL 0x15
+#define MENELAUS_DETECT_CTRL 0x16
+#define MENELAUS_INT_MASK1 0x17
+#define MENELAUS_INT_MASK2 0x18
+#define MENELAUS_INT_STATUS1 0x19
+#define MENELAUS_INT_STATUS2 0x1A
+#define MENELAUS_INT_ACK1 0x1B
+#define MENELAUS_INT_ACK2 0x1C
+#define MENELAUS_GPIO_CTRL 0x1D
+#define MENELAUS_GPIO_IN 0x1E
+#define MENELAUS_GPIO_OUT 0x1F
+#define MENELAUS_BBSMS 0x20
+#define MENELAUS_RTC_CTRL 0x21
+#define MENELAUS_RTC_UPDATE 0x22
+#define MENELAUS_RTC_SEC 0x23
+#define MENELAUS_RTC_MIN 0x24
+#define MENELAUS_RTC_HR 0x25
+#define MENELAUS_RTC_DAY 0x26
+#define MENELAUS_RTC_MON 0x27
+#define MENELAUS_RTC_YR 0x28
+#define MENELAUS_RTC_WKDAY 0x29
+#define MENELAUS_RTC_AL_SEC 0x2A
+#define MENELAUS_RTC_AL_MIN 0x2B
+#define MENELAUS_RTC_AL_HR 0x2C
+#define MENELAUS_RTC_AL_DAY 0x2D
+#define MENELAUS_RTC_AL_MON 0x2E
+#define MENELAUS_RTC_AL_YR 0x2F
+#define MENELAUS_RTC_COMP_MSB 0x30
+#define MENELAUS_RTC_COMP_LSB 0x31
+#define MENELAUS_S1_PULL_EN 0x32
+#define MENELAUS_S1_PULL_DIR 0x33
+#define MENELAUS_S2_PULL_EN 0x34
+#define MENELAUS_S2_PULL_DIR 0x35
+#define MENELAUS_MCT_CTRL1 0x36
+#define MENELAUS_MCT_CTRL2 0x37
+#define MENELAUS_MCT_CTRL3 0x38
+#define MENELAUS_MCT_PIN_ST 0x39
+#define MENELAUS_DEBOUNCE1 0x3A
+
+#define IH_MENELAUS_IRQS 12
+#define MENELAUS_MMC_S1CD_IRQ 0 /* MMC slot 1 card change */
+#define MENELAUS_MMC_S2CD_IRQ 1 /* MMC slot 2 card change */
+#define MENELAUS_MMC_S1D1_IRQ 2 /* MMC DAT1 low in slot 1 */
+#define MENELAUS_MMC_S2D1_IRQ 3 /* MMC DAT1 low in slot 2 */
+#define MENELAUS_LOWBAT_IRQ 4 /* Low battery */
+#define MENELAUS_HOTDIE_IRQ 5 /* Hot die detect */
+#define MENELAUS_UVLO_IRQ 6 /* UVLO detect */
+#define MENELAUS_TSHUT_IRQ 7 /* Thermal shutdown */
+#define MENELAUS_RTCTMR_IRQ 8 /* RTC timer */
+#define MENELAUS_RTCALM_IRQ 9 /* RTC alarm */
+#define MENELAUS_RTCERR_IRQ 10 /* RTC error */
+#define MENELAUS_PSHBTN_IRQ 11 /* Push button */
+#define MENELAUS_RESERVED12_IRQ 12 /* Reserved */
+#define MENELAUS_RESERVED13_IRQ 13 /* Reserved */
+#define MENELAUS_RESERVED14_IRQ 14 /* Reserved */
+#define MENELAUS_RESERVED15_IRQ 15 /* Reserved */
+
+static void menelaus_work(struct work_struct *_menelaus);
+
+/* Initialized by menelaus_init */
+static unsigned short normal_i2c[] = { MENELAUS_I2C_ADDRESS, I2C_CLIENT_END };
+
+I2C_CLIENT_INSMOD;
+
+struct menelaus_chip {
+ unsigned long initialized;
+ struct mutex lock;
+ struct i2c_client client;
+ struct work_struct work;
+ int irq;
+ unsigned vcore_hw_mode:1;
+ void *handlers[16];
+ void (*mmc_callback)(void *data, u8 mask);
+ void *mmc_callback_data;
+};
+
+static struct menelaus_chip menelaus;
+static struct menelaus_platform_data *menelaus_pdata;
+
+static int menelaus_write_reg(int reg, u8 value)
+{
+ int val = i2c_smbus_write_byte_data(&menelaus.client, reg, value);
+
+ if (val < 0) {
+ pr_err("write error");
+ return val;
+ }
+
+ return 0;
+}
+
+static int menelaus_read_reg(int reg)
+{
+ int val = i2c_smbus_read_byte_data(&menelaus.client, reg);
+
+ if (val < 0)
+ pr_err("read error");
+
+ return val;
+}
+
+static int menelaus_enable_irq(int irq)
+{
+ if (irq > 7)
+ return menelaus_write_reg(MENELAUS_INT_MASK2,
+ menelaus_read_reg(MENELAUS_INT_MASK2)
+ & ~(1 << (irq - 8)));
+ else
+ return menelaus_write_reg(MENELAUS_INT_MASK1,
+ menelaus_read_reg(MENELAUS_INT_MASK1)
+ & ~(1 << irq));
+}
+
+static int menelaus_disable_irq(int irq)
+{
+ if (irq > 7)
+ return menelaus_write_reg(menelaus_read_reg(MENELAUS_INT_MASK2)
+ | (1 << (irq - 8)),
+ MENELAUS_INT_MASK2);
+ else
+ return menelaus_write_reg(MENELAUS_INT_MASK1,
+ menelaus_read_reg(MENELAUS_INT_MASK1)
+ | (1 << irq));
+}
+
+static int menelaus_ack_irq(int irq)
+{
+ if (irq > 7)
+ return menelaus_write_reg(MENELAUS_INT_ACK2, 1 << (irq - 8));
+ else
+ return menelaus_write_reg(MENELAUS_INT_ACK1, 1 << irq);
+}
+
+/* Adds a handler for an interrupt. Does not run in interrupt context */
+static int menelaus_add_irq_work(int irq, void * handler)
+{
+ int ret = 0;
+
+ mutex_lock(&menelaus.lock);
+ menelaus.handlers[irq] = handler;
+ ret = menelaus_enable_irq(irq);
+ mutex_unlock(&menelaus.lock);
+
+ return ret;
+}
+
+/* Removes handler for an interrupt */
+static int menelaus_remove_irq_work(int irq)
+{
+ int ret = 0;
+
+ mutex_lock(&menelaus.lock);
+ ret = menelaus_disable_irq(irq);
+ menelaus.handlers[irq] = NULL;
+ mutex_unlock(&menelaus.lock);
+
+ return ret;
+}
+
+/*
+ * Gets scheduled when a card detect interrupt happens. Note that in some cases
+ * this line is wired to card cover switch rather than the card detect switch
+ * in each slot. In this case the cards are not seen by menelaus.
+ * FIXME: Add handling for D1 too
+ */
+static int menelaus_mmc_cd_work(struct menelaus_chip * menelaus_hw)
+{
+ int reg;
+ unsigned char card_mask = 0;
+
+ reg = menelaus_read_reg(MENELAUS_MCT_PIN_ST);
+ if (reg < 0)
+ return reg;
+
+ if (!(reg & 0x1))
+ card_mask |= (1 << 0);
+
+ if (!(reg & 0x2))
+ card_mask |= (1 << 1);
+
+ if (menelaus_hw->mmc_callback)
+ menelaus_hw->mmc_callback(menelaus_hw->mmc_callback_data,
+ card_mask);
+
+ return 0;
+}
+
+/*
+ * Toggles the MMC slots between open-drain and push-pull mode.
+ */
+int menelaus_set_mmc_opendrain(int slot, int enable)
+{
+ int ret, val;
+
+ if (slot != 1 && slot != 2)
+ return -EINVAL;
+ mutex_lock(&menelaus.lock);
+ ret = menelaus_read_reg(MENELAUS_MCT_CTRL1);
+ if (ret < 0) {
+ mutex_unlock(&menelaus.lock);
+ return ret;
+ }
+ val = ret;
+ if (slot == 1) {
+ if (enable)
+ val |= 1 << 2;
+ else
+ val &= ~(1 << 2);
+ } else {
+ if (enable)
+ val |= 1 << 3;
+ else
+ val &= ~(1 << 3);
+ }
+ ret = menelaus_write_reg(MENELAUS_MCT_CTRL1, val);
+ mutex_unlock(&menelaus.lock);
+
+ return ret;
+}
+EXPORT_SYMBOL(menelaus_set_mmc_opendrain);
+
+int menelaus_set_slot_sel(int enable)
+{
+ int ret;
+
+ mutex_lock(&menelaus.lock);
+ ret = menelaus_read_reg(MENELAUS_GPIO_CTRL);
+ if (ret < 0)
+ goto out;
+ ret |= 0x02;
+ if (enable)
+ ret |= 1 << 5;
+ else
+ ret &= ~(1 << 5);
+ ret = menelaus_write_reg(MENELAUS_GPIO_CTRL, ret);
+out:
+ mutex_unlock(&menelaus.lock);
+ return ret;
+}
+EXPORT_SYMBOL(menelaus_set_slot_sel);
+
+int menelaus_set_mmc_slot(int slot, int enable, int power, int cd_en)
+{
+ int ret, val;
+
+ if (slot != 1 && slot != 2)
+ return -EINVAL;
+ if (power >= 3)
+ return -EINVAL;
+
+ mutex_lock(&menelaus.lock);
+
+ ret = menelaus_read_reg(MENELAUS_MCT_CTRL2);
+ if (ret < 0)
+ goto out;
+ val = ret;
+ if (slot == 1) {
+ if (cd_en)
+ val |= (1 << 4) | (1 << 6);
+ else
+ val &= ~((1 << 4) | (1 << 6));
+ } else {
+ if (cd_en)
+ val |= (1 << 5) | (1 << 7);
+ else
+ val &= ~((1 << 5) | (1 << 7));
+ }
+ ret = menelaus_write_reg(MENELAUS_MCT_CTRL2, val);
+ if (ret < 0)
+ goto out;
+
+ ret = menelaus_read_reg(MENELAUS_MCT_CTRL3);
+ if (ret < 0)
+ goto out;
+ val = ret;
+ if (slot == 1) {
+ if (enable)
+ val |= 1 << 0;
+ else
+ val &= ~(1 << 0);
+ } else {
+ int b;
+
+ if (enable)
+ ret |= 1 << 1;
+ else
+ ret &= ~(1 << 1);
+ b = menelaus_read_reg(MENELAUS_MCT_CTRL2);
+ b &= ~0x03;
+ b |= power;
+ ret = menelaus_write_reg(MENELAUS_MCT_CTRL2, b);
+ if (ret < 0)
+ goto out;
+ }
+ /* Disable autonomous shutdown */
+ val &= ~(0x03 << 2);
+ ret = menelaus_write_reg(MENELAUS_MCT_CTRL3, val);
+out:
+ mutex_unlock(&menelaus.lock);
+ return ret;
+}
+EXPORT_SYMBOL(menelaus_set_mmc_slot);
+
+#include <linux/delay.h>
+
+int menelaus_register_mmc_callback(void (*callback)(void *data, u8 card_mask),
+ void *data)
+{
+ int ret = 0;
+
+ menelaus.mmc_callback_data = data;
+ menelaus.mmc_callback = callback;
+ ret = menelaus_add_irq_work(MENELAUS_MMC_S1CD_IRQ,
+ menelaus_mmc_cd_work);
+ if (ret < 0)
+ return ret;
+ ret = menelaus_add_irq_work(MENELAUS_MMC_S2CD_IRQ,
+ menelaus_mmc_cd_work);
+ if (ret < 0)
+ return ret;
+ ret = menelaus_add_irq_work(MENELAUS_MMC_S1D1_IRQ,
+ menelaus_mmc_cd_work);
+ if (ret < 0)
+ return ret;
+ ret = menelaus_add_irq_work(MENELAUS_MMC_S2D1_IRQ,
+ menelaus_mmc_cd_work);
+
+ return ret;
+}
+EXPORT_SYMBOL(menelaus_register_mmc_callback);
+
+void menelaus_unregister_mmc_callback(void)
+{
+ menelaus_remove_irq_work(MENELAUS_MMC_S1CD_IRQ);
+ menelaus_remove_irq_work(MENELAUS_MMC_S2CD_IRQ);
+ menelaus_remove_irq_work(MENELAUS_MMC_S1D1_IRQ);
+ menelaus_remove_irq_work(MENELAUS_MMC_S2D1_IRQ);
+
+ menelaus.mmc_callback = NULL;
+ menelaus.mmc_callback_data = 0;
+}
+EXPORT_SYMBOL(menelaus_unregister_mmc_callback);
+
+struct menelaus_vtg {
+ const char *name;
+ u8 vtg_reg;
+ u8 vtg_shift;
+ u8 vtg_bits;
+ u8 mode_reg;
+};
+
+struct menelaus_vtg_value {
+ u16 vtg;
+ u16 val;
+};
+
+static int menelaus_set_voltage(const struct menelaus_vtg *vtg, int mV,
+ int vtg_val, int mode)
+{
+ int val, ret;
+
+ mutex_lock(&menelaus.lock);
+ if (vtg == 0)
+ goto set_voltage;
+
+ ret = menelaus_read_reg(vtg->vtg_reg);
+ if (ret < 0)
+ goto out;
+ val = ret & ~(((1 << vtg->vtg_bits) - 1) << vtg->vtg_shift);
+ val |= vtg_val << vtg->vtg_shift;
+#ifdef DEBUG
+ printk("menelaus: Setting voltage '%s' to %d mV (reg 0x%02x, val 0x%02x)\n",
+ vtg->name, mV, vtg->vtg_reg, val);
+#endif
+ ret = menelaus_write_reg(vtg->vtg_reg, val);
+ if (ret < 0)
+ goto out;
+set_voltage:
+ ret = menelaus_write_reg(vtg->mode_reg, mode);
+out:
+ mutex_unlock(&menelaus.lock);
+ if (ret == 0) {
+ /* Wait for voltage to stabilize */
+ msleep(1);
+ }
+ return ret;
+}
+
+static int menelaus_get_vtg_value(int vtg, const struct menelaus_vtg_value *tbl,
+ int n)
+{
+ int i;
+
+ for (i = 0; i < n; i++, tbl++)
+ if (tbl->vtg == vtg)
+ return tbl->val;
+ return -EINVAL;
+}
+
+/* Vcore can be programmed in two ways:
+ * SW-controlled: Required voltage is programmed into VCORE_CTRL1
+ * HW-controlled: Required range (roof-floor) is programmed into VCORE_CTRL3
+ * and VCORE_CTRL4
+
+ * Call correct 'set' function accordingly
+ */
+
+static const struct menelaus_vtg_value vcore_values[] = {
+ { 1000, 0 },
+ { 1025, 1 },
+ { 1050, 2 },
+ { 1075, 3 },
+ { 1100, 4 },
+ { 1125, 5 },
+ { 1150, 6 },
+ { 1175, 7 },
+ { 1200, 8 },
+ { 1225, 9 },
+ { 1250, 10 },
+ { 1275, 11 },
+ { 1300, 12 },
+ { 1325, 13 },
+ { 1350, 14 },
+ { 1375, 15 },
+ { 1400, 16 },
+ { 1425, 17 },
+ { 1450, 18 },
+};
+
+int menelaus_set_vcore_sw(unsigned int mV)
+{
+ int val, ret;
+
+ val = menelaus_get_vtg_value(mV, vcore_values, ARRAY_SIZE(vcore_values));
+ if (val < 0)
+ return -EINVAL;
+#ifdef DEBUG
+ printk("menelaus: Setting VCORE to %d mV (val 0x%02x)\n", mV, val);
+#endif
+
+ /* Set SW mode and the voltage in one go. */
+ mutex_lock(&menelaus.lock);
+ ret = menelaus_write_reg(MENELAUS_VCORE_CTRL1, val);
+ if (ret == 0)
+ menelaus.vcore_hw_mode = 0;
+ mutex_unlock(&menelaus.lock);
+ msleep(1);
+
+ return ret;
+}
+
+int menelaus_set_vcore_hw(unsigned int roof_mV, unsigned int floor_mV)
+{
+ int fval, rval, val, ret;
+
+ rval = menelaus_get_vtg_value(roof_mV, vcore_values, ARRAY_SIZE(vcore_values));
+ if (rval < 0)
+ return -EINVAL;
+ fval = menelaus_get_vtg_value(floor_mV, vcore_values, ARRAY_SIZE(vcore_values));
+ if (fval < 0)
+ return -EINVAL;
+
+#ifdef DEBUG
+ printk("menelaus: Setting VCORE FLOOR to %d mV and ROOF to %d mV\n",
+ floor_mV, roof_mV);
+#endif
+
+ mutex_lock(&menelaus.lock);
+ ret = menelaus_write_reg(MENELAUS_VCORE_CTRL3, fval);
+ if (ret < 0)
+ goto out;
+ ret = menelaus_write_reg(MENELAUS_VCORE_CTRL4, rval);
+ if (ret < 0)
+ goto out;
+ if (!menelaus.vcore_hw_mode) {
+ val = menelaus_read_reg(MENELAUS_VCORE_CTRL1);
+ val |= ((1 << 7) | (1 << 5)); /* HW mode, turn OFF byte comparator */
+ ret = menelaus_write_reg(MENELAUS_VCORE_CTRL1, val);
+ menelaus.vcore_hw_mode = 1;
+ }
+ msleep(1);
+out:
+ mutex_unlock(&menelaus.lock);
+ return ret;
+}
+
+static const struct menelaus_vtg vmem_vtg = {
+ .name = "VMEM",
+ .vtg_reg = MENELAUS_LDO_CTRL1,
+ .vtg_shift = 0,
+ .vtg_bits = 2,
+ .mode_reg = MENELAUS_LDO_CTRL3,
+};
+
+static const struct menelaus_vtg_value vmem_values[] = {
+ { 1500, 0 },
+ { 1800, 1 },
+ { 1900, 2 },
+ { 2500, 3 },
+};
+
+int menelaus_set_vmem(unsigned int mV)
+{
+ int val;
+
+ if (mV == 0)
+ return menelaus_set_voltage(&vmem_vtg, 0, 0, 0);
+
+ val = menelaus_get_vtg_value(mV, vmem_values, ARRAY_SIZE(vmem_values));
+ if (val < 0)
+ return -EINVAL;
+ return menelaus_set_voltage(&vmem_vtg, mV, val, 0x02);
+}
+EXPORT_SYMBOL(menelaus_set_vmem);
+
+static const struct menelaus_vtg vio_vtg = {
+ .name = "VIO",
+ .vtg_reg = MENELAUS_LDO_CTRL1,
+ .vtg_shift = 2,
+ .vtg_bits = 2,
+ .mode_reg = MENELAUS_LDO_CTRL4,
+};
+
+static const struct menelaus_vtg_value vio_values[] = {
+ { 1500, 0 },
+ { 1800, 1 },
+ { 2500, 2 },
+ { 2800, 3 },
+};
+
+int menelaus_set_vio(unsigned int mV)
+{
+ int val;
+
+ if (mV == 0)
+ return menelaus_set_voltage(&vio_vtg, 0, 0, 0);
+
+ val = menelaus_get_vtg_value(mV, vio_values, ARRAY_SIZE(vio_values));
+ if (val < 0)
+ return -EINVAL;
+ return menelaus_set_voltage(&vio_vtg, mV, val, 0x02);
+}
+EXPORT_SYMBOL(menelaus_set_vio);
+
+static const struct menelaus_vtg_value vdcdc_values[] = {
+ { 1500, 0 },
+ { 1800, 1 },
+ { 2000, 2 },
+ { 2200, 3 },
+ { 2400, 4 },
+ { 2800, 5 },
+ { 3000, 6 },
+ { 3300, 7 },
+};
+
+static const struct menelaus_vtg vdcdc2_vtg = {
+ .name = "VDCDC2",
+ .vtg_reg = MENELAUS_DCDC_CTRL1,
+ .vtg_shift = 0,
+ .vtg_bits = 3,
+ .mode_reg = MENELAUS_DCDC_CTRL2,
+};
+
+static const struct menelaus_vtg vdcdc3_vtg = {
+ .name = "VDCDC3",
+ .vtg_reg = MENELAUS_DCDC_CTRL1,
+ .vtg_shift = 3,
+ .vtg_bits = 3,
+ .mode_reg = MENELAUS_DCDC_CTRL3,
+};
+
+int menelaus_set_vdcdc(int dcdc, unsigned int mV)
+{
+ const struct menelaus_vtg *vtg;
+ int val;
+
+ if (dcdc != 2 && dcdc != 3)
+ return -EINVAL;
+ if (dcdc == 2)
+ vtg = &vdcdc2_vtg;
+ else
+ vtg = &vdcdc3_vtg;
+
+ if (mV == 0)
+ return menelaus_set_voltage(vtg, 0, 0, 0);
+
+ val = menelaus_get_vtg_value(mV, vdcdc_values, ARRAY_SIZE(vdcdc_values));
+ if (val < 0)
+ return -EINVAL;
+ return menelaus_set_voltage(vtg, mV, val, 0x03);
+}
+
+static const struct menelaus_vtg_value vmmc_values[] = {
+ { 1850, 0 },
+ { 2800, 1 },
+ { 3000, 2 },
+ { 3100, 3 },
+};
+
+static const struct menelaus_vtg vmmc_vtg = {
+ .name = "VMMC",
+ .vtg_reg = MENELAUS_LDO_CTRL1,
+ .vtg_shift = 6,
+ .vtg_bits = 2,
+ .mode_reg = MENELAUS_LDO_CTRL7,
+};
+
+int menelaus_set_vmmc(unsigned int mV)
+{
+ int val;
+
+ if (mV == 0)
+ return menelaus_set_voltage(&vmmc_vtg, 0, 0, 0);
+
+ val = menelaus_get_vtg_value(mV, vmmc_values, ARRAY_SIZE(vmmc_values));
+ if (val < 0)
+ return -EINVAL;
+ return menelaus_set_voltage(&vmmc_vtg, mV, val, 0x02);
+}
+EXPORT_SYMBOL(menelaus_set_vmmc);
+
+
+static const struct menelaus_vtg_value vaux_values[] = {
+ { 1500, 0 },
+ { 1800, 1 },
+ { 2500, 2 },
+ { 2800, 3 },
+};
+
+static const struct menelaus_vtg vaux_vtg = {
+ .name = "VAUX",
+ .vtg_reg = MENELAUS_LDO_CTRL1,
+ .vtg_shift = 4,
+ .vtg_bits = 2,
+ .mode_reg = MENELAUS_LDO_CTRL6,
+};
+
+int menelaus_set_vaux(unsigned int mV)
+{
+ int val;
+
+ if (mV == 0)
+ return menelaus_set_voltage(&vaux_vtg, 0, 0, 0);
+
+ val = menelaus_get_vtg_value(mV, vaux_values, ARRAY_SIZE(vaux_values));
+ if (val < 0)
+ return -EINVAL;
+ return menelaus_set_voltage(&vaux_vtg, mV, val, 0x02);
+}
+EXPORT_SYMBOL(menelaus_set_vaux);
+
+int menelaus_get_slot_pin_states(void)
+{
+ return menelaus_read_reg(MENELAUS_MCT_PIN_ST);
+}
+EXPORT_SYMBOL(menelaus_get_slot_pin_states);
+
+int menelaus_set_regulator_sleep(int enable, u32 val)
+{
+ int t, ret;
+
+ mutex_lock(&menelaus.lock);
+ ret = menelaus_write_reg(MENELAUS_SLEEP_CTRL2, val);
+ if (ret < 0)
+ goto out;
+#ifdef DEBUG
+ printk("menelaus: regulator sleep configuration: %02x\n", val);
+#endif
+ ret = menelaus_read_reg(MENELAUS_GPIO_CTRL);
+ if (ret < 0)
+ goto out;
+ t = ((1 << 6) | 0x04);
+ if (enable)
+ ret |= t;
+ else
+ ret &= ~t;
+ ret = menelaus_write_reg(MENELAUS_GPIO_CTRL, ret);
+out:
+ mutex_unlock(&menelaus.lock);
+ return ret;
+}
+
+/*-----------------------------------------------------------------------*/
+
+/* Handles Menelaus interrupts. Does not run in interrupt context */
+static void menelaus_work(struct work_struct *_menelaus)
+{
+ struct menelaus_chip *menelaus =
+ container_of(_menelaus, struct menelaus_chip, work);
+ int (*handler)(struct menelaus_chip *menelaus);
+
+ while (1) {
+ int i;
+ unsigned char isr;
+
+ isr = menelaus_read_reg(MENELAUS_INT_STATUS1) |
+ (menelaus_read_reg(MENELAUS_INT_STATUS2) << 8);
+
+ if (!isr)
+ break;
+
+ for (i = 0; i < IH_MENELAUS_IRQS; i++) {
+ if (isr & (1 << i)) {
+ mutex_lock(&menelaus->lock);
+ menelaus_disable_irq(i);
+ menelaus_ack_irq(i);
+ if (menelaus->handlers[i]) {
+ handler = menelaus->handlers[i];
+ handler(menelaus);
+ }
+ menelaus_enable_irq(i);
+ mutex_unlock(&menelaus->lock);
+ }
+ }
+ }
+ enable_irq(menelaus->irq);
+}
+
+/*
+ * We cannot use I2C in interrupt context, so we just schedule work.
+ */
+static irqreturn_t menelaus_irq(int irq, void *_menelaus)
+{
+ struct menelaus_chip *menelaus = _menelaus;
+
+ disable_irq_nosync(irq);
+ (void)schedule_work(&menelaus->work);
+
+ return IRQ_HANDLED;
+}
+
+static struct i2c_driver menelaus_i2c_driver;
+
+static int menelaus_probe(struct i2c_adapter *adapter, int address, int kind)
+{
+ struct i2c_client *c;
+ int rev = 0, val;
+ int err = 0;
+
+ if (test_and_set_bit(0, &menelaus.initialized))
+ return -EBUSY;
+
+ c = &menelaus.client;
+ strncpy(c->name, DRIVER_NAME, sizeof(c->name));
+ c->addr = address;
+ c->adapter = adapter;
+ c->driver = &menelaus_i2c_driver;
+ c->flags = 0;
+
+ if ((err = i2c_attach_client(c)) < 0) {
+ pr_err("couldn't attach\n");
+ goto fail1;
+ }
+
+ /* If a true probe check the device */
+ if (kind < 0 && (rev = menelaus_read_reg(MENELAUS_REV)) < 0) {
+ pr_err("device not found");
+ err = -ENODEV;
+ goto fail2;
+ }
+
+ /* Most likely Menelaus interrupt is at SYS_NIRQ */
+ omap_cfg_reg(W19_24XX_SYS_NIRQ);
+ menelaus.irq = INT_24XX_SYS_NIRQ;
+
+ /* Ack and disable all Menelaus interrupts */
+ menelaus_write_reg(MENELAUS_INT_ACK1, 0xff);
+ menelaus_write_reg(MENELAUS_INT_ACK2, 0xff);
+ menelaus_write_reg(MENELAUS_INT_MASK1, 0xff);
+ menelaus_write_reg(MENELAUS_INT_MASK2, 0xff);
+
+ /* Set output buffer strengths */
+ menelaus_write_reg(MENELAUS_MCT_CTRL1, 0x73);
+
+ err = request_irq(menelaus.irq, menelaus_irq, IRQF_DISABLED,
+ DRIVER_NAME, &menelaus);
+ if (err) {
+ printk(KERN_ERR "Could not get Menelaus IRQ\n");
+ goto fail2;
+ }
+
+ mutex_init(&menelaus.lock);
+ INIT_WORK(&menelaus.work, menelaus_work);
+
+ if (kind < 0)
+ pr_info("Menelaus rev %d.%d\n", rev >> 4, rev & 0x0f);
+
+ val = menelaus_read_reg(MENELAUS_VCORE_CTRL1);
+ if (val < 0)
+ goto fail3;
+ if (val & (1 << 7))
+ menelaus.vcore_hw_mode = 1;
+ else
+ menelaus.vcore_hw_mode = 0;
+
+ if (menelaus_pdata != NULL && menelaus_pdata->late_init != NULL) {
+ err = menelaus_pdata->late_init(&c->dev);
+ if (err < 0)
+ goto fail3;
+ }
+
+ return 0;
+fail3:
+ free_irq(menelaus.irq, &menelaus);
+ flush_scheduled_work();
+fail2:
+ i2c_detach_client(c);
+fail1:
+ clear_bit(0, &menelaus.initialized);
+ return err;
+}
+
+static int menelaus_remove(struct i2c_client *client)
+{
+ int err;
+
+ free_irq(menelaus.irq, &menelaus);
+
+ if ((err = i2c_detach_client(client))) {
+ pr_err("client deregistration failed\n");
+ return err;
+ }
+
+ clear_bit(0, &menelaus.initialized);
+
+ return 0;
+}
+
+/*-----------------------------------------------------------------------*/
+
+static int menelaus_scan_bus(struct i2c_adapter *bus)
+{
+ if (!i2c_check_functionality(bus, I2C_FUNC_SMBUS_BYTE_DATA |
+ I2C_FUNC_SMBUS_WRITE_BYTE)) {
+ pr_err("invalid i2c bus functionality\n");
+ return -EINVAL;
+ }
+
+ return i2c_probe(bus, &addr_data, menelaus_probe);
+}
+
+static struct i2c_driver menelaus_i2c_driver = {
+ .driver = {
+ .name = DRIVER_NAME,
+ },
+ .id = I2C_DRIVERID_MISC, /*FIXME:accroding to i2c-ids.h */
+ .class = I2C_CLASS_HWMON,
+ .attach_adapter = menelaus_scan_bus,
+ .detach_client = menelaus_remove,
+};
+
+static int __init menelaus_init(void)
+{
+ int res;
+
+ if ((res = i2c_add_driver(&menelaus_i2c_driver)) < 0) {
+ pr_err("driver registration failed\n");
+ return res;
+ }
+
+ return 0;
+}
+
+static void __exit menelaus_exit(void)
+{
+ if (i2c_del_driver(&menelaus_i2c_driver) < 0)
+ pr_err("driver remove failed\n");
+
+ /* FIXME: Shutdown menelaus parts that can be shut down */
+}
+
+void __init menelaus_set_platform_data(struct menelaus_platform_data *pdata)
+{
+ menelaus_pdata = pdata;
+}
+
+MODULE_AUTHOR("Texas Instruments, Inc.");
+MODULE_DESCRIPTION("I2C interface for Menelaus.");
+MODULE_LICENSE("GPL");
+
+module_init(menelaus_init);
+module_exit(menelaus_exit);
--- /dev/null
+/*
+ * Texas Instrumens TLV320AIC23 audio codec's i2c interface.
+ *
+ * Copyright (c) by Kai Svahn <kai.svahn@nokia.com>
+ * Copyright (c) by Jussi Laako <jussi.laako@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
+ * 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/module.h>
+#include <linux/init.h>
+#include <linux/i2c.h>
+#include <linux/slab.h>
+#include <linux/device.h>
+#include <linux/platform_device.h>
+#include <asm/io.h>
+#include <asm/arch/aic23.h>
+#include <asm/arch/mcbsp.h>
+
+#define TLV320AIC23_VERSION "1.8"
+#define TLV320AIC23_DATE "10-Feb-2006"
+#define MAX_VOL 100
+#define MIN_VOL 0
+#define MAX_GAIN 100
+#define MIN_GAIN 0
+#define OUTPUT_VOLUME_MIN LHV_MIN
+#define OUTPUT_VOLUME_MAX LHV_MAX
+#define OUTPUT_VOLUME_RANGE (OUTPUT_VOLUME_MAX - OUTPUT_VOLUME_MIN)
+#define INPUT_VOLUME_MIN LIV_MIN
+#define INPUT_VOLUME_MAX LIV_MAX
+#define INPUT_VOLUME_RANGE (INPUT_VOLUME_MAX - INPUT_VOLUME_MIN)
+
+/* I2C Addresses to scan */
+static unsigned short normal_i2c[] = { TLV320AIC23ID1, TLV320AIC23ID2, \
+ I2C_CLIENT_END };
+/*static unsigned short normal_i2c_range[] = { I2C_CLIENT_END };*/
+
+/* This makes all addr_data:s */
+I2C_CLIENT_INSMOD;
+
+static struct i2c_driver aic23_driver;
+static struct i2c_client *new_client;
+static int selftest;
+
+static struct aic23_info {
+ u16 volume_reg_left;
+ u16 volume_reg_right;
+ u16 input_gain_reg_left;
+ u16 input_gain_reg_right;
+ u16 power; /* For POWER_DOWN_CONTROL_ADDR */
+ u16 mask; /* For ANALOG_AUDIO_CONTROL_ADDR */
+ int mic_loopback;
+ int mic_enable;
+ int sta;
+ int power_down;
+ int initialized;
+} aic23_info_l;
+
+static int _aic23_write_value(struct i2c_client *client, u8 reg, u16 value)
+{
+ u8 val, wreg;
+
+ /* TLV320AIC23 has 7 bit address and 9 bits of data
+ * so we need to switch one data bit into reg and rest
+ * of data into val
+ */
+
+ wreg = (reg << 1);
+ val = (0x01 & (value >> 8));
+ wreg = (wreg | val);
+ val = (0x00ff & value);
+
+ return i2c_smbus_write_byte_data(client, wreg, val);
+}
+
+int aic23_write_value(u8 reg, u16 value)
+{
+ static struct i2c_client *client;
+ client = new_client;
+ _aic23_write_value(client, reg, value);
+
+ return 0;
+}
+
+static int aic23_detect_client(struct i2c_adapter *adapter, int address,
+ int kind)
+{
+ int err = 0;
+ const char *client_name = "TLV320AIC23 Audio Codec";
+
+ if (!i2c_check_functionality(adapter, I2C_FUNC_SMBUS_WORD_DATA |
+ I2C_FUNC_SMBUS_WRITE_BYTE)) {
+ printk(KERN_WARNING "%s functinality check failed\n",
+ client_name);
+ return err;
+ }
+
+ if (!(new_client = kmalloc(sizeof(struct i2c_client),
+ GFP_KERNEL))) {
+ err = -ENOMEM;
+ printk(KERN_WARNING "Couldn't allocate memory for %s\n",
+ client_name);
+ return err;
+ }
+
+ memset(new_client, 0x00, sizeof(struct i2c_client));
+ new_client->addr = address;
+ new_client->adapter = adapter;
+ new_client->driver = &aic23_driver;
+ new_client->flags = 0;
+ strlcpy(new_client->name, client_name, I2C_NAME_SIZE);
+
+ if ((err = i2c_attach_client(new_client))) {
+ printk(KERN_WARNING "Couldn't attach %s\n", client_name);
+ kfree(new_client);
+ return err;
+ }
+ return 0;
+}
+
+static int aic23_detach_client(struct i2c_client *client)
+{
+ int err;
+
+ if ((err = i2c_detach_client(client))) {
+ printk("aic23.o: Client deregistration failed, \
+ client not detached.\n");
+ return err;
+ }
+ kfree(client);
+ return 0;
+}
+
+static int aic23_attach_adapter(struct i2c_adapter *adapter)
+{
+ int res;
+
+ res = i2c_probe(adapter, &addr_data, &aic23_detect_client);
+ return res;
+}
+
+static struct i2c_driver aic23_driver = {
+ .driver = {
+ .name = "OMAP+TLV320AIC23 codec",
+ /*.flags = I2C_DF_NOTIFY,*/
+ },
+ .id = I2C_DRIVERID_MISC, /* Experimental ID */
+ .attach_adapter = aic23_attach_adapter,
+ .detach_client = aic23_detach_client,
+};
+
+/*
+ * Configures the McBSP3 which is used to send clock to the AIC23 codec.
+ * The input clock rate from DSP is 12MHz.
+ * The DSP clock must be on before this is called.
+ */
+static int omap_mcbsp3_aic23_clock_init(void)
+{
+ u16 w;
+
+ /* enable 12MHz clock to mcbsp 1 & 3 */
+ __raw_writew(__raw_readw(DSP_IDLECT2) | (1<<1), DSP_IDLECT2);
+ __raw_writew(__raw_readw(DSP_RSTCT2) | 1 | 1<<1, DSP_RSTCT2);
+
+ /* disable sample rate generator */
+ OMAP_MCBSP_WRITE(OMAP1610_MCBSP3_BASE, SPCR1, 0x0000);
+ OMAP_MCBSP_WRITE(OMAP1610_MCBSP3_BASE, SPCR2, 0x0000);
+
+ /* pin control register */
+ OMAP_MCBSP_WRITE(OMAP1610_MCBSP3_BASE, PCR0,(CLKXM | CLKXP | CLKRP));
+
+ /* configure srg to send 12MHz pulse from dsp peripheral clock */
+ OMAP_MCBSP_WRITE(OMAP1610_MCBSP3_BASE, SRGR1, 0x0000);
+ OMAP_MCBSP_WRITE(OMAP1610_MCBSP3_BASE, SRGR2, CLKSM);
+
+ /* enable sample rate generator */
+ w = OMAP_MCBSP_READ(OMAP1610_MCBSP3_BASE, SPCR2);
+ OMAP_MCBSP_WRITE(OMAP1610_MCBSP3_BASE, SPCR2, (w | FREE | GRST));
+ printk("Clock enabled to MCBSP1 & 3 \n");
+
+ return 0;
+}
+
+static void update_volume_left(int volume)
+{
+ u16 val = 0;
+ val = ((volume * OUTPUT_VOLUME_RANGE) / 100) + OUTPUT_VOLUME_MIN;
+ aic23_write_value(LEFT_CHANNEL_VOLUME_ADDR, val);
+ aic23_info_l.volume_reg_left = volume;
+}
+
+static void update_volume_right(int volume)
+{
+ u16 val = 0;
+ val = ((volume * OUTPUT_VOLUME_RANGE) / 100) + OUTPUT_VOLUME_MIN;
+ aic23_write_value(RIGHT_CHANNEL_VOLUME_ADDR, val);
+ aic23_info_l.volume_reg_right = volume;
+}
+
+static void set_mic(int mic_en)
+{
+ u16 dg_ctrl;
+
+ if (mic_en) {
+ aic23_info_l.power = OSC_OFF | LINE_OFF;
+ dg_ctrl = ADCHP_ON;
+ aic23_info_l.mask &= ~MICM_MUTED;
+ aic23_info_l.mask |= MICB_20DB; /* STE_ENABLED */
+ } else {
+ aic23_info_l.power =
+ OSC_OFF | ADC_OFF | MIC_OFF | LINE_OFF;
+ dg_ctrl = 0x00;
+ aic23_info_l.mask =
+ DAC_SELECTED | INSEL_MIC | MICM_MUTED;
+ }
+ aic23_write_value(POWER_DOWN_CONTROL_ADDR,
+ aic23_info_l.power);
+ aic23_write_value(DIGITAL_AUDIO_CONTROL_ADDR, dg_ctrl);
+ aic23_write_value(ANALOG_AUDIO_CONTROL_ADDR,
+ aic23_info_l.mask);
+ aic23_info_l.mic_enable = mic_en;
+
+ printk(KERN_INFO "aic23 mic state: %i\n", mic_en);
+}
+
+static void aic23_init_power(void)
+{
+ aic23_write_value(RESET_CONTROL_ADDR, 0x00);
+
+ if (aic23_info_l.initialized == 0) {
+ aic23_write_value(LEFT_CHANNEL_VOLUME_ADDR, LHV_MIN);
+ aic23_write_value(RIGHT_CHANNEL_VOLUME_ADDR, LHV_MIN);
+ }
+ else {
+ update_volume_left(aic23_info_l.volume_reg_left);
+ update_volume_right(aic23_info_l.volume_reg_right);
+ }
+
+ aic23_info_l.mask = DAC_SELECTED | INSEL_MIC | MICM_MUTED;
+ aic23_write_value(ANALOG_AUDIO_CONTROL_ADDR,
+ aic23_info_l.mask);
+ aic23_write_value(DIGITAL_AUDIO_CONTROL_ADDR, 0x00);
+ aic23_write_value(DIGITAL_AUDIO_FORMAT_ADDR, LRP_ON | FOR_DSP);
+ aic23_write_value(SAMPLE_RATE_CONTROL_ADDR, USB_CLK_ON);
+ aic23_write_value(DIGITAL_INTERFACE_ACT_ADDR, ACT_ON);
+ aic23_info_l.power = OSC_OFF | ADC_OFF | MIC_OFF | LINE_OFF;
+ aic23_write_value(POWER_DOWN_CONTROL_ADDR,
+ aic23_info_l.power);
+
+ /* enable mic input */
+ if (aic23_info_l.mic_enable)
+ set_mic(aic23_info_l.mic_enable);
+
+ printk(KERN_INFO "aic23_init_power() done\n");
+}
+
+void aic23_power_down(void)
+{
+ if (aic23_info_l.initialized) {
+ printk("aic23 powering down\n");
+ aic23_write_value(POWER_DOWN_CONTROL_ADDR, 0xff);
+ }
+ aic23_info_l.power_down = 1;
+}
+
+void aic23_power_up(void)
+{
+ if (aic23_info_l.initialized) {
+ printk("aic23 powering up\n");
+ aic23_init_power();
+ }
+ aic23_info_l.power_down = 0;
+}
+
+/*----------------------------------------------------------------------*/
+/* sysfs initializations */
+/*----------------------------------------------------------------------*/
+
+static ssize_t store_volume_left(struct device *dev,
+ struct device_attribute *attr,
+ const char *buf, size_t count)
+{
+ signed volume;
+
+ sscanf(buf, "%i", &volume);
+
+ if (volume < MIN_VOL) {
+ aic23_power_down();
+ return count;
+ } else if (volume > MIN_VOL && aic23_info_l.power_down) {
+ aic23_info_l.volume_reg_left = volume;
+ aic23_power_up();
+ return count;
+ }
+ if (volume > MAX_VOL)
+ volume = MAX_VOL;
+
+ update_volume_left(volume);
+ return count;
+}
+
+static ssize_t show_volume_left(struct device *dev,
+ struct device_attribute *attr, char *buf)
+{
+ return sprintf(buf, "%u\n", aic23_info_l.volume_reg_left);
+}
+
+static DEVICE_ATTR(volume_left, S_IRUGO | S_IWUGO,
+ show_volume_left, store_volume_left);
+
+static ssize_t store_volume_right(struct device *dev,
+ struct device_attribute *attr,
+ const char *buf, size_t count)
+{
+ signed volume;
+
+ sscanf(buf, "%i", &volume);
+ if (volume < MIN_VOL) {
+ aic23_power_down();
+ return count;
+ } else if (volume > MIN_VOL && aic23_info_l.power_down) {
+ aic23_info_l.volume_reg_right = volume;
+ aic23_power_up();
+ return count;
+ }
+ if (volume > MAX_VOL)
+ volume = MAX_VOL;
+
+ update_volume_right(volume);
+ return count;
+}
+
+static ssize_t show_volume_right(struct device *dev,
+ struct device_attribute *attr, char *buf)
+{
+ return sprintf(buf, "%u\n", aic23_info_l.volume_reg_right);
+}
+
+static DEVICE_ATTR(volume_right, S_IRUGO | S_IWUGO,
+ show_volume_right, store_volume_right);
+
+static ssize_t store_gain_left(struct device *dev,
+ struct device_attribute *attr,
+ const char *buf, size_t count)
+{
+ u16 val = 0;
+ unsigned gain;
+
+ sscanf(buf, "%u", &gain);
+ if (gain > MAX_VOL)
+ gain = MAX_VOL;
+
+ val = ((gain * INPUT_VOLUME_RANGE) / 100) + INPUT_VOLUME_MIN;
+ aic23_write_value(LEFT_LINE_VOLUME_ADDR, val);
+ aic23_info_l.input_gain_reg_left = gain;
+
+ return count;
+}
+
+static ssize_t show_gain_left(struct device *dev,
+ struct device_attribute *attr, char *buf)
+{
+ return sprintf(buf, "%u\n", aic23_info_l.input_gain_reg_left);
+}
+
+static DEVICE_ATTR(gain_left, S_IRUGO | S_IWUSR, show_gain_left,
+ store_gain_left);
+
+static ssize_t store_gain_right(struct device *dev,
+ struct device_attribute *attr,
+ const char *buf, size_t count)
+{
+ u16 val = 0;
+ unsigned gain;
+
+ sscanf(buf, "%u", &gain);
+ if (gain > MAX_VOL)
+ gain = MAX_VOL;
+
+ val = ((gain * INPUT_VOLUME_RANGE) / 100) + INPUT_VOLUME_MIN;
+ aic23_write_value(RIGHT_LINE_VOLUME_ADDR, val);
+ aic23_info_l.input_gain_reg_right = gain;
+
+ return count;
+}
+
+static ssize_t show_gain_right(struct device *dev,
+ struct device_attribute *attr, char *buf)
+{
+ return sprintf(buf, "%u\n", aic23_info_l.input_gain_reg_right);
+}
+
+static DEVICE_ATTR(gain_right, S_IRUGO | S_IWUSR, show_gain_right,
+ store_gain_right);
+
+static ssize_t store_mic_loopback(struct device *dev,
+ struct device_attribute *attr,
+ const char *buf, size_t count)
+{
+ int mic;
+
+ sscanf(buf, "%i", &mic);
+ if (mic > 0) {
+ aic23_write_value(POWER_DOWN_CONTROL_ADDR, \
+ OSC_OFF | ADC_OFF | LINE_OFF);
+ aic23_info_l.mask = STE_ENABLED | DAC_SELECTED \
+ | INSEL_MIC | MICB_20DB;
+ aic23_write_value(ANALOG_AUDIO_CONTROL_ADDR,
+ aic23_info_l.mask);
+ mic = 1;
+ }
+ else {
+ aic23_write_value(POWER_DOWN_CONTROL_ADDR, \
+ OSC_OFF | ADC_OFF | MIC_OFF | LINE_OFF);
+ mic = 0;
+ }
+ aic23_info_l.mic_loopback = mic;
+
+ return count;
+}
+
+static ssize_t show_mic_loopback(struct device *dev,
+ struct device_attribute *attr, char *buf)
+{
+ return sprintf(buf, "%i\n", aic23_info_l.mic_loopback);
+}
+
+static DEVICE_ATTR(mic_loopback, S_IRUGO | S_IWUSR,
+ show_mic_loopback, store_mic_loopback);
+
+static ssize_t store_st_attenuation(struct device *dev,
+ struct device_attribute *attr,
+ const char *buf, size_t count)
+{
+ unsigned sta;
+ u16 tmp;
+
+ sscanf(buf, "%u", &sta);
+ if (sta > 3)
+ sta = 3;
+
+ tmp = aic23_info_l.mask;
+ tmp &= 0x3f;
+
+ aic23_info_l.mask = tmp | STA_REG(sta);
+ aic23_write_value(ANALOG_AUDIO_CONTROL_ADDR,
+ aic23_info_l.mask);
+ aic23_info_l.sta = sta;
+
+ return count;
+}
+
+static ssize_t show_st_attenuation(struct device *dev,
+ struct device_attribute *attr, char *buf)
+{
+ return sprintf(buf, "%i\n", aic23_info_l.sta);
+}
+
+static DEVICE_ATTR(st_attenuation, S_IRUGO | S_IWUSR,
+ show_st_attenuation, store_st_attenuation);
+
+static ssize_t store_mic_enable(struct device *dev,
+ struct device_attribute *attr,
+ const char *buf, size_t count)
+{
+ int mic;
+
+ sscanf(buf, "%i", &mic);
+ set_mic(mic);
+
+ return count;
+}
+
+static ssize_t show_mic_enable(struct device *dev,
+ struct device_attribute *attr, char *buf)
+{
+ return sprintf(buf, "%i\n", aic23_info_l.mic_enable);
+}
+
+static DEVICE_ATTR(mic_enable, S_IRUGO | S_IWUSR,
+ show_mic_enable, store_mic_enable);
+
+static ssize_t show_audio_selftest(struct device *dev,
+ struct device_attribute *attr, char *buf)
+{
+ return sprintf(buf, "%i\n", selftest);
+}
+
+static DEVICE_ATTR(audio_selftest, S_IRUGO | S_IWUSR,
+ show_audio_selftest, NULL);
+
+static int audio_i2c_probe(struct platform_device *dev)
+{
+ int r;
+
+ if ((r = device_create_file(&dev->dev, &dev_attr_volume_left)) != 0)
+ return r;
+ else if ((r = device_create_file(&dev->dev,
+ &dev_attr_volume_right)) != 0)
+ goto err_volume_left;
+ else if ((r = device_create_file(&dev->dev,
+ &dev_attr_gain_right)) != 0)
+ goto err_volume_right;
+ else if ((r = device_create_file(&dev->dev,
+ &dev_attr_gain_left)) != 0)
+ goto err_gain_right;
+ else if ((r = device_create_file(&dev->dev,
+ &dev_attr_mic_loopback)) != 0)
+ goto err_gain_left;
+ else if ((r = device_create_file(&dev->dev,
+ &dev_attr_mic_enable)) != 0)
+ goto err_mic_loopback;
+ else if ((r = device_create_file(&dev->dev,
+ &dev_attr_st_attenuation)) != 0)
+ goto err_mic_enable;
+ else if ((r = device_create_file(&dev->dev,
+ &dev_attr_audio_selftest)) != 0)
+ goto err_st_attenuation;
+ else
+ return r;
+
+err_st_attenuation:
+ device_remove_file(&dev->dev, &dev_attr_st_attenuation);
+err_mic_enable:
+ device_remove_file(&dev->dev, &dev_attr_mic_enable);
+err_mic_loopback:
+ device_remove_file(&dev->dev, &dev_attr_mic_loopback);
+err_gain_left:
+ device_remove_file(&dev->dev, &dev_attr_gain_left);
+err_gain_right:
+ device_remove_file(&dev->dev, &dev_attr_gain_right);
+err_volume_right:
+ device_remove_file(&dev->dev, &dev_attr_volume_right);
+err_volume_left:
+ device_remove_file(&dev->dev, &dev_attr_volume_left);
+
+ return r;
+}
+
+static int audio_i2c_remove(struct platform_device *dev)
+{
+ device_remove_file(&dev->dev, &dev_attr_st_attenuation);
+ device_remove_file(&dev->dev, &dev_attr_mic_enable);
+ device_remove_file(&dev->dev, &dev_attr_mic_loopback);
+ device_remove_file(&dev->dev, &dev_attr_gain_left);
+ device_remove_file(&dev->dev, &dev_attr_gain_right);
+ device_remove_file(&dev->dev, &dev_attr_volume_right);
+ device_remove_file(&dev->dev, &dev_attr_volume_left);
+
+ return 0;
+}
+
+/*----------------------------------------------------------------*/
+/* PM functions */
+/*----------------------------------------------------------------*/
+
+static void audio_i2c_shutdown(struct platform_device *dev)
+{
+ /* Let's mute the codec before powering off to prevent
+ * glitch in the sound
+ */
+ aic23_write_value(LEFT_CHANNEL_VOLUME_ADDR, LHV_MIN);
+ aic23_write_value(RIGHT_CHANNEL_VOLUME_ADDR, LHV_MIN);
+ aic23_power_down();
+}
+
+static int audio_i2c_suspend(struct platform_device *dev, pm_message_t state)
+{
+ /* Let's mute the codec before powering off to prevent
+ * glitch in the sound
+ */
+ aic23_write_value(LEFT_CHANNEL_VOLUME_ADDR, LHV_MIN);
+ aic23_write_value(RIGHT_CHANNEL_VOLUME_ADDR, LHV_MIN);
+ aic23_power_down();
+
+ return 0;
+}
+
+static int audio_i2c_resume(struct platform_device *dev)
+{
+ aic23_power_up();
+
+ return 0;
+}
+
+static struct platform_driver audio_i2c_driver = {
+ .driver = {
+ .owner = THIS_MODULE,
+ .name = "audio-i2c",
+ },
+ .shutdown = audio_i2c_shutdown,
+ .probe = audio_i2c_probe,
+ .remove = audio_i2c_remove,
+ .suspend = audio_i2c_suspend,
+ .resume = audio_i2c_resume,
+};
+
+static struct platform_device audio_i2c_device = {
+ .name = "audio-i2c",
+ .id = -1,
+};
+
+/*----------------------------------------------------------------*/
+
+static int __init aic23_init(void)
+{
+ selftest = 0;
+ aic23_info_l.initialized = 0;
+
+ if (i2c_add_driver(&aic23_driver)) {
+ printk("aic23 i2c: Driver registration failed, \
+ module not inserted.\n");
+ selftest = -ENODEV;
+ return selftest;
+ }
+
+ if (platform_driver_register(&audio_i2c_driver)) {
+ printk(KERN_WARNING "Failed to register audio i2c driver\n");
+ selftest = -ENODEV;
+ return selftest;
+ }
+
+ if (platform_device_register(&audio_i2c_device)) {
+ printk(KERN_WARNING "Failed to register audio i2c device\n");
+ platform_driver_unregister(&audio_i2c_driver);
+ selftest = -ENODEV;
+ return selftest;
+ }
+ /* FIXME: Do in board-specific file */
+ omap_mcbsp3_aic23_clock_init();
+ if (!aic23_info_l.power_down)
+ aic23_power_up();
+ aic23_info_l.initialized = 1;
+ printk("TLV320AIC23 I2C version %s (%s)\n",
+ TLV320AIC23_VERSION, TLV320AIC23_DATE);
+
+ return selftest;
+}
+
+static void __exit aic23_exit(void)
+{
+ int res;
+
+ aic23_power_down();
+ if ((res = i2c_del_driver(&aic23_driver)))
+ printk("aic23 i2c: Driver remove failed, module not removed.\n");
+
+ platform_device_unregister(&audio_i2c_device);
+ platform_driver_unregister(&audio_i2c_driver);
+}
+
+MODULE_AUTHOR("Kai Svahn <kai.svahn@nokia.com>");
+MODULE_DESCRIPTION("I2C interface for TLV320AIC23 codec.");
+MODULE_LICENSE("GPL");
+
+module_init(aic23_init)
+module_exit(aic23_exit)
+
+EXPORT_SYMBOL(aic23_write_value);
+EXPORT_SYMBOL(aic23_power_up);
+EXPORT_SYMBOL(aic23_power_down);
--- /dev/null
+/*
+ * twl4030_core.c - driver for TWL4030 PM and audio CODEC device
+ *
+ * Copyright (C) 2005-2006 Texas Instruments, Inc.
+ *
+ * Modifications to defer interrupt handling to a kernel thread:
+ * Copyright (C) 2006 MontaVista Software, Inc.
+ *
+ * Based on tlv320aic23.c:
+ * Copyright (c) by Kai Svahn <kai.svahn@nokia.com>
+ *
+ * Code cleanup and modifications to IRQ handler.
+ * by syed khasim <x0khasim@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/module.h>
+#include <linux/kernel_stat.h>
+#include <linux/init.h>
+#include <linux/time.h>
+#include <linux/interrupt.h>
+#include <linux/random.h>
+#include <linux/syscalls.h>
+#include <linux/kthread.h>
+
+#include <linux/i2c.h>
+#include <linux/slab.h>
+#include <linux/clk.h>
+#include <linux/device.h>
+
+#include <asm/irq.h>
+#include <asm/mach/irq.h>
+
+#include <asm/arch/twl4030.h>
+#include <asm/arch/gpio.h>
+#include <asm/arch/mux.h>
+
+/**** Macro Definitions */
+#define TWL_CLIENT_STRING "TWL4030-ID"
+#define TWL_CLIENT_USED 1
+#define TWL_CLIENT_FREE 0
+
+/* IRQ Flags */
+#define FREE 0
+#define USED 1
+
+/** Primary Interrupt Handler on TWL4030 Registers */
+
+/**** Register Definitions */
+
+#define REG_PIH_ISR_P1 (0x1)
+#define REG_PIH_ISR_P2 (0x2)
+#define REG_PIH_SIR (0x3)
+
+/* Triton Core internal information (BEGIN) */
+
+/* Last - for index max*/
+#define TWL4030_MODULE_LAST TWL4030_MODULE_SECURED_REG
+
+/* Slave address */
+#define TWL4030_NUM_SLAVES 0x04
+#define TWL4030_SLAVENUM_NUM0 0x00
+#define TWL4030_SLAVENUM_NUM1 0x01
+#define TWL4030_SLAVENUM_NUM2 0x02
+#define TWL4030_SLAVENUM_NUM3 0x03
+#define TWL4030_SLAVEID_ID0 0x48
+#define TWL4030_SLAVEID_ID1 0x49
+#define TWL4030_SLAVEID_ID2 0x4A
+#define TWL4030_SLAVEID_ID3 0x4B
+
+/* Base Address defns */
+/* USB ID */
+#define TWL4030_BASEADD_USB 0x0000
+/* AUD ID */
+#define TWL4030_BASEADD_AUDIO_VOICE 0x0000
+#define TWL4030_BASEADD_GPIO 0x0098
+
+#define TWL4030_BASEADD_INTBR 0x0085
+#define TWL4030_BASEADD_PIH 0x0080
+#define TWL4030_BASEADD_TEST 0x004C
+/* AUX ID */
+#define TWL4030_BASEADD_INTERRUPTS 0x00B9
+#define TWL4030_BASEADD_LED 0x00EE
+#define TWL4030_BASEADD_MADC 0x0000
+#define TWL4030_BASEADD_MAIN_CHARGE 0x0074
+#define TWL4030_BASEADD_PRECHARGE 0x00AA
+#define TWL4030_BASEADD_PWM0 0x00F8
+#define TWL4030_BASEADD_PWM1 0x00FB
+#define TWL4030_BASEADD_PWMA 0x00EF
+#define TWL4030_BASEADD_PWMB 0x00F1
+#define TWL4030_BASEADD_KEYPAD 0x00D2
+/* POWER ID */
+#define TWL4030_BASEADD_BACKUP 0x0014
+#define TWL4030_BASEADD_INT 0x002E
+#define TWL4030_BASEADD_PM_MASTER 0x0036
+#define TWL4030_BASEADD_PM_RECIEVER 0x005B
+#define TWL4030_BASEADD_RTC 0x001C
+#define TWL4030_BASEADD_SECURED_REG 0x0000
+
+/* Triton Core internal information (END) */
+
+/* Few power values */
+#define R_CFG_BOOT 0x05
+#define R_PROTECT_KEY 0x0E
+
+/* access control */
+#define KEY_UNLOCK1 0xce
+#define KEY_UNLOCK2 0xec
+#define KEY_LOCK 0x00
+
+#define HFCLK_FREQ_19p2_MHZ (1 << 0)
+#define HFCLK_FREQ_26_MHZ (2 << 0)
+#define HFCLK_FREQ_38p4_MHZ (3 << 0)
+#define HIGH_PERF_SQ (1 << 3)
+
+/* on I2C-1 for 2430SDP */
+#define CONFIG_I2C_TWL4030_ID 1
+
+/**** Helper functions */
+static int
+twl4030_detect_client(struct i2c_adapter *adapter, unsigned char sid);
+static int twl4030_attach_adapter(struct i2c_adapter *adapter);
+static int twl4030_detach_client(struct i2c_client *client);
+static void do_twl4030_irq(unsigned int irq, irq_desc_t *desc);
+
+static void twl_init_irq(void);
+
+/**** Data Structures */
+/* To have info on T2 IRQ substem activated or not */
+static unsigned char twl_irq_used = FREE;
+
+/* Structure to define on TWL4030 Slave ID */
+struct twl4030_client {
+ struct i2c_client client;
+ const char client_name[sizeof(TWL_CLIENT_STRING) + 1];
+ const unsigned char address;
+ const char adapter_index;
+ unsigned char inuse;
+
+ /* max numb of i2c_msg required is for read =2 */
+ struct i2c_msg xfer_msg[2];
+
+ /* To lock access to xfer_msg */
+ struct semaphore xfer_lock;
+};
+
+/* Module Mapping */
+struct twl4030mapping {
+ unsigned char sid; /* Slave ID */
+ unsigned char base; /* base address */
+};
+
+/* mapping the module id to slave id and base address */
+static struct twl4030mapping twl4030_map[TWL4030_MODULE_LAST + 1] = {
+ { TWL4030_SLAVENUM_NUM0, TWL4030_BASEADD_USB },
+ { TWL4030_SLAVENUM_NUM1, TWL4030_BASEADD_AUDIO_VOICE },
+ { TWL4030_SLAVENUM_NUM1, TWL4030_BASEADD_GPIO },
+ { TWL4030_SLAVENUM_NUM1, TWL4030_BASEADD_INTBR },
+ { TWL4030_SLAVENUM_NUM1, TWL4030_BASEADD_PIH },
+ { TWL4030_SLAVENUM_NUM1, TWL4030_BASEADD_TEST },
+ { TWL4030_SLAVENUM_NUM2, TWL4030_BASEADD_KEYPAD },
+ { TWL4030_SLAVENUM_NUM2, TWL4030_BASEADD_MADC },
+ { TWL4030_SLAVENUM_NUM2, TWL4030_BASEADD_INTERRUPTS },
+ { TWL4030_SLAVENUM_NUM2, TWL4030_BASEADD_LED },
+ { TWL4030_SLAVENUM_NUM2, TWL4030_BASEADD_MAIN_CHARGE },
+ { TWL4030_SLAVENUM_NUM2, TWL4030_BASEADD_PRECHARGE },
+ { TWL4030_SLAVENUM_NUM2, TWL4030_BASEADD_PWM0 },
+ { TWL4030_SLAVENUM_NUM2, TWL4030_BASEADD_PWM1 },
+ { TWL4030_SLAVENUM_NUM2, TWL4030_BASEADD_PWMA },
+ { TWL4030_SLAVENUM_NUM2, TWL4030_BASEADD_PWMB },
+ { TWL4030_SLAVENUM_NUM3, TWL4030_BASEADD_BACKUP },
+ { TWL4030_SLAVENUM_NUM3, TWL4030_BASEADD_INT },
+ { TWL4030_SLAVENUM_NUM3, TWL4030_BASEADD_PM_MASTER },
+ { TWL4030_SLAVENUM_NUM3, TWL4030_BASEADD_PM_RECIEVER },
+ { TWL4030_SLAVENUM_NUM3, TWL4030_BASEADD_RTC },
+ { TWL4030_SLAVENUM_NUM3, TWL4030_BASEADD_SECURED_REG },
+};
+
+static struct twl4030_client twl4030_modules[TWL4030_NUM_SLAVES] = {
+ {
+ .address = TWL4030_SLAVEID_ID0,
+ .client_name = TWL_CLIENT_STRING "0",
+ .adapter_index = CONFIG_I2C_TWL4030_ID,
+ },
+ {
+ .address = TWL4030_SLAVEID_ID1,
+ .client_name = TWL_CLIENT_STRING "1",
+ .adapter_index = CONFIG_I2C_TWL4030_ID,
+ },
+ {
+ .address = TWL4030_SLAVEID_ID2,
+ .client_name = TWL_CLIENT_STRING "2",
+ .adapter_index = CONFIG_I2C_TWL4030_ID,
+ },
+ {
+ .address = TWL4030_SLAVEID_ID3,
+ .client_name = TWL_CLIENT_STRING "3",
+ .adapter_index = CONFIG_I2C_TWL4030_ID,
+ },
+};
+
+/* One Client Driver , 4 Clients */
+static struct i2c_driver twl4030_driver = {
+ .driver.name = "TWL4030 I2C",
+ .attach_adapter = twl4030_attach_adapter,
+ .detach_client = twl4030_detach_client,
+};
+
+/*
+ * TWL4030 doesn't have PIH mask, hence dummy function for mask
+ * and unmask.
+ */
+
+static void twl4030_i2c_ackirq(unsigned int irq) {}
+static void twl4030_i2c_disableint(unsigned int irq) {}
+static void twl4030_i2c_enableint(unsigned int irq) {}
+
+/* information for processing in the Work Item */
+static struct irq_chip twl4030_irq_chip = {
+ .ack = twl4030_i2c_ackirq,
+ .mask = twl4030_i2c_disableint,
+ .unmask = twl4030_i2c_enableint,
+};
+
+/* Global Functions */
+/*
+ * @brief twl4030_i2c_write - Writes a n bit register in TWL4030
+ *
+ * @param mod_no - module number
+ * @param *value - an array of num_bytes+1 containing data to write
+ * IMPORTANT - Allocate value num_bytes+1 and valid data starts at
+ * Offset 1.
+ * @param reg - register address (just offset will do)
+ * @param num_bytes - number of bytes to transfer
+ *
+ * @return result of operation - 0 is success
+ */
+int twl4030_i2c_write(u8 mod_no, u8 * value, u8 reg, u8 num_bytes)
+{
+ int ret;
+ int sid;
+ struct twl4030_client *client;
+ struct i2c_msg *msg;
+
+ if (unlikely(mod_no > TWL4030_MODULE_LAST)) {
+ printk(KERN_ERR "TWL4030: Invalid module Number\n");
+ return -EPERM;
+ }
+ sid = twl4030_map[mod_no].sid;
+ client = &(twl4030_modules[sid]);
+
+ if (unlikely(client->inuse != TWL_CLIENT_USED)) {
+ printk(KERN_ERR
+ "TWL4030: I2C Client[%d] is not initialized[%d]\n",
+ sid, __LINE__);
+ return -EPERM;
+ }
+ down(&(client->xfer_lock));
+ /*
+ * [MSG1]: fill the register address data
+ * fill the data Tx buffer
+ */
+ msg = &(client->xfer_msg[0]);
+ msg->addr = client->address;
+ msg->len = num_bytes + 1;
+ msg->flags = 0;
+ msg->buf = value;
+ /* over write the first byte of buffer with the register address */
+ *value = twl4030_map[mod_no].base + reg;
+ ret = i2c_transfer(client->client.adapter, client->xfer_msg, 1);
+ up(&(client->xfer_lock));
+
+ /* i2cTransfer returns num messages.translate it pls.. */
+ if (ret >= 0)
+ ret = 0;
+ return ret;
+}
+
+/**
+ * @brief twl4030_i2c_read - Reads a n bit register in TWL4030
+ *
+ * @param mod_no - module number
+ * @param *value - an array of num_bytes containing data to be read
+ * @param reg - register address (just offset will do)
+ * @param num_bytes - number of bytes to transfer
+ *
+ * @return result of operation - num_bytes is success else failure.
+ */
+int twl4030_i2c_read(u8 mod_no, u8 * value, u8 reg, u8 num_bytes)
+{
+ int ret;
+ u8 val;
+ int sid;
+ struct twl4030_client *client;
+ struct i2c_msg *msg;
+ if (unlikely(mod_no > TWL4030_MODULE_LAST)) {
+ printk(KERN_ERR "TWL4030: Invalid module Number\n");
+ return -EPERM;
+ }
+ sid = twl4030_map[mod_no].sid;
+ client = &(twl4030_modules[sid]);
+
+ if (unlikely(client->inuse != TWL_CLIENT_USED)) {
+ printk(KERN_ERR
+ "TWL4030: I2C Client[%d] is not initialized[%d]\n",
+ sid, __LINE__);
+ return -EPERM;
+ }
+ down(&(client->xfer_lock));
+ /* [MSG1] fill the register address data */
+ msg = &(client->xfer_msg[0]);
+ msg->addr = client->address;
+ msg->len = 1;
+ val = twl4030_map[mod_no].base + reg;
+ msg->buf = &val;
+ /* [MSG2] fill the data rx buffer */
+ msg = &(client->xfer_msg[1]);
+ msg->addr = client->address;
+ msg->flags = I2C_M_RD; /* Read the register value */
+ msg->len = num_bytes; /* only n bytes */
+ msg->buf = value;
+ ret = i2c_transfer(client->client.adapter, client->xfer_msg, 2);
+ up(&(client->xfer_lock));
+
+ /* i2cTransfer returns num messages.translate it pls.. */
+ if (ret >= 0)
+ ret = 0;
+ return ret;
+}
+
+/**
+ * @brief twl4030_i2c_write_u8 - Writes a 8 bit register in TWL4030
+ *
+ * @param mod_no - module number
+ * @param value - the value to be written 8 bit
+ * @param reg - register address (just offset will do)
+ *
+ * @return result of operation - 0 is success
+ */
+int twl4030_i2c_write_u8(u8 mod_no, u8 value, u8 reg)
+{
+ int ret;
+ /* 2 bytes offset 1 contains the data offset 0 is used by i2c_write */
+ u8 temp_buffer[2] = { 0 };
+ /* offset 1 contains the data */
+ temp_buffer[1] = value;
+ ret = twl4030_i2c_write(mod_no, temp_buffer, reg, 1);
+ return ret;
+}
+
+/**
+ * @brief twl4030_i2c_read_u8 - Reads a 8 bit register from TWL4030
+ *
+ * @param mod_no - module number
+ * @param *value - the value read 8 bit
+ * @param reg - register address (just offset will do)
+ *
+ * @return result of operation - 0 is success
+ */
+int twl4030_i2c_read_u8(u8 mod_no, u8 * value, u8 reg)
+{
+ int ret = 0;
+ ret = twl4030_i2c_read(mod_no, value, reg, 1);
+ return ret;
+}
+
+/**** Helper Functions */
+
+/*
+ * do_twl4030_module_irq() is the desc->handle method for each of the twl4030
+ * module interrupts. It executes in kernel thread context.
+ * On entry, cpu interrupts are disabled.
+ */
+static void do_twl4030_module_irq(unsigned int irq, irq_desc_t *desc)
+{
+ struct irqaction *action;
+ const unsigned int cpu = smp_processor_id();
+
+ /*
+ * Earlier this was desc->triggered = 1;
+ */
+ desc->status = IRQ_INPROGRESS;
+
+ /*
+ * The desc->handle method would normally call the desc->chip->ack
+ * method here, but we won't bother since our ack method is NULL.
+ */
+
+ if (!desc->depth) {
+ kstat_cpu(cpu).irqs[irq]++;
+
+ action = desc->action;
+ if (action) {
+ int ret;
+ int status = 0;
+ int retval = 0;
+
+ local_irq_enable();
+
+ do {
+ /* Call the ISR with cpu interrupts enabled */
+ ret = action->handler(irq, action->dev_id);
+ if (ret == IRQ_HANDLED)
+ status |= action->flags;
+ retval |= ret;
+ action = action->next;
+ } while (action);
+
+ if (status & IRQF_SAMPLE_RANDOM)
+ add_interrupt_randomness(irq);
+
+ local_irq_disable();
+
+ if (retval != IRQ_HANDLED)
+ printk(KERN_ERR "ISR for TWL4030 module"
+ " irq %d can't handle interrupt\n", irq);
+
+ /*
+ * Here is where we should call the unmask method, but
+ * again we won't bother since it is NULL.
+ */
+ } else
+ printk(KERN_CRIT "TWL4030 module irq %d has no ISR"
+ " but can't be masked!\n", irq);
+ } else
+ printk(KERN_CRIT "TWL4030 module irq %d is disabled but can't"
+ " be masked!\n", irq);
+}
+
+/*
+ * twl4030_irq_thread() runs as a kernel thread. It queries the twl4030
+ * interrupt controller to see which modules are generating interrupt requests
+ * and then calls the desc->handle method for each module requesting service.
+ */
+static int twl4030_irq_thread(void *data)
+{
+ int irq = (int)data;
+ irq_desc_t *desc = irq_desc + irq;
+ static unsigned i2c_errors;
+ const static unsigned max_i2c_errors = 100;
+
+ while (!kthread_should_stop()) {
+ int ret;
+ int module_irq;
+ u8 pih_isr;
+
+ ret = twl4030_i2c_read_u8(TWL4030_MODULE_PIH, &pih_isr,
+ REG_PIH_ISR_P1);
+ if (ret) {
+ printk(KERN_WARNING "I2C error %d while reading TWL4030"
+ " PIH ISR register.\n", ret);
+ if (++i2c_errors >= max_i2c_errors) {
+ printk(KERN_ERR "Maximum I2C error count"
+ " exceeded. Terminating %s.\n",
+ __FUNCTION__);
+ break;
+ }
+ continue;
+ }
+
+ for (module_irq = IH_TWL4030_BASE; 0 != pih_isr;
+ pih_isr >>= 1, module_irq++) {
+ if (pih_isr & 0x1) {
+ irq_desc_t *d = irq_desc + module_irq;
+
+ local_irq_disable();
+
+ d->handle_irq(module_irq, d);
+
+ local_irq_enable();
+ }
+ }
+
+ local_irq_disable();
+
+ set_current_state(TASK_INTERRUPTIBLE);
+ desc->chip->unmask(irq);
+
+ local_irq_enable();
+
+ schedule();
+ }
+ set_current_state(TASK_RUNNING);
+ return 0;
+}
+
+/*
+ * do_twl4030_irq() is the desc->handle method for the twl4030 interrupt.
+ * This is a chained interrupt, so there is no desc->action method for it.
+ * Now we need to query the interrupt controller in the twl4030 to determine
+ * which module is generating the interrupt request. However, we can't do i2c
+ * transactions in interrupt context, so we must defer that work to a kernel
+ * thread. All we do here is acknowledge and mask the interrupt and wakeup
+ * the kernel thread.
+ */
+static void do_twl4030_irq(unsigned int irq, irq_desc_t *desc)
+{
+ const unsigned int cpu = smp_processor_id();
+ struct task_struct *thread = (struct task_struct *)desc->chip_data;
+
+ /*
+ * Earlier this was desc->triggered = 1;
+ */
+ desc->status = IRQ_INPROGRESS;
+
+ /*
+ * Acknowledge, clear _AND_ disable the interrupt.
+ */
+ desc->chip->ack(irq);
+
+ if (!desc->depth) {
+ kstat_cpu(cpu).irqs[irq]++;
+
+ if (thread && thread->state != TASK_RUNNING)
+ wake_up_process(thread);
+ }
+}
+
+/* attach a client to the adapter */
+static int twl4030_detect_client(struct i2c_adapter *adapter, unsigned char sid)
+{
+ int err = 0;
+ struct twl4030_client *client;
+ if (unlikely(sid >= TWL4030_NUM_SLAVES)) {
+ printk(KERN_ERR "TWL4030: sid[%d] >MOD_LAST[%d]\n", sid,
+ TWL4030_NUM_SLAVES);
+ return -EPERM;
+ }
+
+ /* Check basic functionality */
+ if (!(err = i2c_check_functionality(adapter, I2C_FUNC_SMBUS_WORD_DATA |
+ I2C_FUNC_SMBUS_WRITE_BYTE))) {
+ printk(KERN_WARNING
+ "TWL4030: SlaveID=%d functionality check failed\n", sid);
+ return err;
+ }
+ client = &(twl4030_modules[sid]);
+ if (unlikely(client->inuse)) {
+ printk(KERN_ERR "TWL4030: Client is already in Use.....\n");
+ printk("%s[ID=0x%x] NOT attached to I2c Adapter %s\n",
+ client->client_name, client->address, adapter->name);
+ return -EPERM;
+ }
+
+ memset(&(client->client), 0, sizeof(struct i2c_client));
+
+ client->client.addr = client->address;
+ client->client.adapter = adapter;
+ client->client.driver = &twl4030_driver;
+
+ memcpy(&(client->client.name), client->client_name,
+ sizeof(TWL_CLIENT_STRING) + 1);
+ printk("TWL4030: TRY attach Slave %s on Adapter %s[%d][%x]\n",
+ client->client_name, adapter->name, err, err);
+ if ((err = i2c_attach_client(&(client->client))))
+ printk(KERN_WARNING
+ "TWL4030: Couldn't attach Slave %s on Adapter "
+ "%s[%d][%x]\n",
+ client->client_name, adapter->name, err, err);
+ else {
+ client->inuse = TWL_CLIENT_USED;
+ init_MUTEX(&client->xfer_lock);
+ }
+ return err;
+}
+
+/* adapter callback */
+static int twl4030_attach_adapter(struct i2c_adapter *adapter)
+{
+ int i;
+ int ret = 0;
+ static int twl_i2c_adapter = 1;
+ for (i = 0; i < TWL4030_NUM_SLAVES; i++) {
+ /* Check if I need to hook on to this adapter or not */
+ if (twl4030_modules[i].adapter_index == twl_i2c_adapter) {
+ if ((ret = twl4030_detect_client(adapter, i)))
+ goto free_client;
+ }
+ }
+ twl_i2c_adapter++;
+
+ /*
+ * Check if the PIH module is initialized, if yes, then init
+ * the T2 Interrupt subsystem
+ */
+ if ((twl4030_modules[twl4030_map[TWL4030_MODULE_PIH].sid].inuse ==
+ TWL_CLIENT_USED) && (twl_irq_used != USED)) {
+ twl_init_irq();
+ twl_irq_used = USED;
+ }
+ return 0;
+
+free_client:
+ printk(KERN_ERR
+ "TWL4030: TWL_CLIENT(Idx=%d] REGISTRATION FAILED=%d[0x%x]\n", i,
+ ret, ret);
+
+ /* ignore current slave..it never got registered */
+ i--;
+ while (i >= 0) {
+ /* now remove all those from the current adapter... */
+ if (twl4030_modules[i].adapter_index == twl_i2c_adapter)
+ (void)twl4030_detach_client(&(twl4030_modules[i].client));
+ i--;
+ }
+ return ret;
+}
+
+/* adapter's callback */
+static int twl4030_detach_client(struct i2c_client *iclient)
+{
+ int err;
+ if ((err = i2c_detach_client(iclient))) {
+ printk(KERN_ERR
+ "TWL4030: Client deregistration failed, client not detached.\n");
+ return err;
+ }
+ return 0;
+}
+
+struct task_struct *start_twl4030_irq_thread(int irq)
+{
+ struct task_struct *thread;
+
+ thread = kthread_create(twl4030_irq_thread, (void *)irq,
+ "twl4030 irq %d", irq);
+ if (!thread)
+ printk(KERN_ERR "%s: could not create twl4030 irq %d thread!\n",
+ __FUNCTION__, irq);
+
+ return thread;
+}
+
+/*
+ * These three functions should be part of Voltage frame work
+ * added here to complete the functionality for now.
+ */
+static int protect_pm_master(void)
+{
+ int e = 0;
+ e = twl4030_i2c_write_u8(TWL4030_MODULE_PM_MASTER, KEY_LOCK,
+ R_PROTECT_KEY);
+ return e;
+}
+
+static int unprotect_pm_master(void)
+{
+ int e = 0;
+ e |= twl4030_i2c_write_u8(TWL4030_MODULE_PM_MASTER, KEY_UNLOCK1,
+ R_PROTECT_KEY);
+ e |= twl4030_i2c_write_u8(TWL4030_MODULE_PM_MASTER, KEY_UNLOCK2,
+ R_PROTECT_KEY);
+ return e;
+}
+
+int power_companion_init(void)
+{
+ struct clk *osc;
+ u32 rate, ctrl = HFCLK_FREQ_26_MHZ;
+ int e = 0;
+
+ osc = clk_get(NULL,"osc_ck");
+ rate = clk_get_rate(osc);
+ clk_put(osc);
+
+ switch(rate) {
+ case 19200000 : ctrl = HFCLK_FREQ_19p2_MHZ; break;
+ case 26000000 : ctrl = HFCLK_FREQ_26_MHZ; break;
+ case 38400000 : ctrl = HFCLK_FREQ_38p4_MHZ; break;
+ }
+
+ ctrl |= HIGH_PERF_SQ;
+ e |= unprotect_pm_master();
+ /* effect->MADC+USB ck en */
+ e |= twl4030_i2c_write_u8(TWL4030_MODULE_PM_MASTER, ctrl, R_CFG_BOOT);
+ e |= protect_pm_master();
+
+ return e;
+}
+
+static void twl_init_irq(void)
+{
+ int i = 0;
+ int res = 0;
+ int line = 0;
+ /*
+ * We end up with interrupts from other modules before
+ * they get a chance to handle them...
+ */
+ /* PWR_ISR1 */
+ res = twl4030_i2c_write_u8(TWL4030_MODULE_INT, 0xFF, 0x00);
+ if (res < 0) {
+ line = __LINE__;
+ goto irq_exit_path;
+ }
+
+ /* PWR_ISR2 */
+ res = twl4030_i2c_write_u8(TWL4030_MODULE_INT, 0xFF, 0x02);
+ if (res < 0) {
+ line = __LINE__;
+ goto irq_exit_path;
+ }
+
+ /* PWR_IMR1 */
+ res = twl4030_i2c_write_u8(TWL4030_MODULE_INT, 0xFF, 0x1);
+ if (res < 0) {
+ line = __LINE__;
+ goto irq_exit_path;
+ }
+
+ /* PWR_IMR2 */
+ res = twl4030_i2c_write_u8(TWL4030_MODULE_INT, 0xFF, 0x3);
+ if (res < 0) {
+ line = __LINE__;
+ goto irq_exit_path;
+ }
+
+ /* Clear off any other pending interrupts on power */
+ /* PWR_ISR1 */
+ res = twl4030_i2c_write_u8(TWL4030_MODULE_INT, 0xFF, 0x00);
+ if (res < 0) {
+ line = __LINE__;
+ goto irq_exit_path;
+ }
+
+ /* PWR_ISR2 */
+ res = twl4030_i2c_write_u8(TWL4030_MODULE_INT, 0xFF, 0x02);
+ if (res < 0) {
+ line = __LINE__;
+ goto irq_exit_path;
+ }
+ /* POWER HACK (END) */
+ /* Slave address 0x4A */
+
+ /* BCIIMR1_1 */
+ res = twl4030_i2c_write_u8(TWL4030_MODULE_INTERRUPTS, 0xFF, 0x3);
+ if (res < 0) {
+ line = __LINE__;
+ goto irq_exit_path;
+ }
+
+ /* BCIIMR1_2 */
+ res = twl4030_i2c_write_u8(TWL4030_MODULE_INTERRUPTS, 0xFF, 0x4);
+ if (res < 0) {
+ line = __LINE__;
+ goto irq_exit_path;
+ }
+
+ /* BCIIMR2_1 */
+ res = twl4030_i2c_write_u8(TWL4030_MODULE_INTERRUPTS, 0xFF, 0x7);
+ if (res < 0) {
+ line = __LINE__;
+ goto irq_exit_path;
+ }
+
+ /* BCIIMR2_2 */
+ res = twl4030_i2c_write_u8(TWL4030_MODULE_INTERRUPTS, 0xFF, 0x8);
+ if (res < 0) {
+ line = __LINE__;
+ goto irq_exit_path;
+ }
+
+ /* MAD C */
+ /* MADC_IMR1 */
+ res = twl4030_i2c_write_u8(TWL4030_MODULE_MADC, 0xFF, 0x62);
+ if (res < 0) {
+ line = __LINE__;
+ goto irq_exit_path;
+ }
+
+ /* MADC_IMR2 */
+ res = twl4030_i2c_write_u8(TWL4030_MODULE_MADC, 0xFF, 0x64);
+ if (res < 0) {
+ line = __LINE__;
+ goto irq_exit_path;
+ }
+
+ /* key Pad */
+ /* KEYPAD - IMR1 */
+ res = twl4030_i2c_write_u8(TWL4030_MODULE_KEYPAD, 0xFF, (0x12));
+ if (res < 0) {
+ line = __LINE__;
+ goto irq_exit_path;
+ }
+ {
+ u8 clear;
+ /* Clear ISR */
+ twl4030_i2c_read_u8(TWL4030_MODULE_KEYPAD, &clear, 0x11);
+ twl4030_i2c_read_u8(TWL4030_MODULE_KEYPAD, &clear, 0x11);
+ }
+
+ /* KEYPAD - IMR2 */
+ res = twl4030_i2c_write_u8(TWL4030_MODULE_KEYPAD, 0xFF, (0x14));
+ if (res < 0) {
+ line = __LINE__;
+ goto irq_exit_path;
+ }
+
+ /* Slave address 0x49 */
+ /* GPIO_IMR1A */
+ res = twl4030_i2c_write_u8(TWL4030_MODULE_GPIO, 0xFF, (0x1C));
+ if (res < 0) {
+ line = __LINE__;
+ goto irq_exit_path;
+ }
+
+ /* GPIO_IMR2A */
+ res = twl4030_i2c_write_u8(TWL4030_MODULE_GPIO, 0xFF, (0x1D));
+ if (res < 0) {
+ line = __LINE__;
+ goto irq_exit_path;
+ }
+
+ /* GPIO_IMR3A */
+ res = twl4030_i2c_write_u8(TWL4030_MODULE_GPIO, 0xFF, (0x1E));
+ if (res < 0) {
+ line = __LINE__;
+ goto irq_exit_path;
+ }
+
+ /* GPIO_IMR1B */
+ res = twl4030_i2c_write_u8(TWL4030_MODULE_GPIO, 0xFF, (0x22));
+ if (res < 0) {
+ line = __LINE__;
+ goto irq_exit_path;
+ }
+
+ /* GPIO_IMR2B */
+ res = twl4030_i2c_write_u8(TWL4030_MODULE_GPIO, 0xFF, (0x23));
+ if (res < 0) {
+ line = __LINE__;
+ goto irq_exit_path;
+ }
+
+ /* GPIO_IMR3B */
+ res = twl4030_i2c_write_u8(TWL4030_MODULE_GPIO, 0xFF, (0x24));
+ if (res < 0) {
+ line = __LINE__;
+ goto irq_exit_path;
+ }
+
+ /* install an irq handler for each of the PIH modules */
+ for (i = IH_TWL4030_BASE; i < IH_TWL4030_END; i++) {
+ set_irq_chip(i, &twl4030_irq_chip);
+ set_irq_handler(i, do_twl4030_module_irq);
+ set_irq_flags(i, IRQF_VALID);
+ }
+
+ /* install an irq handler to demultiplex the TWL4030 interrupt */
+ set_irq_data(TWL4030_IRQNUM, start_twl4030_irq_thread(TWL4030_IRQNUM));
+ set_irq_type(TWL4030_IRQNUM, IRQT_FALLING);
+ set_irq_chained_handler(TWL4030_IRQNUM, do_twl4030_irq);
+
+ res = power_companion_init();
+ if (res < 0) {
+ line = __LINE__;
+ goto irq_exit_path;
+ }
+
+irq_exit_path:
+ if (res)
+ printk(KERN_ERR
+ "TWL4030: Unable to register interrupt "
+ "subsystem[%d][%d]\n", res, line);
+}
+
+static int __init twl4030_init(void)
+{
+ int res;
+ if ((res = i2c_register_driver(THIS_MODULE, &twl4030_driver))) {
+ printk(KERN_ERR "TWL4030: Driver registration failed \n");
+ return res;
+ }
+ printk(KERN_INFO "TWL4030: Driver registration complete.\n");
+ return res;
+}
+
+static void __exit twl4030_exit(void)
+{
+ if (i2c_del_driver(&twl4030_driver))
+ printk(KERN_ERR
+ "TWL4030: Driver remove failed, module not removed\n");
+ twl_irq_used = FREE;
+}
+
+subsys_initcall(twl4030_init);
+module_exit(twl4030_exit);
+
+EXPORT_SYMBOL(twl4030_i2c_write_u8);
+EXPORT_SYMBOL(twl4030_i2c_read_u8);
+EXPORT_SYMBOL(twl4030_i2c_read);
+EXPORT_SYMBOL(twl4030_i2c_write);
+
+MODULE_AUTHOR("Texas Instruments, Inc.");
+MODULE_DESCRIPTION("I2C Core interface for TWL4030");
+MODULE_LICENSE("GPL");
--- /dev/null
+/*
+ * twl4030.h - header for TWL4030 PM and audio CODEC device
+ *
+ * Copyright (C) 2005-2006 Texas Instruments, Inc.
+ *
+ * Based on tlv320aic23.c:
+ * Copyright (c) by Kai Svahn <kai.svahn@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
+ * 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 __TWL4030_H_
+#define __TWL4030_H_
+
+/* USB ID */
+#define TWL4030_MODULE_USB 0x00
+/* AUD ID */
+#define TWL4030_MODULE_AUDIO_VOICE 0x01
+#define TWL4030_MODULE_GPIO 0x02
+#define TWL4030_MODULE_INTBR 0x03
+#define TWL4030_MODULE_PIH 0x04
+#define TWL4030_MODULE_TEST 0x05
+/* AUX ID */
+#define TWL4030_MODULE_KEYPAD 0x06
+#define TWL4030_MODULE_MADC 0x07
+#define TWL4030_MODULE_INTERRUPTS 0x08
+#define TWL4030_MODULE_LED 0x09
+#define TWL4030_MODULE_MAIN_CHARGE 0x0A
+#define TWL4030_MODULE_PRECHARGE 0x0B
+#define TWL4030_MODULE_PWM0 0x0C
+#define TWL4030_MODULE_PWM1 0x0D
+#define TWL4030_MODULE_PWMA 0x0E
+#define TWL4030_MODULE_PWMB 0x0F
+/* POWER ID */
+#define TWL4030_MODULE_BACKUP 0x10
+#define TWL4030_MODULE_INT 0x11
+#define TWL4030_MODULE_PM_MASTER 0x12
+#define TWL4030_MODULE_PM_RECIEVER 0x13
+#define TWL4030_MODULE_RTC 0x14
+#define TWL4030_MODULE_SECURED_REG 0x15
+
+/* IRQ information-need base */
+#include <asm/arch/irqs.h>
+/* TWL4030 interrupts */
+
+#define TWL4030_MODIRQ_GPIO (IH_TWL4030_BASE + 0)
+#define TWL4030_MODIRQ_KEYPAD (IH_TWL4030_BASE + 1)
+#define TWL4030_MODIRQ_BCI (IH_TWL4030_BASE + 2)
+#define TWL4030_MODIRQ_MADC (IH_TWL4030_BASE + 3)
+#define TWL4030_MODIRQ_USB (IH_TWL4030_BASE + 4)
+#define TWL4030_MODIRQ_PWR (IH_TWL4030_BASE + 5)
+/* Rest are unsued currently*/
+
+/* Offsets to Power Registers */
+#define TWL4030_VDAC_DEV_GRP 0x3B
+#define TWL4030_VDAC_DEDICATED 0x3E
+#define TWL4030_VAUX2_DEV_GRP 0x1B
+#define TWL4030_VAUX2_DEDICATED 0x1E
+#define TWL4030_VAUX3_DEV_GRP 0x1F
+#define TWL4030_VAUX3_DEDICATED 0x22
+
+/* Functions to read and write from TWL4030 */
+
+/*
+ * IMP NOTE:
+ * The base address of the module will be added by the triton driver
+ * It is the caller's responsibility to ensure sane values
+ */
+int twl4030_i2c_write_u8(u8 mod_no, u8 val, u8 reg);
+int twl4030_i2c_read_u8(u8 mod_no, u8* val, u8 reg);
+
+ /*
+ * i2c_write: IMPORTANT - Allocate value num_bytes+1 and valid data starts at
+ * Offset 1.
+ */
+int twl4030_i2c_write(u8 mod_no, u8 * value, u8 reg, u8 num_bytes);
+int twl4030_i2c_read(u8 mod_no, u8 * value, u8 reg, u8 num_bytes);
+
+#endif /* End of __TWL4030_H */
--- /dev/null
+/*
+ *
+ * TI TSC2101 Audio CODEC and TS control registers definition
+ *
+ *
+ * Copyright 2003 MontaVista Software Inc.
+ * Author: MontaVista Software, Inc.
+ * source@mvista.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 SOFTWARE IS PROVIDED ``AS IS'' AND ANY EXPRESS OR IMPLIED
+ * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
+ * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN
+ * NO EVENT SHALL THE AUTHOR BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT
+ * NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF
+ * USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
+ * ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+ * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF
+ * THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ *
+ * 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.,
+ * 675 Mass Ave, Cambridge, MA 02139, USA.
+ */
+
+#ifndef __ASM_HARDWARE_TSC2101_H
+#define __ASM_HARDWARE_TSC2101_H
+
+/* Page 0 Touch Screen Data Registers */
+#define TSC2101_TS_X (0x00)
+#define TSC2101_TS_Y (0x01)
+#define TSC2101_TS_Z1 (0x02)
+#define TSC2101_TS_Z2 (0x03)
+#define TSC2101_TS_BAT (0x05)
+#define TSC2101_TS_AUX1 (0x07)
+#define TSC2101_TS_AUX2 (0x08)
+#define TSC2101_TS_TEMP1 (0x09)
+#define TSC2101_TS_TEMP2 (0x0A)
+
+/* Page 1 Touch Screen Control registers */
+#define TSC2101_TS_ADC_CTRL (0x00)
+#define TSC2101_TS_STATUS (0x01)
+#define TSC2101_TS_BUFFER_CTRL (0x02)
+#define TSC2101_TS_REF_CTRL (0x03)
+#define TSC2101_TS_RESET_CTRL (0x04)
+#define TSC2101_TS_CONFIG_CTRL (0x05)
+#define TSC2101_TS_TEMP_MAX_THRESHOLD (0x06)
+#define TSC2101_TS_TEMP_MIN_THRESHOLD (0x07)
+#define TSC2101_TS_AUX1_MAX_THRESHOLD (0x08)
+#define TSC2101_TS_AUX1_MIN_THRESHOLD (0x09)
+#define TSC2101_TS_AUX2_MAX_THRESHOLD (0x0A)
+#define TSC2101_TS_AUX2_MIN_THRESHOLD (0x0B)
+#define TSC2101_TS_MEASURE_CONFIG (0x0C)
+#define TSC2101_TS_PROG_DELAY (0x0D)
+
+/* Page 2 Audio codec Control registers */
+#define TSC2101_AUDIO_CTRL_1 (0x00)
+#define TSC2101_HEADSET_GAIN_CTRL (0x01)
+#define TSC2101_DAC_GAIN_CTRL (0x02)
+#define TSC2101_MIXER_PGA_CTRL (0x03)
+#define TSC2101_AUDIO_CTRL_2 (0x04)
+#define TSC2101_CODEC_POWER_CTRL (0x05)
+#define TSC2101_AUDIO_CTRL_3 (0x06)
+#define TSC2101_LCH_BASS_BOOST_N0 (0x07)
+#define TSC2101_LCH_BASS_BOOST_N1 (0x08)
+#define TSC2101_LCH_BASS_BOOST_N2 (0x09)
+#define TSC2101_LCH_BASS_BOOST_N3 (0x0A)
+#define TSC2101_LCH_BASS_BOOST_N4 (0x0B)
+#define TSC2101_LCH_BASS_BOOST_N5 (0x0C)
+#define TSC2101_LCH_BASS_BOOST_D1 (0x0D)
+#define TSC2101_LCH_BASS_BOOST_D2 (0x0E)
+#define TSC2101_LCH_BASS_BOOST_D4 (0x0F)
+#define TSC2101_LCH_BASS_BOOST_D5 (0x10)
+#define TSC2101_RCH_BASS_BOOST_N0 (0x11)
+#define TSC2101_RCH_BASS_BOOST_N1 (0x12)
+#define TSC2101_RCH_BASS_BOOST_N2 (0x13)
+#define TSC2101_RCH_BASS_BOOST_N3 (0x14)
+#define TSC2101_RCH_BASS_BOOST_N4 (0x15)
+#define TSC2101_RCH_BASS_BOOST_N5 (0x16)
+#define TSC2101_RCH_BASS_BOOST_D1 (0x17)
+#define TSC2101_RCH_BASS_BOOST_D2 (0x18)
+#define TSC2101_RCH_BASS_BOOST_D4 (0x19)
+#define TSC2101_RCH_BASS_BOOST_D5 (0x1A)
+#define TSC2101_PLL_PROG_1 (0x1B)
+#define TSC2101_PLL_PROG_2 (0x1C)
+#define TSC2101_AUDIO_CTRL_4 (0x1D)
+#define TSC2101_HANDSET_GAIN_CTRL (0x1E)
+#define TSC2101_BUZZER_GAIN_CTRL (0x1F)
+#define TSC2101_AUDIO_CTRL_5 (0x20)
+#define TSC2101_AUDIO_CTRL_6 (0x21)
+#define TSC2101_AUDIO_CTRL_7 (0x22)
+#define TSC2101_GPIO_CTRL (0x23)
+#define TSC2101_AGC_CTRL (0x24)
+#define TSC2101_POWERDOWN_STS (0x25)
+#define TSC2101_MIC_AGC_CONTROL (0x26)
+#define TSC2101_CELL_AGC_CONTROL (0x27)
+
+/* Bit field definitions for TS Control */
+#define TSC2101_DATA_AVAILABLE 0x4000
+#define TSC2101_BUFFERMODE_DISABLE 0x0
+#define TSC2101_REF_POWERUP 0x16
+#define TSC2101_ENABLE_TOUCHDETECT 0x08
+#define TSC2101_PRG_DELAY 0x0900
+#define TSC2101_ADC_CONTROL 0x8874
+#define TSC2101_ADC_POWERDOWN 0x4000
+
+/* Bit position */
+#define TSC2101_BIT(ARG) ((0x01)<<(ARG))
+
+/* Field masks for Audio Control 1 */
+#define AC1_ADCHPF(ARG) (((ARG) & 0x03) << 14)
+#define AC1_WLEN(ARG) (((ARG) & 0x03) << 10)
+#define AC1_DATFM(ARG) (((ARG) & 0x03) << 8)
+#define AC1_DACFS(ARG) (((ARG) & 0x07) << 3)
+#define AC1_ADCFS(ARG) (((ARG) & 0x07))
+
+/* Field masks for TSC2101_HEADSET_GAIN_CTRL */
+#define HGC_ADMUT_HED TSC2101_BIT(15)
+#define HGC_ADPGA_HED(ARG) (((ARG) & 0x7F) << 8)
+#define HGC_AGCTG_HED(ARG) (((ARG) & 0x07) << 5)
+#define HGC_AGCTC_HED(ARG) (((ARG) & 0x0F) << 1)
+#define HGC_AGCEN_HED (0x01)
+
+/* Field masks for TSC2101_DAC_GAIN_CTRL */
+#define DGC_DALMU TSC2101_BIT(15)
+#define DGC_DALVL(ARG) (((ARG) & 0x7F) << 8)
+#define DGC_DARMU TSC2101_BIT(7)
+#define DGC_DARVL(ARG) (((ARG) & 0x7F))
+
+/* Field masks for TSC2101_MIXER_PGA_CTRL */
+#define MPC_ASTMU TSC2101_BIT(15)
+#define MPC_ASTG(ARG) (((ARG) & 0x7F) << 8)
+#define MPC_MICSEL(ARG) (((ARG) & 0x07) << 5)
+#define MPC_MICADC TSC2101_BIT(4)
+#define MPC_CPADC TSC2101_BIT(3)
+#define MPC_ASTGF (0x01)
+
+/* Field formats for TSC2101_AUDIO_CTRL_2 */
+#define AC2_KCLEN TSC2101_BIT(15)
+#define AC2_KCLAC(ARG) (((ARG) & 0x07) << 12)
+#define AC2_APGASS TSC2101_BIT(11)
+#define AC2_KCLFRQ(ARG) (((ARG) & 0x07) << 8)
+#define AC2_KCLLN(ARG) (((ARG) & 0x0F) << 4)
+#define AC2_DLGAF TSC2101_BIT(3)
+#define AC2_DRGAF TSC2101_BIT(2)
+#define AC2_DASTC TSC2101_BIT(1)
+#define AC2_ADGAF (0x01)
+
+/* Field masks for TSC2101_CODEC_POWER_CTRL */
+#define CPC_MBIAS_HND TSC2101_BIT(15)
+#define CPC_MBIAS_HED TSC2101_BIT(14)
+#define CPC_ASTPWD TSC2101_BIT(13)
+#define CPC_SP1PWDN TSC2101_BIT(12)
+#define CPC_SP2PWDN TSC2101_BIT(11)
+#define CPC_DAPWDN TSC2101_BIT(10)
+#define CPC_ADPWDN TSC2101_BIT(9)
+#define CPC_VGPWDN TSC2101_BIT(8)
+#define CPC_COPWDN TSC2101_BIT(7)
+#define CPC_LSPWDN TSC2101_BIT(6)
+#define CPC_ADPWDF TSC2101_BIT(5)
+#define CPC_LDAPWDF TSC2101_BIT(4)
+#define CPC_RDAPWDF TSC2101_BIT(3)
+#define CPC_ASTPWF TSC2101_BIT(2)
+#define CPC_BASSBC TSC2101_BIT(1)
+#define CPC_DEEMPF (0x01)
+
+/* Field masks for TSC2101_AUDIO_CTRL_3 */
+#define AC3_DMSVOL(ARG) (((ARG) & 0x03) << 14)
+#define AC3_REFFS TSC2101_BIT(13)
+#define AC3_DAXFM TSC2101_BIT(12)
+#define AC3_SLVMS TSC2101_BIT(11)
+#define AC3_ADCOVF TSC2101_BIT(8)
+#define AC3_DALOVF TSC2101_BIT(7)
+#define AC3_DAROVF TSC2101_BIT(6)
+#define AC3_CLPST TSC2101_BIT(3)
+#define AC3_REVID(ARG) (((ARG) & 0x07))
+
+/* Field masks for TSC2101_PLL_PROG_1 */
+#define PLL1_PLLSEL TSC2101_BIT(15)
+#define PLL1_QVAL(ARG) (((ARG) & 0x0F) << 11)
+#define PLL1_PVAL(ARG) (((ARG) & 0x07) << 8)
+#define PLL1_I_VAL(ARG) (((ARG) & 0x3F) << 2)
+
+/* Field masks of TSC2101_PLL_PROG_2 */
+#define PLL2_D_VAL(ARG) (((ARG) & 0x3FFF) << 2)
+
+/* Field masks for TSC2101_AUDIO_CTRL_4 */
+#define AC4_ADSTPD TSC2101_BIT(15)
+#define AC4_DASTPD TSC2101_BIT(14)
+#define AC4_ASSTPD TSC2101_BIT(13)
+#define AC4_CISTPD TSC2101_BIT(12)
+#define AC4_BISTPD TSC2101_BIT(11)
+#define AC4_AGCHYS(ARG) (((ARG) & 0x03) << 9)
+#define AC4_MB_HED(ARG) (((ARG) & 0x03) << 7)
+#define AC4_MB_HND TSC2101_BIT(6)
+#define AC4_SCPFL TSC2101_BIT(1)
+
+/* Field masks settings for TSC2101_HANDSET_GAIN_CTRL */
+#define HNGC_ADMUT_HND TSC2101_BIT(15)
+#define HNGC_ADPGA_HND(ARG) (((ARG) & 0x7F) << 8)
+#define HNGC_AGCTG_HND(ARG) (((ARG) & 0x07) << 5)
+#define HNGC_AGCTC_HND(ARG) (((ARG) & 0x0F) << 1)
+#define HNGC_AGCEN_HND (0x01)
+
+/* Field masks settings for TSC2101_BUZZER_GAIN_CTRL */
+#define BGC_MUT_CP TSC2101_BIT(15)
+#define BGC_CPGA(ARG) (((ARG) & 0x7F) << 8)
+#define BGC_CPGF TSC2101_BIT(7)
+#define BGC_MUT_BU TSC2101_BIT(6)
+#define BGC_BPGA(ARG) (((ARG) & 0x0F) << 2)
+#define BGC_BUGF TSC2101_BIT(1)
+
+/* Field masks settings for TSC2101_AUDIO_CTRL_5 */
+#define AC5_DIFFIN TSC2101_BIT(15)
+#define AC5_DAC2SPK1(ARG) (((ARG) & 0x03) << 13)
+#define AC5_AST2SPK1 TSC2101_BIT(12)
+#define AC5_BUZ2SPK1 TSC2101_BIT(11)
+#define AC5_KCL2SPK1 TSC2101_BIT(10)
+#define AC5_CPI2SPK1 TSC2101_BIT(9)
+#define AC5_DAC2SPK2(ARG) (((ARG) & 0x03) << 7)
+#define AC5_AST2SPK2 TSC2101_BIT(6)
+#define AC5_BUZ2SPK2 TSC2101_BIT(5)
+#define AC5_KCL2SPK2 TSC2101_BIT(4)
+#define AC5_CPI2SPK2 TSC2101_BIT(3)
+#define AC5_MUTSPK1 TSC2101_BIT(2)
+#define AC5_MUTSPK2 TSC2101_BIT(1)
+#define AC5_HDSCPTC (0x01)
+
+/* Field masks settings for TSC2101_AUDIO_CTRL_6 */
+#define AC6_SPL2LSK TSC2101_BIT(15)
+#define AC6_AST2LSK TSC2101_BIT(14)
+#define AC6_BUZ2LSK TSC2101_BIT(13)
+#define AC6_KCL2LSK TSC2101_BIT(12)
+#define AC6_CPI2LSK TSC2101_BIT(11)
+#define AC6_MIC2CPO TSC2101_BIT(10)
+#define AC6_SPL2CPO TSC2101_BIT(9)
+#define AC6_SPR2CPO TSC2101_BIT(8)
+#define AC6_MUTLSPK TSC2101_BIT(7)
+#define AC6_MUTSPK2 TSC2101_BIT(6)
+#define AC6_LDSCPTC TSC2101_BIT(5)
+#define AC6_VGNDSCPTC TSC2101_BIT(4)
+#define AC6_CAPINTF TSC2101_BIT(3)
+
+/* Field masks settings for TSC2101_AUDIO_CTRL_7 */
+#define AC7_DETECT TSC2101_BIT(15)
+#define AC7_HESTYPE(ARG) (((ARG) & 0x03) << 13)
+#define AC7_HDDETFL TSC2101_BIT(12)
+#define AC7_BDETFL TSC2101_BIT(11)
+#define AC7_HDDEBNPG(ARG) (((ARG) & 0x03) << 9)
+#define AC7_BDEBNPG(ARG) (((ARG) & 0x03) << 6)
+#define AC7_DGPIO2 TSC2101_BIT(4)
+#define AC7_DGPIO1 TSC2101_BIT(3)
+#define AC7_CLKGPIO2 TSC2101_BIT(2)
+#define AC7_ADWSF(ARG) (((ARG) & 0x03))
+
+/* Field masks settings for TSC2101_GPIO_CTRL */
+#define GC_GPO2EN TSC2101_BIT(15)
+#define GC_GPO2SG TSC2101_BIT(14)
+#define GC_GPI2EN TSC2101_BIT(13)
+#define GC_GPI2SGF TSC2101_BIT(12)
+#define GC_GPO1EN TSC2101_BIT(11)
+#define GC_GPO1SG TSC2101_BIT(10)
+#define GC_GPI1EN TSC2101_BIT(9)
+#define GC_GPI1SGF TSC2101_BIT(8)
+
+/* Field masks for TSC2101_AGC_CTRL */
+#define AC_AGCNF_CELL TSC2101_BIT(14)
+#define AC_AGCNL(ARG) (((ARG) & 0x07) << 11)
+#define AC_AGCHYS_CELL(ARG) (((ARG) & 0x03) << 9)
+#define AC_CLPST_CELL TSC2101_BIT(8)
+#define AC_AGCTG_CELL(ARG) (((ARG) & 0x07) << 5)
+#define AC_AGCTC_CELL(ARG) (((ARG) & 0x0F) << 1)
+#define AC_AGCEN_CELL (0x01)
+
+/* Field masks for TSC2101_POWERDOWN_STS */
+#define PS_SPK1FL TSC2101_BIT(15)
+#define PS_SPK2FL TSC2101_BIT(14)
+#define PS_HNDFL TSC2101_BIT(13)
+#define PS_VGNDFL TSC2101_BIT(12)
+#define PS_LSPKFL TSC2101_BIT(11)
+#define PS_CELLFL TSC2101_BIT(10)
+#define PS_PSEQ TSC2101_BIT(5)
+#define PS_PSTIME TSC2101_BIT(4)
+
+/* Field masks for Register Mic AGC Control */
+#define MAC_MMPGA(ARG) (((ARG) & 0x7F) << 9)
+#define MAC_MDEBNS(ARG) (((ARG) & 0x07) << 6)
+#define MAC_MDEBSN(ARG) (((ARG) & 0x07) << 3)
+
+/* Field masks for Register Cellphone AGC Control */
+#define CAC_CMPGA(ARG) (((ARG) & 0x7F) << 9)
+#define CAC_CDEBNS(ARG) (((ARG) & 0x07) << 6)
+#define CAC_CDEBSN(ARG) (((ARG) & 0x07) << 3)
+
+#endif /* __ASM_HARDWARE_TSC2101_H */
#define I2C_DRIVERID_WM8750 90 /* Wolfson WM8750 audio codec */
#define I2C_DRIVERID_WM8753 91 /* Wolfson WM8753 audio codec */
+#define I2C_DRIVERID_MISC 99 /* Whatever until sorted out */
+
#define I2C_DRIVERID_I2CDEV 900
#define I2C_DRIVERID_ARP 902 /* SMBus ARP Client */
#define I2C_DRIVERID_ALERT 903 /* SMBus Alert Responder Client */