svn commit: r263936 - in head/sys: arm/conf arm/samsung/exynos boot/fdt/dts/arm

Ruslan Bukin br at FreeBSD.org
Sun Mar 30 15:22:38 UTC 2014


Author: br
Date: Sun Mar 30 15:22:36 2014
New Revision: 263936
URL: http://svnweb.freebsd.org/changeset/base/263936

Log:
  Add support for keyboard used in Samsung Chromebook (ARM machine)
  
  Support covers device drivers for:
  - Interrupt Combiner
  - gpio/pad, External Interrupts Controller (pad)
  - I2C Interface
  - Chrome Embedded Controller
  - Chrome Keyboard
  
  Also:
  - Use new gpio dev class in EHCI driver
  - Expand device tree information

Added:
  head/sys/arm/conf/CHROMEBOOK.hints   (contents, props changed)
  head/sys/arm/samsung/exynos/chrome_ec.c   (contents, props changed)
  head/sys/arm/samsung/exynos/chrome_ec.h   (contents, props changed)
  head/sys/arm/samsung/exynos/chrome_kb.c   (contents, props changed)
  head/sys/arm/samsung/exynos/chrome_kb.h   (contents, props changed)
  head/sys/arm/samsung/exynos/exynos5_combiner.c   (contents, props changed)
  head/sys/arm/samsung/exynos/exynos5_combiner.h   (contents, props changed)
  head/sys/arm/samsung/exynos/exynos5_i2c.c   (contents, props changed)
  head/sys/arm/samsung/exynos/exynos5_pad.c   (contents, props changed)
  head/sys/arm/samsung/exynos/exynos5_pad.h   (contents, props changed)
Modified:
  head/sys/arm/conf/CHROMEBOOK
  head/sys/arm/samsung/exynos/exynos5_ehci.c
  head/sys/arm/samsung/exynos/files.exynos5
  head/sys/boot/fdt/dts/arm/exynos5250-arndale.dts
  head/sys/boot/fdt/dts/arm/exynos5250-chromebook.dts
  head/sys/boot/fdt/dts/arm/exynos5250.dtsi

Modified: head/sys/arm/conf/CHROMEBOOK
==============================================================================
--- head/sys/arm/conf/CHROMEBOOK	Sun Mar 30 14:57:00 2014	(r263935)
+++ head/sys/arm/conf/CHROMEBOOK	Sun Mar 30 15:22:36 2014	(r263936)
@@ -20,6 +20,11 @@
 include		"EXYNOS5250.common"
 ident		CHROMEBOOK
 
+hints		"CHROMEBOOK.hints"
+
+device		chrome_ec	# Chrome Embedded Controller
+device		chrome_kb	# Chrome Keyboard
+
 # Framebuffer
 device		vt
 device		kbdmux

Added: head/sys/arm/conf/CHROMEBOOK.hints
==============================================================================
--- /dev/null	00:00:00 1970	(empty, because file is newly added)
+++ head/sys/arm/conf/CHROMEBOOK.hints	Sun Mar 30 15:22:36 2014	(r263936)
@@ -0,0 +1,5 @@
+# $FreeBSD$
+
+# Chrome Embedded Controller
+hint.chrome_ec.0.at="iicbus0"
+hint.chrome_ec.0.addr=0x1e

Added: head/sys/arm/samsung/exynos/chrome_ec.c
==============================================================================
--- /dev/null	00:00:00 1970	(empty, because file is newly added)
+++ head/sys/arm/samsung/exynos/chrome_ec.c	Sun Mar 30 15:22:36 2014	(r263936)
@@ -0,0 +1,253 @@
+/*-
+ * Copyright (c) 2014 Ruslan Bukin <br at bsdpad.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 THE AUTHOR AND CONTRIBUTORS ``AS IS'' AND
+ * ANY EXPREC OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNEC FOR A PARTICULAR PURPOSE
+ * ARE DISCLAIMED.  IN NO EVENT SHALL THE 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 BUSINEC 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.
+ */
+
+/*
+ * Samsung Chromebook Embedded Controller
+ */
+
+#include <sys/cdefs.h>
+__FBSDID("$FreeBSD$");
+
+#include <sys/param.h>
+#include <sys/systm.h>
+#include <sys/bus.h>
+#include <sys/kernel.h>
+#include <sys/module.h>
+#include <sys/malloc.h>
+#include <sys/rman.h>
+#include <sys/timeet.h>
+#include <sys/timetc.h>
+#include <sys/watchdog.h>
+#include <sys/gpio.h>
+
+#include <dev/fdt/fdt_common.h>
+#include <dev/ofw/openfirm.h>
+#include <dev/ofw/ofw_bus.h>
+#include <dev/ofw/ofw_bus_subr.h>
+
+#include <machine/bus.h>
+#include <machine/fdt.h>
+#include <machine/cpu.h>
+#include <machine/intr.h>
+
+#include <dev/iicbus/iiconf.h>
+
+#include "iicbus_if.h"
+#include "gpio_if.h"
+
+#include <arm/samsung/exynos/chrome_ec.h>
+
+/* TODO: export to DTS */
+#define OUR_GPIO	177
+#define EC_GPIO		168
+
+struct ec_softc {
+	device_t	dev;
+};
+
+struct ec_softc *ec_sc;
+
+/*
+ * bus_claim, bus_release
+ * both functions used for bus arbitration
+ * in multi-master mode
+ */
+
+static int
+bus_claim(struct ec_softc *sc)
+{
+	device_t gpio_dev;
+	int status;
+
+	gpio_dev = devclass_get_device(devclass_find("gpio"), 0);
+        if (gpio_dev == NULL) {
+		device_printf(sc->dev, "cant find gpio_dev\n");
+		return (1);
+	}
+
+	/* Say we want the bus */
+	GPIO_PIN_SET(gpio_dev, OUR_GPIO, GPIO_PIN_LOW);
+
+	/* Check EC decision */
+	GPIO_PIN_GET(gpio_dev, EC_GPIO, &status);
+
+	if (status == 1) {
+		/* Okay. We have bus */
+		return (0);
+	}
+
+	/* EC is master */
+	return (-1);
+}
+
+static int
+bus_release(struct ec_softc *sc)
+{
+	device_t gpio_dev;
+
+	gpio_dev = devclass_get_device(devclass_find("gpio"), 0);
+        if (gpio_dev == NULL) {
+		device_printf(sc->dev, "cant find gpio_dev\n");
+		return (1);
+	}
+
+	GPIO_PIN_SET(gpio_dev, OUR_GPIO, GPIO_PIN_HIGH);
+
+	return (0);
+}
+
+static int
+ec_probe(device_t dev)
+{
+
+	device_set_desc(dev, "Chromebook Embedded Controller");
+	return (BUS_PROBE_DEFAULT);
+}
+
+static int
+fill_checksum(uint8_t *data_out, int len)
+{
+	int res;
+	int i;
+
+	res = 0;
+	for (i = 0; i < len; i++) {
+		res += data_out[i];
+	}
+
+	data_out[len] = (res & 0xff);
+
+	return (0);
+}
+
+int
+ec_command(uint8_t cmd, uint8_t *dout, uint8_t dout_len,
+    uint8_t *dinp, uint8_t dinp_len)
+{
+	struct ec_softc *sc;
+	uint8_t *msg_dout;
+	uint8_t *msg_dinp;
+	int ret;
+	int i;
+
+	msg_dout = malloc(dout_len + 4, M_DEVBUF, M_NOWAIT);
+	msg_dinp = malloc(dinp_len + 4, M_DEVBUF, M_NOWAIT);
+
+	if (ec_sc == NULL)
+		return (-1);
+
+	sc = ec_sc;
+
+	msg_dout[0] = EC_CMD_VERSION0;
+	msg_dout[1] = cmd;
+	msg_dout[2] = dout_len;
+
+	for (i = 0; i < dout_len; i++) {
+		msg_dout[i + 3] = dout[i];
+	};
+
+	fill_checksum(msg_dout, dout_len + 3);
+
+	struct iic_msg msgs[] = {
+		{ 0x1e, IIC_M_WR, dout_len + 4, msg_dout, },
+		{ 0x1e, IIC_M_RD, dinp_len + 4, msg_dinp, },
+	};
+
+	ret = iicbus_transfer(sc->dev, msgs, 2);
+	if (ret != 0) {
+		device_printf(sc->dev, "i2c transfer returned %d\n", ret);
+		free(msg_dout, M_DEVBUF);
+		free(msg_dinp, M_DEVBUF);
+		return (-1);
+	}
+
+	for (i = 0; i < dinp_len; i++) {
+		dinp[i] = msg_dinp[i + 3];
+	};
+
+	free(msg_dout, M_DEVBUF);
+	free(msg_dinp, M_DEVBUF);
+	return (0);
+}
+
+int ec_hello(void)
+{
+	uint8_t data_in[4];
+	uint8_t data_out[4];
+
+	data_in[0] = 0x40;
+	data_in[1] = 0x30;
+	data_in[2] = 0x20;
+	data_in[3] = 0x10;
+
+	ec_command(EC_CMD_MKBP_STATE, data_in, 4,
+	    data_out, 4);
+
+	return (0);
+}
+
+static int
+ec_attach(device_t dev)
+{
+	struct ec_softc *sc;
+
+	sc = device_get_softc(dev);
+	sc->dev = dev;
+
+	ec_sc = sc;
+
+	/*
+	 * Claim the bus.
+	 *
+	 * We don't know cases when EC is master,
+	 * so hold the bus forever for us.
+	 *
+	 */
+
+	if (bus_claim(sc) != 0) {
+		return (ENXIO);
+	}
+
+	return (0);
+}
+
+static device_method_t ec_methods[] = {
+	DEVMETHOD(device_probe,		ec_probe),
+	DEVMETHOD(device_attach,	ec_attach),
+	{ 0, 0 }
+};
+
+static driver_t ec_driver = {
+	"chrome_ec",
+	ec_methods,
+	sizeof(struct ec_softc),
+};
+
+static devclass_t ec_devclass;
+
+DRIVER_MODULE(chrome_ec, iicbus, ec_driver, ec_devclass, 0, 0);
+MODULE_VERSION(chrome_ec, 1);
+MODULE_DEPEND(chrome_ec, iicbus, 1, 1, 1);

Added: head/sys/arm/samsung/exynos/chrome_ec.h
==============================================================================
--- /dev/null	00:00:00 1970	(empty, because file is newly added)
+++ head/sys/arm/samsung/exynos/chrome_ec.h	Sun Mar 30 15:22:36 2014	(r263936)
@@ -0,0 +1,36 @@
+/*-
+ * Copyright (c) 2014 Ruslan Bukin <br at bsdpad.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 THE 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 THE 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.
+ *
+ * $FreeBSD$
+ */
+
+#define	EC_CMD_HELLO		0x01
+#define	EC_CMD_GET_VERSION	0x02
+#define	EC_CMD_MKBP_STATE	0x60
+#define	EC_CMD_VERSION0		0xdc
+
+int ec_command(uint8_t cmd, uint8_t *dout, uint8_t dout_len,
+    uint8_t *dinp, uint8_t dinp_len);
+int ec_hello(void);

Added: head/sys/arm/samsung/exynos/chrome_kb.c
==============================================================================
--- /dev/null	00:00:00 1970	(empty, because file is newly added)
+++ head/sys/arm/samsung/exynos/chrome_kb.c	Sun Mar 30 15:22:36 2014	(r263936)
@@ -0,0 +1,792 @@
+/*-
+ * Copyright (c) 2014 Ruslan Bukin <br at bsdpad.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 THE 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 THE 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.
+ */
+
+/*
+ * Samsung Chromebook Keyboard
+ */
+
+#include <sys/cdefs.h>
+__FBSDID("$FreeBSD$");
+
+#include <sys/param.h>
+#include <sys/systm.h>
+#include <sys/bus.h>
+#include <sys/kernel.h>
+#include <sys/module.h>
+#include <sys/malloc.h>
+#include <sys/rman.h>
+#include <sys/proc.h>
+#include <sys/sched.h>
+#include <sys/kdb.h>
+#include <sys/timeet.h>
+#include <sys/timetc.h>
+#include <sys/mutex.h>
+#include <sys/gpio.h>
+
+#include <dev/fdt/fdt_common.h>
+#include <dev/ofw/openfirm.h>
+#include <dev/ofw/ofw_bus.h>
+#include <dev/ofw/ofw_bus_subr.h>
+
+#include <sys/ioccom.h>
+#include <sys/filio.h>
+#include <sys/tty.h>
+#include <sys/kbio.h>
+
+#include <machine/bus.h>
+#include <machine/fdt.h>
+#include <machine/cpu.h>
+#include <machine/intr.h>
+
+#include "gpio_if.h"
+
+#include <arm/samsung/exynos/chrome_ec.h>
+#include <arm/samsung/exynos/chrome_kb.h>
+
+#include <arm/samsung/exynos/exynos5_combiner.h>
+#include <arm/samsung/exynos/exynos5_pad.h>
+
+#define	CKB_LOCK()	mtx_lock(&Giant)
+#define	CKB_UNLOCK()	mtx_unlock(&Giant)
+
+#ifdef	INVARIANTS
+/*
+ * Assert that the lock is held in all contexts
+ * where the code can be executed.
+ */
+#define	CKB_LOCK_ASSERT()	mtx_assert(&Giant, MA_OWNED)
+/*
+ * Assert that the lock is held in the contexts
+ * where it really has to be so.
+ */
+#define	CKB_CTX_LOCK_ASSERT()			 	\
+	do {						\
+		if (!kdb_active && panicstr == NULL)	\
+			mtx_assert(&Giant, MA_OWNED);	\
+	} while (0)
+#else
+#define CKB_LOCK_ASSERT()	(void)0
+#define CKB_CTX_LOCK_ASSERT()	(void)0
+#endif
+
+/*
+ * Define a stub keyboard driver in case one hasn't been
+ * compiled into the kernel
+ */
+#include <sys/kbio.h>
+#include <dev/kbd/kbdreg.h>
+#include <dev/kbd/kbdtables.h>
+
+#define	CKB_NFKEY		12
+#define	CKB_FLAG_COMPOSE	0x1
+#define	CKB_FLAG_POLLING	0x2
+#define	KBD_DRIVER_NAME		"ckbd"
+
+/* TODO: take interrupt from DTS */
+#define	KB_GPIO_INT		146
+
+struct ckb_softc {
+	keyboard_t sc_kbd;
+	keymap_t sc_keymap;
+	accentmap_t sc_accmap;
+	fkeytab_t sc_fkeymap[CKB_NFKEY];
+
+	struct resource*	sc_mem_res;
+	struct resource*	sc_irq_res;
+	void*			sc_intr_hl;
+
+	int	sc_mode;	/* input mode (K_XLATE,K_RAW,K_CODE) */
+	int	sc_state;	/* shift/lock key state */
+	int	sc_accents;	/* accent key index (> 0) */
+	int	sc_flags;	/* flags */
+
+	struct callout		sc_repeat_callout;
+	int			sc_repeat_key;
+	int			sc_repeating;
+
+	int			flag;
+	int			rows;
+	int			cols;
+	device_t		dev;
+	struct thread		*sc_poll_thread;
+
+	uint8_t			*scan_local;
+	uint8_t			*scan;
+};
+
+/* prototypes */
+static void	ckb_set_leds(struct ckb_softc *, uint8_t);
+static int	ckb_set_typematic(keyboard_t *, int);
+static uint32_t	ckb_read_char(keyboard_t *, int);
+static void	ckb_clear_state(keyboard_t *);
+static int	ckb_ioctl(keyboard_t *, u_long, caddr_t);
+static int	ckb_enable(keyboard_t *);
+static int	ckb_disable(keyboard_t *);
+
+static void
+ckb_repeat(void *arg)
+{
+	struct ckb_softc *sc;
+
+	sc = arg;
+
+	if (KBD_IS_ACTIVE(&sc->sc_kbd) && KBD_IS_BUSY(&sc->sc_kbd)) {
+		if (sc->sc_repeat_key != -1) {
+			sc->sc_repeating = 1;
+			sc->sc_kbd.kb_callback.kc_func(&sc->sc_kbd,
+			    KBDIO_KEYINPUT, sc->sc_kbd.kb_callback.kc_arg);
+		}
+	}
+}
+
+/* detect a keyboard, not used */
+static int
+ckb__probe(int unit, void *arg, int flags)
+{
+
+	return (ENXIO);
+}
+
+/* reset and initialize the device, not used */
+static int
+ckb_init(int unit, keyboard_t **kbdp, void *arg, int flags)
+{
+
+	return (ENXIO);
+}
+
+/* test the interface to the device, not used */
+static int
+ckb_test_if(keyboard_t *kbd)
+{
+
+	return (0);
+}
+
+/* finish using this keyboard, not used */
+static int
+ckb_term(keyboard_t *kbd)
+{
+
+	return (ENXIO);
+}
+
+/* keyboard interrupt routine, not used */
+static int
+ckb_intr(keyboard_t *kbd, void *arg)
+{
+
+        return (0);
+}
+
+/* lock the access to the keyboard, not used */
+static int
+ckb_lock(keyboard_t *kbd, int lock)
+{
+
+        return (1);
+}
+
+/* clear the internal state of the keyboard */
+static void
+ckb_clear_state(keyboard_t *kbd)
+{
+	struct ckb_softc *sc;
+
+	sc = kbd->kb_data;
+
+	CKB_CTX_LOCK_ASSERT();
+
+	sc->sc_flags &= ~(CKB_FLAG_COMPOSE | CKB_FLAG_POLLING);
+	sc->sc_state &= LOCK_MASK; /* preserve locking key state */
+	sc->sc_accents = 0;
+}
+
+/* save the internal state, not used */
+static int
+ckb_get_state(keyboard_t *kbd, void *buf, size_t len)
+{
+
+	return (len == 0) ? 1 : -1;
+}
+
+/* set the internal state, not used */
+static int
+ckb_set_state(keyboard_t *kbd, void *buf, size_t len)
+{
+
+	return (EINVAL);
+}
+
+
+/* check if data is waiting */
+static int
+ckb_check(keyboard_t *kbd)
+{
+	struct ckb_softc *sc;
+	int i;
+
+	sc = kbd->kb_data;
+
+	CKB_CTX_LOCK_ASSERT();
+
+	if (!KBD_IS_ACTIVE(kbd))
+		return (0);
+
+	if (sc->sc_flags & CKB_FLAG_POLLING) {
+		return (1);
+	};
+
+	for (i = 0; i < sc->cols; i++)
+		if (sc->scan_local[i] != sc->scan[i]) {
+			return (1);
+		};
+
+	if (sc->sc_repeating)
+		return (1);
+
+	return (0);
+}
+
+/* check if char is waiting */
+static int
+ckb_check_char_locked(keyboard_t *kbd)
+{
+	CKB_CTX_LOCK_ASSERT();
+
+	if (!KBD_IS_ACTIVE(kbd))
+		return (0);
+
+	return (ckb_check(kbd));
+}
+
+static int
+ckb_check_char(keyboard_t *kbd)
+{
+	int result;
+
+	CKB_LOCK();
+	result = ckb_check_char_locked(kbd);
+	CKB_UNLOCK();
+
+	return (result);
+}
+
+/* read one byte from the keyboard if it's allowed */
+/* Currently unused. */
+static int
+ckb_read(keyboard_t *kbd, int wait)
+{
+	CKB_CTX_LOCK_ASSERT();
+
+	if (!KBD_IS_ACTIVE(kbd))
+		return (-1);
+
+	printf("Implement ME: %s\n", __func__);
+	return (0);
+}
+
+int scantokey(int i, int j);
+
+int
+scantokey(int i, int j)
+{
+	int k;
+
+	for (k = 0; k < KEYMAP_LEN; k++)
+		if ((keymap[k].col == i) && (keymap[k].row == j))
+			return (keymap[k].key);
+
+	return (0);
+}
+
+/* read char from the keyboard */
+static uint32_t
+ckb_read_char_locked(keyboard_t *kbd, int wait)
+{
+	struct ckb_softc *sc;
+	int i,j;
+	uint16_t key;
+	int oldbit;
+	int newbit;
+
+	sc = kbd->kb_data;
+
+	CKB_CTX_LOCK_ASSERT();
+
+	if (!KBD_IS_ACTIVE(kbd))
+		return (NOKEY);
+
+	if (sc->sc_repeating) {
+		sc->sc_repeating = 0;
+		callout_reset(&sc->sc_repeat_callout, hz / 10,
+                    ckb_repeat, sc);
+		return (sc->sc_repeat_key);
+	};
+
+	if (sc->sc_flags & CKB_FLAG_POLLING) {
+		/* TODO */
+	};
+
+	for (i = 0; i < sc->cols; i++) {
+		for (j = 0; j < sc->rows; j++) {
+			oldbit = (sc->scan_local[i] & (1 << j));
+			newbit = (sc->scan[i] & (1 << j));
+
+			if (oldbit == newbit)
+				continue;
+
+			key = scantokey(i,j);
+			if (key == 0) {
+				continue;
+			};
+
+			if (newbit > 0) {
+				/* key pressed */
+				sc->scan_local[i] |= (1 << j);
+
+				/* setup repeating */
+				sc->sc_repeat_key = key;
+				callout_reset(&sc->sc_repeat_callout,
+				    hz / 2, ckb_repeat, sc);
+
+			} else {
+				/* key released */
+				sc->scan_local[i] &= ~(1 << j);
+
+				/* release flag */
+				key |= 0x80;
+
+				/* unsetup repeating */
+				sc->sc_repeat_key = -1;
+				callout_stop(&sc->sc_repeat_callout);
+			}
+
+			return (key);
+		}
+	}
+
+	return (NOKEY);
+}
+
+/* Currently wait is always false. */
+static uint32_t
+ckb_read_char(keyboard_t *kbd, int wait)
+{
+	uint32_t keycode;
+
+	CKB_LOCK();
+	keycode = ckb_read_char_locked(kbd, wait);
+	CKB_UNLOCK();
+
+	return (keycode);
+}
+
+
+/* some useful control functions */
+static int
+ckb_ioctl_locked(keyboard_t *kbd, u_long cmd, caddr_t arg)
+{
+	struct ckb_softc *sc;
+	int i;
+
+	sc = kbd->kb_data;
+
+	CKB_LOCK_ASSERT();
+
+	switch (cmd) {
+	case KDGKBMODE:		/* get keyboard mode */
+		*(int *)arg = sc->sc_mode;
+		break;
+
+	case KDSKBMODE:		/* set keyboard mode */
+		switch (*(int *)arg) {
+		case K_XLATE:
+			if (sc->sc_mode != K_XLATE) {
+				/* make lock key state and LED state match */
+				sc->sc_state &= ~LOCK_MASK;
+				sc->sc_state |= KBD_LED_VAL(kbd);
+			}
+			/* FALLTHROUGH */
+		case K_RAW:
+		case K_CODE:
+			if (sc->sc_mode != *(int *)arg) {
+				if ((sc->sc_flags & CKB_FLAG_POLLING) == 0)
+					ckb_clear_state(kbd);
+				sc->sc_mode = *(int *)arg;
+			}
+			break;
+		default:
+			return (EINVAL);
+		}
+		break;
+
+	case KDGETLED:			/* get keyboard LED */
+		*(int *)arg = KBD_LED_VAL(kbd);
+		break;
+
+	case KDSETLED:			/* set keyboard LED */
+		/* NOTE: lock key state in "sc_state" won't be changed */
+		if (*(int *)arg & ~LOCK_MASK)
+			return (EINVAL);
+
+		i = *(int *)arg;
+
+		/* replace CAPS LED with ALTGR LED for ALTGR keyboards */
+		if (sc->sc_mode == K_XLATE &&
+		    kbd->kb_keymap->n_keys > ALTGR_OFFSET) {
+			if (i & ALKED)
+				i |= CLKED;
+			else
+				i &= ~CLKED;
+		}
+		if (KBD_HAS_DEVICE(kbd)) {
+			/* Configure LED */
+		}
+
+		KBD_LED_VAL(kbd) = *(int *)arg;
+		break;
+	case KDGKBSTATE:		/* get lock key state */
+		*(int *)arg = sc->sc_state & LOCK_MASK;
+		break;
+
+	case KDSKBSTATE:		/* set lock key state */
+		if (*(int *)arg & ~LOCK_MASK) {
+			return (EINVAL);
+		}
+		sc->sc_state &= ~LOCK_MASK;
+		sc->sc_state |= *(int *)arg;
+
+		/* set LEDs and quit */
+		return (ckb_ioctl(kbd, KDSETLED, arg));
+
+	case KDSETREPEAT:		/* set keyboard repeat rate (new
+					 * interface) */
+
+		if (!KBD_HAS_DEVICE(kbd)) {
+			return (0);
+		}
+		if (((int *)arg)[1] < 0) {
+			return (EINVAL);
+		}
+		if (((int *)arg)[0] < 0) {
+			return (EINVAL);
+		}
+		if (((int *)arg)[0] < 200)	/* fastest possible value */
+			kbd->kb_delay1 = 200;
+		else
+			kbd->kb_delay1 = ((int *)arg)[0];
+		kbd->kb_delay2 = ((int *)arg)[1];
+		return (0);
+
+	case KDSETRAD:			/* set keyboard repeat rate (old
+					 * interface) */
+		return (ckb_set_typematic(kbd, *(int *)arg));
+
+	case PIO_KEYMAP:		/* set keyboard translation table */
+	case OPIO_KEYMAP:		/* set keyboard translation table
+					 * (compat) */
+	case PIO_KEYMAPENT:		/* set keyboard translation table
+					 * entry */
+	case PIO_DEADKEYMAP:		/* set accent key translation table */
+		sc->sc_accents = 0;
+		/* FALLTHROUGH */
+	default:
+		return (genkbd_commonioctl(kbd, cmd, arg));
+	}
+
+	return (0);
+}
+
+static int
+ckb_ioctl(keyboard_t *kbd, u_long cmd, caddr_t arg)
+{
+	int result;
+
+	/*
+	 * XXX KDGKBSTATE, KDSKBSTATE and KDSETLED can be called from any
+	 * context where printf(9) can be called, which among other things
+	 * includes interrupt filters and threads with any kinds of locks
+	 * already held.  For this reason it would be dangerous to acquire
+	 * the Giant here unconditionally.  On the other hand we have to
+	 * have it to handle the ioctl.
+	 * So we make our best effort to auto-detect whether we can grab
+	 * the Giant or not.  Blame syscons(4) for this.
+	 */
+	switch (cmd) {
+	case KDGKBSTATE:
+	case KDSKBSTATE:
+	case KDSETLED:
+		if (!mtx_owned(&Giant) && !SCHEDULER_STOPPED())
+			return (EDEADLK);	/* best I could come up with */
+		/* FALLTHROUGH */
+	default:
+		CKB_LOCK();
+		result = ckb_ioctl_locked(kbd, cmd, arg);
+		CKB_UNLOCK();
+		return (result);
+	}
+}
+
+
+/*
+ * Enable the access to the device; until this function is called,
+ * the client cannot read from the keyboard.
+ */
+static int
+ckb_enable(keyboard_t *kbd)
+{
+
+	CKB_LOCK();
+	KBD_ACTIVATE(kbd);
+	CKB_UNLOCK();
+
+	return (0);
+}
+
+/* disallow the access to the device */
+static int
+ckb_disable(keyboard_t *kbd)
+{
+
+	CKB_LOCK();
+	KBD_DEACTIVATE(kbd);
+	CKB_UNLOCK();
+
+	return (0);
+}
+
+/* local functions */
+
+static int
+ckb_set_typematic(keyboard_t *kbd, int code)
+{
+	static const int delays[] = {250, 500, 750, 1000};
+	static const int rates[] = {34, 38, 42, 46, 50, 55, 59, 63,
+		68, 76, 84, 92, 100, 110, 118, 126,
+		136, 152, 168, 184, 200, 220, 236, 252,
+	272, 304, 336, 368, 400, 440, 472, 504};
+
+	if (code & ~0x7f) {
+		return (EINVAL);
+	}
+	kbd->kb_delay1 = delays[(code >> 5) & 3];
+	kbd->kb_delay2 = rates[code & 0x1f];
+	return (0);
+}
+
+static int
+ckb_poll(keyboard_t *kbd, int on)
+{
+	struct ckb_softc *sc;
+
+	sc = kbd->kb_data;
+
+	CKB_LOCK();
+	if (on) {
+		sc->sc_flags |= CKB_FLAG_POLLING;
+		sc->sc_poll_thread = curthread;
+	} else {
+		sc->sc_flags &= ~CKB_FLAG_POLLING;
+	}
+	CKB_UNLOCK();
+
+	return (0);
+}
+
+/* local functions */
+
+static int dummy_kbd_configure(int flags);
+
+keyboard_switch_t ckbdsw = {
+	.probe = &ckb__probe,
+	.init = &ckb_init,
+	.term = &ckb_term,
+	.intr = &ckb_intr,
+	.test_if = &ckb_test_if,
+	.enable = &ckb_enable,
+	.disable = &ckb_disable,
+	.read = &ckb_read,
+	.check = &ckb_check,
+	.read_char = &ckb_read_char,
+	.check_char = &ckb_check_char,
+	.ioctl = &ckb_ioctl,
+	.lock = &ckb_lock,
+	.clear_state = &ckb_clear_state,
+	.get_state = &ckb_get_state,
+	.set_state = &ckb_set_state,
+	.get_fkeystr = &genkbd_get_fkeystr,
+	.poll = &ckb_poll,
+	.diag = &genkbd_diag,
+};
+
+static int
+dummy_kbd_configure(int flags)
+{
+
+	return (0);
+}
+
+KEYBOARD_DRIVER(ckbd, ckbdsw, dummy_kbd_configure);
+
+static int
+parse_dts(struct ckb_softc *sc)
+{
+	phandle_t node;
+	pcell_t dts_value;
+	int len;
+
+	if ((node = ofw_bus_get_node(sc->dev)) == -1)
+		return (ENXIO);
+
+	if ((len = OF_getproplen(node, "keypad,num-rows")) <= 0)
+		return (ENXIO);
+	OF_getprop(node, "keypad,num-rows", &dts_value, len);
+	sc->rows = fdt32_to_cpu(dts_value);
+
+	if ((len = OF_getproplen(node, "keypad,num-columns")) <= 0)
+		return (ENXIO);
+	OF_getprop(node, "keypad,num-columns", &dts_value, len);
+	sc->cols = fdt32_to_cpu(dts_value);
+
+	if ((sc->rows == 0) || (sc->cols == 0))
+		return (ENXIO);
+
+	return (0);
+}
+

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


More information about the svn-src-all mailing list