svn commit: r231962 - in projects/armv6/sys/arm: conf ti/omap4 ti/twl

Oleksandr Tymoshenko gonzo at FreeBSD.org
Tue Feb 21 06:10:36 UTC 2012


Author: gonzo
Date: Tue Feb 21 06:10:35 2012
New Revision: 231962
URL: http://svn.freebsd.org/changeset/base/231962

Log:
  Add TWL companion devices support by Ben R. Gray slightly modified
  by me:
  
  - style(9) cleanup
  - make clear distinction between bus driver and actual companion device
  - FDT-ize and get rid of references to hints
  - Hardcode TWL6030  support. Actual run-time chip detection: TBD
  - Make sysctls R/O. Unless there's something really pressing -
      do not let userland tinker with voltages.
  
  Submitted by:	Ben R. Gray

Added:
  projects/armv6/sys/arm/ti/twl/
  projects/armv6/sys/arm/ti/twl/twl.c
  projects/armv6/sys/arm/ti/twl/twl.h
  projects/armv6/sys/arm/ti/twl/twl_vreg.c
  projects/armv6/sys/arm/ti/twl/twl_vreg.h
Modified:
  projects/armv6/sys/arm/conf/PANDABOARD
  projects/armv6/sys/arm/ti/omap4/files.omap4

Modified: projects/armv6/sys/arm/conf/PANDABOARD
==============================================================================
--- projects/armv6/sys/arm/conf/PANDABOARD	Tue Feb 21 04:12:28 2012	(r231961)
+++ projects/armv6/sys/arm/conf/PANDABOARD	Tue Feb 21 06:10:35 2012	(r231962)
@@ -130,6 +130,8 @@ device		smsc		# SMSC LAN95xx USB Etherne
 
 # OMAP-specific devices
 device		omap_dma
+device		twl
+device		twl_vreg
 
 # Flattened Device Tree
 options         FDT

Modified: projects/armv6/sys/arm/ti/omap4/files.omap4
==============================================================================
--- projects/armv6/sys/arm/ti/omap4/files.omap4	Tue Feb 21 04:12:28 2012	(r231961)
+++ projects/armv6/sys/arm/ti/omap4/files.omap4	Tue Feb 21 06:10:35 2012	(r231962)
@@ -28,4 +28,7 @@ arm/ti/omap_mmc.c				optional	mmc
 arm/ti/omap4/omap4_prcm_clks.c			standard
 arm/ti/omap4/omap4_scm_padconf.c		standard
 
+arm/ti/twl/twl.c				optional	twl
+arm/ti/twl/twl_vreg.c				optional	twl twl_vreg
+
 dev/uart/uart_dev_ns8250.c			optional	uart

Added: projects/armv6/sys/arm/ti/twl/twl.c
==============================================================================
--- /dev/null	00:00:00 1970	(empty, because file is newly added)
+++ projects/armv6/sys/arm/ti/twl/twl.c	Tue Feb 21 06:10:35 2012	(r231962)
@@ -0,0 +1,380 @@
+/*-
+ * Copyright (c) 2011
+ *	Ben Gray <ben.r.gray at gmail.com>.
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ * 1. Redistributions of source code must retain the above copyright
+ *    notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ *    notice, this list of conditions and the following disclaimer in the
+ *    documentation and/or other materials provided with the distribution.
+ *
+ * THIS SOFTWARE IS PROVIDED BY AUTHOR AND CONTRIBUTORS ``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 AUTHOR OR CONTRIBUTORS 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.
+ */
+
+#include <sys/cdefs.h>
+__FBSDID("$FreeBSD$");
+
+/*
+ * Texas Instruments TWL4030/TWL5030/TWL60x0/TPS659x0 Power Management and
+ * Audio CODEC devices.
+ *
+ * This driver acts as a bus for mor specific companion devices
+ *
+ */
+
+#include <sys/param.h>
+#include <sys/systm.h>
+#include <sys/kernel.h>
+#include <sys/lock.h>
+#include <sys/module.h>
+#include <sys/bus.h>
+#include <sys/resource.h>
+#include <sys/rman.h>
+#include <sys/sysctl.h>
+#include <sys/mutex.h>
+#include <sys/malloc.h>
+
+#include <machine/bus.h>
+#include <machine/cpu.h>
+#include <machine/cpufunc.h>
+#include <machine/frame.h>
+#include <machine/resource.h>
+#include <machine/intr.h>
+
+#include <dev/iicbus/iiconf.h>
+#include "iicbus_if.h"
+
+#include "arm/ti/twl/twl.h"
+
+/* TWL device IDs */
+#define TWL_DEVICE_UNKNOWN          0xffff
+#define TWL_DEVICE_4030             0x4030
+#define TWL_DEVICE_6025             0x6025
+#define TWL_DEVICE_6030             0x6030
+
+/* Each TWL device typically has more than one I2C address */
+#define TWL_MAX_SUBADDRS            4
+
+/* The maxium number of bytes that can be written in one call */
+#define TWL_MAX_IIC_DATA_SIZE       63
+
+/* The TWL devices typically use 4 I2C address for the different internal
+ * register sets, plus one SmartReflex I2C address.
+ */
+#define TWL_CHIP_ID0                0x48
+#define TWL_CHIP_ID1                0x49
+#define TWL_CHIP_ID2                0x4A
+#define TWL_CHIP_ID3                0x4B
+
+#define TWL_SMARTREFLEX_CHIP_ID     0x12
+
+#define TWL_INVALID_CHIP_ID         0xff
+
+/**
+ *	Structure that stores the driver context.
+ *
+ *	This structure is allocated during driver attach.
+ */
+struct twl_softc {
+	device_t		sc_dev;
+	struct mtx		sc_mtx;
+
+	uint8_t			sc_subaddr_map[TWL_MAX_SUBADDRS];
+
+	struct intr_config_hook	sc_scan_hook;
+
+	device_t		sc_vreg;
+};
+
+/**
+ *	Macros for driver mutex locking
+ */
+#define TWL_LOCK(_sc)             mtx_lock(&(_sc)->sc_mtx)
+#define	TWL_UNLOCK(_sc)           mtx_unlock(&(_sc)->sc_mtx)
+#define TWL_LOCK_INIT(_sc) \
+	mtx_init(&_sc->sc_mtx, device_get_nameunit(_sc->sc_dev), \
+	         "twl", MTX_DEF)
+#define TWL_LOCK_DESTROY(_sc)     mtx_destroy(&_sc->sc_mtx);
+#define TWL_ASSERT_LOCKED(_sc)    mtx_assert(&_sc->sc_mtx, MA_OWNED);
+#define TWL_ASSERT_UNLOCKED(_sc)  mtx_assert(&_sc->sc_mtx, MA_NOTOWNED);
+
+/**
+ *	twl_read - read one or more registers from the TWL device
+ *	@sc: device soft context
+ *	@nsub: the sub-module to read from
+ *	@reg: the register offset within the module to read
+ *	@buf: buffer to store the bytes in
+ *	@cnt: the number of bytes to read
+ *
+ *	Reads one or registers and stores the result in the suppled buffer.
+ *
+ *	LOCKING:
+ *	Expects the TWL lock to be held.
+ *
+ *	RETURNS:
+ *	Zero on success or a negative error code on failure.
+ */
+int
+twl_read(device_t dev, uint8_t nsub, uint8_t reg, uint8_t *buf, uint16_t cnt)
+{
+	struct twl_softc *sc;
+	struct iic_msg msg[2];
+	uint8_t addr;
+	int rc;
+
+	sc = device_get_softc(dev);
+
+	TWL_LOCK(sc);
+
+	addr = sc->sc_subaddr_map[nsub];
+	if (addr == TWL_INVALID_CHIP_ID) {
+		TWL_UNLOCK(sc);
+		return (EIO);
+	}
+
+	/* Set the address to read from */
+	msg[0].slave = addr;
+	msg[0].flags = IIC_M_WR | IIC_M_NOSTOP;
+	msg[0].len = 1;
+	msg[0].buf = &reg;
+	/* Read the data back */
+	msg[1].slave = addr;
+	msg[1].flags = IIC_M_RD;
+	msg[1].len = cnt;
+	msg[1].buf = buf;
+
+	rc = iicbus_transfer(sc->sc_dev, msg, 2);
+
+	TWL_UNLOCK(sc);
+
+	if (rc != 0) {
+		device_printf(sc->sc_dev, "iicbus read failed (adr:0x%02x, reg:0x%02x)\n",
+		              addr, reg);
+		return (EIO);
+	}
+
+	return (0);
+}
+
+/**
+ *	twl_write - writes one or more registers to the TWL device
+ *	@sc: device soft context
+ *	@nsub: the sub-module to read from
+ *	@reg: the register offset within the module to read
+ *	@buf: data to write
+ *	@cnt: the number of bytes to write
+ *
+ *	Writes one or more registers.
+ *
+ *	LOCKING:
+ *	Expects the TWL lock to be held.
+ *
+ *	RETURNS:
+ *	Zero on success or a negative error code on failure.
+ */
+int
+twl_write(device_t dev, uint8_t nsub, uint8_t reg, uint8_t *buf, uint16_t cnt)
+{
+	struct twl_softc *sc;
+	struct iic_msg msg;
+	uint8_t addr;
+	uint8_t tmp_buf[TWL_MAX_IIC_DATA_SIZE + 1];
+	int rc;
+
+	if (cnt > TWL_MAX_IIC_DATA_SIZE)
+		return (ENOMEM);
+
+	/* Set the register address as the first byte */
+	tmp_buf[0] = reg;
+	memcpy(&tmp_buf[1], buf, cnt);
+
+	sc = device_get_softc(dev);
+
+	TWL_LOCK(sc);
+
+	addr = sc->sc_subaddr_map[nsub];
+	if (addr == TWL_INVALID_CHIP_ID) {
+		TWL_UNLOCK(sc);
+		return (EIO);
+	}
+
+	/* Setup the transfer and execute it */
+	msg.slave = addr;
+	msg.flags = IIC_M_WR;
+	msg.len = cnt + 1;
+	msg.buf = tmp_buf;
+
+	rc = iicbus_transfer(sc->sc_dev, &msg, 1);
+
+	TWL_UNLOCK(sc);
+
+	if (rc != 0) {
+		device_printf(sc->sc_dev, "iicbus write failed (adr:0x%02x, reg:0x%02x)\n",
+		              addr, reg);
+		return (EIO);
+	}
+
+	return (0);
+}
+
+/**
+ *	twl_test_present - checks if a device with given address is present
+ *	@sc: device soft context
+ *	@addr: the address of the device to scan for
+ *
+ *  Sends just the address byte and checks for an ACK. If no ACK then device
+ *  is assumed to not be present, otherwise device is present.
+ *
+ *	LOCKING:
+ *	It's expected the TWL lock is held while this function is called.
+ *
+ *	RETURNS:
+ *	EIO if device is not present, otherwise 0 is returned.
+ */
+static int
+twl_test_present(struct twl_softc *sc, uint8_t addr)
+{
+	struct iic_msg msg;
+	uint8_t tmp;
+
+	TWL_ASSERT_LOCKED(sc);
+
+	/* Set the address to read from */
+	msg.slave = addr;
+	msg.flags = IIC_M_RD;
+	msg.len = 1;
+	msg.buf = &tmp;
+
+	if (iicbus_transfer(sc->sc_dev, &msg, 1) != 0)
+		return (EIO);
+
+	return (0);
+}
+
+/**
+ *	twl_scan - disables IRQ's on the given channel
+ *	@ch: the channel to disable IRQ's on
+ *
+ *	Disable interupt generation for the given channel.
+ *
+ *	RETURNS:
+ *	BUS_PROBE_NOWILDCARD
+ */
+static void
+twl_scan(void *dev)
+{
+	struct twl_softc *sc;
+	unsigned i;
+	uint8_t base = TWL_CHIP_ID0;
+
+	sc = device_get_softc((device_t)dev);
+
+	TWL_LOCK(sc);
+
+	memset(sc->sc_subaddr_map, TWL_INVALID_CHIP_ID, TWL_MAX_SUBADDRS);
+
+	/* Try each of the addresses (0x48, 0x49, 0x4a & 0x4b) to determine which
+	 * sub modules we have.
+	 */
+	for (i = 0; i < TWL_MAX_SUBADDRS; i++) {
+		if (twl_test_present(sc, (base + i)) == 0) {
+			sc->sc_subaddr_map[i] = (base + i);
+			device_printf(sc->sc_dev, "Found (sub)device at 0x%02x\n", (base + i));
+		}
+	}
+
+	TWL_UNLOCK(sc);
+
+	/* Finished with the interrupt hook */
+	config_intrhook_disestablish(&sc->sc_scan_hook);
+}
+
+static void
+twl_identify(driver_t *driver, device_t parent)
+{
+
+        BUS_ADD_CHILD(parent, 0, "twl", 0);
+}
+
+static int
+twl_probe(device_t dev)
+{
+	device_set_desc(dev, "TI TWL4030/TWL5030/TWL60x0/TPS659x0 Companion IC");
+
+	return (BUS_PROBE_NOWILDCARD);
+}
+
+static int
+twl_attach(device_t dev)
+{
+	struct twl_softc *sc;
+
+	sc = device_get_softc(dev);
+	sc->sc_dev = dev;
+
+	TWL_LOCK_INIT(sc);
+
+	/* We have to wait until interrupts are enabled. I2C read and write
+	 * only works if the interrupts are available.
+	 */
+	sc->sc_scan_hook.ich_func = twl_scan;
+	sc->sc_scan_hook.ich_arg = dev;
+
+	if (config_intrhook_establish(&sc->sc_scan_hook) != 0)
+		return (ENOMEM);
+
+	/* FIXME: should be in DTS file */
+	if ((sc->sc_vreg = device_add_child(dev, "twl_vreg", -1)) == NULL)
+		device_printf(dev, "could not allocate twl_vreg instance\n");
+
+	return (bus_generic_attach(dev));
+}
+
+static int
+twl_detach(device_t dev)
+{
+	struct twl_softc *sc;
+	int rv;
+
+	sc = device_get_softc(dev);
+
+	if (sc->sc_vreg && (rv = device_delete_child(dev, sc->sc_vreg)) != 0)
+		return (rv);
+
+	TWL_LOCK_DESTROY(sc);
+
+	return (0);
+}
+
+static device_method_t twl_methods[] = {
+	DEVMETHOD(device_identify,	twl_identify),
+	DEVMETHOD(device_probe,		twl_probe),
+	DEVMETHOD(device_attach,	twl_attach),
+	DEVMETHOD(device_detach,	twl_detach),
+
+	{0, 0},
+};
+
+static driver_t twl_driver = {
+	"twl",
+	twl_methods,
+	sizeof(struct twl_softc),
+};
+static devclass_t twl_devclass;
+
+DRIVER_MODULE(twl, iicbus, twl_driver, twl_devclass, 0, 0);
+MODULE_VERSION(twl, 1);

Added: projects/armv6/sys/arm/ti/twl/twl.h
==============================================================================
--- /dev/null	00:00:00 1970	(empty, because file is newly added)
+++ projects/armv6/sys/arm/ti/twl/twl.h	Tue Feb 21 06:10:35 2012	(r231962)
@@ -0,0 +1,33 @@
+/*-
+ * Copyright (c) 2011
+ *	Ben Gray <ben.r.gray at gmail.com>.
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ * 1. Redistributions of source code must retain the above copyright
+ *    notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ *    notice, this list of conditions and the following disclaimer in the
+ *    documentation and/or other materials provided with the distribution.
+ *
+ * THIS SOFTWARE IS PROVIDED BY AUTHOR AND CONTRIBUTORS ``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 AUTHOR OR CONTRIBUTORS 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.
+ */
+#ifndef _TWL_H_
+#define _TWL_H_
+
+int twl_read(device_t dev, uint8_t nsub, uint8_t reg, uint8_t *buf, uint16_t cnt);
+int twl_write(device_t dev, uint8_t nsub, uint8_t reg, uint8_t *buf, uint16_t cnt);
+
+#endif /* _TWL_H_ */

Added: projects/armv6/sys/arm/ti/twl/twl_vreg.c
==============================================================================
--- /dev/null	00:00:00 1970	(empty, because file is newly added)
+++ projects/armv6/sys/arm/ti/twl/twl_vreg.c	Tue Feb 21 06:10:35 2012	(r231962)
@@ -0,0 +1,1057 @@
+/*-
+ * Copyright (c) 2011
+ *	Ben Gray <ben.r.gray at gmail.com>.
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ * 1. Redistributions of source code must retain the above copyright
+ *    notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ *    notice, this list of conditions and the following disclaimer in the
+ *    documentation and/or other materials provided with the distribution.
+ *
+ * THIS SOFTWARE IS PROVIDED BY AUTHOR AND CONTRIBUTORS ``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 AUTHOR OR CONTRIBUTORS 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.
+ */
+
+#include <sys/cdefs.h>
+__FBSDID("$FreeBSD$");
+
+/*
+ * Texas Instruments TWL4030/TWL5030/TWL60x0/TPS659x0 Power Management and
+ * Audio CODEC devices.
+ *
+ * This code is based on the Linux TWL multifunctional device driver, which is
+ * copyright (C) 2005-2006 Texas Instruments, Inc.
+ *
+ * These chips are typically used as support ICs for the OMAP range of embedded
+ * ARM processes/SOC from Texas Instruments.  They are typically used to control
+ * on board voltages, however some variants have other features like audio
+ * codecs, USB OTG transceivers, RTC, PWM, etc.
+ *
+ * Currently this driver focuses on the voltage regulator side of things,
+ * however in future it might be wise to split up this driver so that there is
+ * one base driver used for communication and other child drivers that
+ * manipulate the various modules on the chip.
+ *
+ * Voltage Regulators
+ * ------------------
+ * - Voltage regulators can belong to different power groups, in this driver we
+ *   put the regulators under our control in the "Application power group".
+ *
+ */
+
+#include <sys/param.h>
+#include <sys/systm.h>
+#include <sys/kernel.h>
+#include <sys/lock.h>
+#include <sys/module.h>
+#include <sys/bus.h>
+#include <sys/resource.h>
+#include <sys/rman.h>
+#include <sys/sysctl.h>
+#include <sys/mutex.h>
+#include <sys/malloc.h>
+
+#include <machine/bus.h>
+#include <machine/cpu.h>
+#include <machine/cpufunc.h>
+#include <machine/frame.h>
+#include <machine/resource.h>
+#include <machine/intr.h>
+
+#include <dev/iicbus/iiconf.h>
+
+#include "twl.h"
+#include "twl_vreg.h"
+
+/* The register sets are divided up into groups with the following base address
+ * and I2C addresses.
+ */
+
+/*
+ * Power Groups bits for the 4030 and 6030 devices
+ */
+#define TWL4030_P3_GRP		0x80	/* Peripherals, power group */
+#define TWL4030_P2_GRP		0x40	/* Modem power group */
+#define TWL4030_P1_GRP		0x20	/* Application power group (FreeBSD control) */
+
+#define TWL6030_P3_GRP		0x04	/* Modem power group */
+#define TWL6030_P2_GRP		0x02	/* Connectivity power group */
+#define TWL6030_P1_GRP		0x01	/* Application power group (FreeBSD control) */
+
+/*
+ * Register offsets within a LDO regulator register set
+ */
+#define TWL_VREG_GRP		0x00	/* Regulator GRP register */
+#define TWL_VREG_STATE		0x02
+#define TWL_VREG_VSEL		0x03	/* Voltage select register */
+
+#define UNDF  0xFFFF
+
+static const uint16_t twl6030_voltages[] = {
+	0000, 1000, 1100, 1200, 1300, 1400, 1500, 1600,
+	1700, 1800, 1900, 2000, 2100, 2200, 2300, 2400,
+	2500, 2600, 2700, 2800, 2900, 3000, 3100, 3200,
+	3300, UNDF, UNDF, UNDF, UNDF, UNDF, UNDF, 2750
+};
+
+static const uint16_t twl4030_vaux1_voltages[] = {
+	1500, 1800, 2500, 2800, 3000, 3000, 3000, 3000
+};
+static const uint16_t twl4030_vaux2_voltages[] = {
+	1700, 1700, 1900, 1300, 1500, 1800, 2000, 2500,
+	2100, 2800, 2200, 2300, 2400, 2400, 2400, 2400
+};
+static const uint16_t twl4030_vaux3_voltages[] = {
+	1500, 1800, 2500, 2800, 3000, 3000, 3000, 3000
+};
+static const uint16_t twl4030_vaux4_voltages[] = {
+	700,  1000, 1200, 1300, 1500, 1800, 1850, 2500,
+	2600, 2800, 2850, 3000, 3150, 3150, 3150, 3150
+};
+static const uint16_t twl4030_vmmc1_voltages[] = {
+	1850, 2850, 3000, 3150
+};
+static const uint16_t twl4030_vmmc2_voltages[] = {
+	1000, 1000, 1200, 1300, 1500, 1800, 1850, 2500,
+	2600, 2800, 2850, 3000, 3150, 3150, 3150, 3150
+};
+static const uint16_t twl4030_vpll1_voltages[] = {
+	1000, 1200, 1300, 1800, 2800, 3000, 3000, 3000
+};
+static const uint16_t twl4030_vpll2_voltages[] = {
+	700,  1000, 1200, 1300, 1500, 1800, 1850, 2500,
+	2600, 2800, 2850, 3000, 3150, 3150, 3150, 3150
+};
+static const uint16_t twl4030_vsim_voltages[] = {
+	1000, 1200, 1300, 1800, 2800, 3000, 3000, 3000
+};
+static const uint16_t twl4030_vdac_voltages[] = {
+	1200, 1300, 1800, 1800
+};
+static const uint16_t twl4030_vdd1_voltages[] = {
+	800, 1450
+};
+static const uint16_t twl4030_vdd2_voltages[] = {
+	800, 1450, 1500
+};
+static const uint16_t twl4030_vio_voltages[] = {
+	1800, 1850
+};
+static const uint16_t twl4030_vintana2_voltages[] = {
+	2500, 2750
+};
+
+/**
+ *  Support voltage regulators for the different IC's
+ */
+struct twl_regulator {
+	const char	*name;
+	uint8_t		subdev;
+	uint8_t		regbase;
+
+	uint16_t	fixedvoltage;
+
+	const uint16_t	*voltages;
+	uint32_t	num_voltages;
+};
+
+#define TWL_REGULATOR_ADJUSTABLE(name, subdev, reg, voltages) \
+	{ name, subdev, reg, 0, voltages, (sizeof(voltages)/sizeof(voltages[0])) }
+#define TWL_REGULATOR_FIXED(name, subdev, reg, voltage) \
+	{ name, subdev, reg, voltage, NULL, 0 }
+
+static const struct twl_regulator twl4030_regulators[] = {
+	TWL_REGULATOR_ADJUSTABLE("vaux1",    0, 0x17, twl4030_vaux1_voltages),
+	TWL_REGULATOR_ADJUSTABLE("vaux2",    0, 0x1B, twl4030_vaux2_voltages),
+	TWL_REGULATOR_ADJUSTABLE("vaux3",    0, 0x1F, twl4030_vaux3_voltages),
+	TWL_REGULATOR_ADJUSTABLE("vaux4",    0, 0x23, twl4030_vaux4_voltages),
+	TWL_REGULATOR_ADJUSTABLE("vmmc1",    0, 0x27, twl4030_vmmc1_voltages),
+	TWL_REGULATOR_ADJUSTABLE("vmmc2",    0, 0x2B, twl4030_vmmc2_voltages),
+	TWL_REGULATOR_ADJUSTABLE("vpll1",    0, 0x2F, twl4030_vpll1_voltages),
+	TWL_REGULATOR_ADJUSTABLE("vpll2",    0, 0x33, twl4030_vpll2_voltages),
+	TWL_REGULATOR_ADJUSTABLE("vsim",     0, 0x37, twl4030_vsim_voltages),
+	TWL_REGULATOR_ADJUSTABLE("vdac",     0, 0x3B, twl4030_vdac_voltages),
+	TWL_REGULATOR_ADJUSTABLE("vintana2", 0, 0x43, twl4030_vintana2_voltages),
+	TWL_REGULATOR_FIXED("vintana1", 0, 0x3F, 1500),
+	TWL_REGULATOR_FIXED("vintdig",  0, 0x47, 1500),
+	TWL_REGULATOR_FIXED("vusb1v5",  0, 0x71, 1500),
+	TWL_REGULATOR_FIXED("vusb1v8",  0, 0x74, 1800),
+	TWL_REGULATOR_FIXED("vusb3v1",  0, 0x77, 3100),
+	{ NULL, 0, 0x00, 0, NULL, 0 }
+};
+
+static const struct twl_regulator twl6030_regulators[] = {
+	TWL_REGULATOR_ADJUSTABLE("vaux1", 0, 0x84, twl6030_voltages),
+	TWL_REGULATOR_ADJUSTABLE("vaux2", 0, 0x89, twl6030_voltages),
+	TWL_REGULATOR_ADJUSTABLE("vaux3", 0, 0x8C, twl6030_voltages),
+	TWL_REGULATOR_ADJUSTABLE("vmmc",  0, 0x98, twl6030_voltages),
+	TWL_REGULATOR_ADJUSTABLE("vpp",   0, 0x9C, twl6030_voltages),
+	TWL_REGULATOR_ADJUSTABLE("vusim", 0, 0xA4, twl6030_voltages),
+	TWL_REGULATOR_FIXED("vmem",  0, 0x64, 1800),
+	TWL_REGULATOR_FIXED("vusb",  0, 0xA0, 3300),
+	TWL_REGULATOR_FIXED("v1v8",  0, 0x46, 1800),
+	TWL_REGULATOR_FIXED("v2v1",  0, 0x4C, 2100),
+	TWL_REGULATOR_FIXED("v1v29", 0, 0x40, 1290),
+	TWL_REGULATOR_FIXED("vcxio", 0, 0x90, 1800),
+	TWL_REGULATOR_FIXED("vdac",  0, 0x94, 1800),
+	TWL_REGULATOR_FIXED("vana",  0, 0x80, 2100),
+	{ NULL, 0, 0x00, 0, NULL, 0 } 
+};
+
+#define TWL_VREG_MAX_NAMELEN  32
+
+/**
+ *  Linked list of voltage regulators support by the device.
+ */
+struct twl_regulator_entry {
+	LIST_ENTRY(twl_regulator_entry) entries;
+
+	char			name[TWL_VREG_MAX_NAMELEN];
+	struct sysctl_oid	*oid;
+
+	uint8_t			sub_dev;
+	uint8_t			reg_off;
+
+	uint16_t		fixed_voltage;
+
+	const uint16_t		*supp_voltages;
+	uint32_t		num_supp_voltages;
+};
+
+/**
+ *	Structure that stores the driver context.
+ *
+ *	This structure is allocated during driver attach.
+ */
+struct twl_vreg_softc {
+	device_t			sc_dev;
+	device_t			sc_pdev;
+
+	struct mtx			sc_mtx;
+
+	struct intr_config_hook sc_init_hook;
+
+	LIST_HEAD(twl_regulator_list, twl_regulator_entry) sc_vreg_list;
+};
+
+/**
+ *	Macros for driver mutex locking
+ */
+#define TWL_VREG_LOCK(_sc)		mtx_lock(&(_sc)->sc_mtx)
+#define	TWL_VREG_UNLOCK(_sc)		mtx_unlock(&(_sc)->sc_mtx)
+#define TWL_VREG_LOCK_INIT(_sc) \
+	mtx_init(&_sc->sc_mtx, device_get_nameunit(_sc->sc_dev), \
+	         "twl_vreg", MTX_DEF)
+#define TWL_VREG_LOCK_DESTROY(_sc)	mtx_destroy(&_sc->sc_mtx);
+#define TWL_VREG_ASSERT_LOCKED(_sc)	mtx_assert(&_sc->sc_mtx, MA_OWNED);
+#define TWL_VREG_ASSERT_UNLOCKED(_sc)	mtx_assert(&_sc->sc_mtx, MA_NOTOWNED);
+
+static int debug;
+
+/**
+ *	twl_is_4030 - returns true if the device is TWL4030
+ *	twl_is_6025 - returns true if the device is TWL6025
+ *	twl_is_6030 - returns true if the device is TWL6030
+ *	@sc: device soft context
+ *
+ *	Returns a non-zero value if the device matches.
+ *
+ *	LOCKING:
+ *	None.
+ *
+ *	RETURNS:
+ *	Returns a non-zero value if the device matches, otherwise zero.
+ */
+static int
+twl_is_4030(device_t dev)
+{
+
+	return (0);
+}
+
+static int
+twl_is_6025(device_t dev)
+{
+
+	return (0);
+}
+
+static int
+twl_is_6030(device_t dev)
+{
+
+	return (1);
+}
+
+/**
+ *	twl_vreg_read_1 - read one or more registers from the TWL device
+ *	@sc: device soft context
+ *	@nsub: the sub-module to read from
+ *	@reg: the register offset within the module to read
+ *	@buf: buffer to store the bytes in
+ *	@cnt: the number of bytes to read
+ *
+ *	Reads one or registers and stores the result in the suppled buffer.
+ *
+ *	LOCKING:
+ *	Expects the TWL lock to be held.
+ *
+ *	RETURNS:
+ *	Zero on success or a negative error code on failure.
+ */
+static inline int
+twl_vreg_read_1(struct twl_vreg_softc *sc, struct twl_regulator_entry *regulator,
+    uint8_t off, uint8_t *val)
+{
+	return (twl_read(sc->sc_pdev, regulator->sub_dev, 
+	    regulator->reg_off + off, val, 1));
+}
+
+/**
+ *	twl_write - writes one or more registers to the TWL device
+ *	@sc: device soft context
+ *	@nsub: the sub-module to read from
+ *	@reg: the register offset within the module to read
+ *	@buf: data to write
+ *	@cnt: the number of bytes to write
+ *
+ *	Writes one or more registers.
+ *
+ *	LOCKING:
+ *	Expects the TWL lock to be held.
+ *
+ *	RETURNS:
+ *	Zero on success or a negative error code on failure.
+ */
+static inline int
+twl_vreg_write_1(struct twl_vreg_softc *sc, struct twl_regulator_entry *regulator,
+    uint8_t off, uint8_t val)
+{
+	return (twl_write(sc->sc_pdev, regulator->sub_dev,
+	    regulator->reg_off + off, &val, 1));
+}
+
+/**
+ *	twl_millivolt_to_vsel - gets the vsel bit value to write into the register
+ *	                        for a desired voltage
+ *	@sc: the device soft context
+ *	@regulator: pointer to the regulator device
+ *	@millivolts: the millivolts to find the bit value for
+ *	@bitval: upond return will contain the value to write
+ *	@diff: upon return will contain the difference between the requested
+ *	       voltage value and the actual voltage (in millivolts)
+ *
+ *  Accepts a voltage value and tries to find the closest match to the actual
+ *	supported voltages.  If a match is found within 100mv of the target, the
+ *	function returns the VSEL value.  If no voltage match is found the function
+ *	returns UNDEF.
+ *
+ *	LOCKING:
+ *	It's expected the TWL lock is held while this function is called.
+ *
+ *	RETURNS:
+ *	A value to load into the VSEL register if matching voltage found, if not
+ *	EINVAL is returned.
+ */
+static int
+twl_vreg_millivolt_to_vsel(struct twl_vreg_softc *sc,
+    struct twl_regulator_entry *regulator, int millivolts)
+{
+	int delta, smallest_delta;
+	unsigned i, closest_idx;
+
+	TWL_VREG_ASSERT_LOCKED(sc);
+
+	/* First check that variable voltage is supported */
+	if (regulator->supp_voltages == NULL)
+		return (EINVAL);
+
+	/* Loop over the support voltages and try and find the closest match */
+	closest_idx = 0;
+	smallest_delta = 0x7fffffff;
+	for (i = 0; i < regulator->num_supp_voltages; i++) {
+
+		/* Ignore undefined values */
+		if (regulator->supp_voltages[i] == UNDF)
+			continue;
+
+		/* Calculate the difference */
+		delta = millivolts - (int)regulator->supp_voltages[i];
+		if (abs(delta) < smallest_delta) {
+			smallest_delta = abs(delta);
+			closest_idx = i;
+		}
+	}
+
+	/* Check we got a voltage that was within 150mv of the actual target, this
+	 * is just a value I picked out of thin air.
+	 */
+	if (smallest_delta > 100)
+		return (EINVAL);
+
+	return (closest_idx);
+}
+
+/**
+ *	twl_regulator_is_enabled - returns the enabled status of the regulator
+ *	@sc: the device soft context
+ *	@regulator: pointer to the regulator device
+ *
+ *
+ *
+ *	LOCKING:
+ *	It's expected the TWL lock is held while this function is called.
+ *
+ *	RETURNS:
+ *	Zero if disabled, positive non-zero value if enabled, on failure a negative
+ *	error code.
+ */
+static int
+twl_vreg_is_regulator_enabled(struct twl_vreg_softc *sc,
+    struct twl_regulator_entry *regulator)
+{
+	int err;
+	uint8_t grp;
+	uint8_t state;
+
+	TWL_VREG_ASSERT_LOCKED(sc);
+
+	/* The status reading is different for the different devices */
+	if (twl_is_4030(sc->sc_dev)) {
+
+		err = twl_vreg_read_1(sc, regulator, TWL_VREG_GRP, &state);
+		if (err)
+			return (err);
+
+		return (state & TWL4030_P1_GRP);
+
+	} else if (twl_is_6030(sc->sc_dev) || twl_is_6025(sc->sc_dev)) {
+
+		/* Check the regulator is in the application group */
+		if (twl_is_6030(sc->sc_dev)) {
+			err = twl_vreg_read_1(sc, regulator, TWL_VREG_GRP, &grp);
+			if (err)
+				return (err);
+
+			if (!(grp & TWL6030_P1_GRP))
+				return (0);
+		}
+
+		/* Read the application mode state and verify it's ON */
+		err = twl_vreg_read_1(sc, regulator, TWL_VREG_STATE, &state);
+		if (err)
+			return (err);
+
+		return ((state & 0x0C) == 0x04);
+	}
+
+	return (EINVAL);
+}
+
+/**
+ *	twl_disable_regulator - disables the voltage regulator
+ *	@sc: the device soft context
+ *	@regulator: pointer to the regulator device
+ *
+ *  Disables the regulator which will stop the out drivers.
+ *
+ *	LOCKING:
+ *	It's expected the TWL lock is held while this function is called.
+ *
+ *	RETURNS:
+ *	Zero on success, or otherwise a negative error code.
+ */
+static int
+twl_vreg_disable_regulator(struct twl_vreg_softc *sc,
+    struct twl_regulator_entry *regulator)
+{
+	int err = 0;
+	uint8_t grp;
+
+	TWL_VREG_ASSERT_LOCKED(sc);
+
+	if (twl_is_4030(sc->sc_dev)) {
+
+		/* Read the regulator CFG_GRP register */
+		err = twl_vreg_read_1(sc, regulator, TWL_VREG_GRP, &grp);
+		if (err)
+			return (err);
+
+		/* On the TWL4030 we just need to remove the regulator from all the
+		 * power groups.
+		 */
+		grp &= ~(TWL4030_P1_GRP | TWL4030_P2_GRP | TWL4030_P3_GRP);
+		err = twl_vreg_write_1(sc, regulator, TWL_VREG_GRP, grp);
+
+	} else if (twl_is_6030(sc->sc_dev) || twl_is_6025(sc->sc_dev)) {
+
+		/* On TWL6030 we need to make sure we disable power for all groups */
+		if (twl_is_6030(sc->sc_dev))
+			grp = TWL6030_P1_GRP | TWL6030_P2_GRP | TWL6030_P3_GRP;
+		else
+			grp = 0x00;
+
+		/* Write the resource state to "OFF" */
+		err = twl_vreg_write_1(sc, regulator, TWL_VREG_STATE, (grp << 5));
+	}
+
+	return (err);
+}
+
+/**
+ *	twl_enable_regulator - enables the voltage regulator
+ *	@sc: the device soft context
+ *	@regulator: pointer to the regulator device
+ *
+ *  Enables the regulator which will enable the voltage out.
+ *
+ *	LOCKING:
+ *	It's expected the TWL lock is held while this function is called.
+ *
+ *	RETURNS:
+ *	Zero on success, or otherwise a negative error code.
+ */
+static int
+twl_vreg_enable_regulator(struct twl_vreg_softc *sc,
+    struct twl_regulator_entry *regulator)
+{
+	int err;
+	uint8_t grp;
+
+	TWL_VREG_ASSERT_LOCKED(sc);
+
+	/* Read the regulator CFG_GRP register */
+	err = twl_vreg_read_1(sc, regulator, TWL_VREG_GRP, &grp);
+	if (err)
+		return (err);
+
+	/* Enable the regulator by ensuring it's in the application power group
+	 * and is in the "on" state.
+	 */
+	if (twl_is_4030(sc->sc_dev)) {
+
+		/* On the TWL4030 we just need to ensure the regulator is in the right
+		 * power domain, don't need to turn on explicitly like TWL6030.
+		 */
+		grp |= TWL4030_P1_GRP;
+		err = twl_vreg_write_1(sc, regulator, TWL_VREG_GRP, grp);
+
+	} else if (twl_is_6030(sc->sc_dev) || twl_is_6025(sc->sc_dev)) {
+
+		if (twl_is_6030(sc->sc_dev) && !(grp & TWL6030_P1_GRP)) {
+			grp |= TWL6030_P1_GRP;
+			err = twl_vreg_write_1(sc, regulator, TWL_VREG_GRP, grp);
+			if (err)

*** DIFF OUTPUT TRUNCATED AT 1000 LINES ***


More information about the svn-src-projects mailing list