summaryrefslogtreecommitdiff
path: root/gpio
diff options
context:
space:
mode:
authorNoé Rubinstein <nrubinstein@proformatique.com>2010-07-28 12:25:26 +0200
committerNoé Rubinstein <nrubinstein@proformatique.com>2010-07-28 12:25:26 +0200
commited6f4dbfa44f154af94776093a2b43fc7a8a7320 (patch)
treef005809a0ba245d6ca4f7ecfa1e6075db1fe7687 /gpio
parentf10dbbcb7cd35ac9bc3406dab41177572faa884d (diff)
GPIO kernel interface driver
Diffstat (limited to 'gpio')
-rw-r--r--gpio/Makefile13
-rw-r--r--gpio/common.h134
-rw-r--r--gpio/gpio.c490
-rw-r--r--gpio/gpio.h130
4 files changed, 767 insertions, 0 deletions
diff --git a/gpio/Makefile b/gpio/Makefile
new file mode 100644
index 0000000..c4cd3b7
--- /dev/null
+++ b/gpio/Makefile
@@ -0,0 +1,13 @@
+PWD := $(shell pwd)
+
+KSRC ?= /bad__ksrc__not_set
+
+obj-m := gpio.o
+modules:
+
+modules modules_install clean:
+ $(MAKE) -C $(KSRC) M=$(PWD) $@
+
+distclean: clean
+ rm -f Module.symvers
+
diff --git a/gpio/common.h b/gpio/common.h
new file mode 100644
index 0000000..22eda01
--- /dev/null
+++ b/gpio/common.h
@@ -0,0 +1,134 @@
+
+/*
+ * This file is provided under a dual BSD/GPLv2 license. When using or
+ * redistributing this file, you may do so under either license.
+ *
+ * GPL LICENSE SUMMARY
+ *
+ * Copyright(c) 2007,2008,2009 Intel Corporation. All rights reserved.
+ *
+ * This program is free software; you can redistribute it and/or modify
+ * it under the terms of version 2 of the GNU General Public License as
+ * published by the Free Software Foundation.
+ *
+ * This program is distributed in the hope that it will be useful, but
+ * WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
+ * General Public License for more details.
+ *
+ * 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., 51 Franklin St - Fifth Floor, Boston, MA 02110-1301 USA.
+ * The full GNU General Public License is included in this distribution
+ * in the file called LICENSE.GPL.
+ *
+ * Contact Information:
+ * Intel Corporation
+ *
+ * BSD LICENSE
+ *
+ * Copyright(c) 2007,2008,2009 Intel Corporation. All rights reserved.
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * * Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * * 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.
+ * * Neither the name of Intel Corporation nor the names of its
+ * contributors may be used to endorse or promote products derived
+ * from this software without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS 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 COPYRIGHT
+ * OWNER 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.
+ *
+ *
+ * version: Embedded.L.1.0.3-144
+ */
+
+/*****************************************************************************
+ * Module name:
+ * gpio
+ *
+ * Abstract:
+ * This header file is to be included by the gpio.c file only.
+ * It is OS independent.
+ *
+ * Revision:
+ *
+ *
+ *****************************************************************************/
+
+#ifndef COMMON_H
+#define COMMON_H
+
+#define SEL 2
+#define LVL 2
+
+//offset into low pin count(LPC) config space of the GPIO base address
+#define GPIO_BAR_OFFSET 0x48
+
+//vendor and device IDs of LPC device
+#define LPC_VENDOR_ID 0x8086
+#define LPC_DEVICE_ID 0x5031
+
+//Location of the LPC device on the PCI bus
+#define LPC_BUS_NUM 0
+#define LPC_DEVICE_NUM 31
+#define LPC_FUNCTION_NUM 0
+
+#define MAX_GPIO_SIGNALS 64
+
+//GPIO register memory size in bytes
+#define GPIO_MEM_SIZE 64
+
+//msb bit number of a GPIO register
+#define GPIO_REG_MSB 31
+
+//number of bits in a GPIO register
+#define GPIO_REG_BITS 32
+
+// offsets for gpio registers
+#define GPIO_USE_SEL 0x00
+#define GP_IO_SEL 0x04
+#define GP_LVL 0x0c
+#define GPO_BLINK 0x18
+#define GPI_INV 0x2c
+#define GPIO_USE_SEL2 0x30
+#define GP_IO_SEL2 0x34
+#define GP_LVL2 0x38
+
+
+/******************************************************************************
+ Description:
+ This structure contains an IO address to each of the gpio registers
+ contained in the hardware device memory. Each register can then be
+ accessed using the IO address.
+ *****************************************************************************/
+struct gpio_regs
+{
+ unsigned int gpio_use_sel; // alternative or gpio function (signals 0-31)
+ unsigned int gp_io_sel; // input or output (signals 0-31)
+ unsigned int gp_lvl; // low or high level (signals 0-31)
+ unsigned int gpo_blink; // blink function (signals 0-31)
+ unsigned int gpi_inv; // invert function (signals 0-31)
+ unsigned int gpio_use_sel2; // alternative or gpio function (signals 32-63)
+ unsigned int gp_io_sel2; // input or output (signals 32-63)
+ unsigned int gp_lvl2; // low or high level (signals 32-63)
+};
+
+#endif
diff --git a/gpio/gpio.c b/gpio/gpio.c
new file mode 100644
index 0000000..abecc1f
--- /dev/null
+++ b/gpio/gpio.c
@@ -0,0 +1,490 @@
+
+/*
+ * This file is provided under a dual BSD/GPLv2 license. When using or
+ * redistributing this file, you may do so under either license.
+ *
+ * GPL LICENSE SUMMARY
+ *
+ * Copyright(c) 2007,2008,2009 Intel Corporation. All rights reserved.
+ *
+ * This program is free software; you can redistribute it and/or modify
+ * it under the terms of version 2 of the GNU General Public License as
+ * published by the Free Software Foundation.
+ *
+ * This program is distributed in the hope that it will be useful, but
+ * WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
+ * General Public License for more details.
+ *
+ * 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., 51 Franklin St - Fifth Floor, Boston, MA 02110-1301 USA.
+ * The full GNU General Public License is included in this distribution
+ * in the file called LICENSE.GPL.
+ *
+ * Contact Information:
+ * Intel Corporation
+ *
+ * BSD LICENSE
+ *
+ * Copyright(c) 2007,2008,2009 Intel Corporation. All rights reserved.
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * * Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * * 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.
+ * * Neither the name of Intel Corporation nor the names of its
+ * contributors may be used to endorse or promote products derived
+ * from this software without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS 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 COPYRIGHT
+ * OWNER 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.
+ *
+ *
+ * version: Embedded.L.1.0.3-144
+ */
+
+/*****************************************************************************
+ * @ingroup GPIO_GENERAL
+ *
+ * @file gpio_ref.c
+ *
+ * @description
+ * The gpio module is a linux driver which provides a reference
+ * implementation for the control of the gpio signals.
+ * Communication is done through the ioctl API
+ * and gpio signal control is accomplished using the set of ioctl
+ * control codes which are defined for this driver.
+ *
+ *****************************************************************************/
+
+#include <linux/delay.h>
+#include "gpio.h"
+
+MODULE_AUTHOR("Intel(R) Corporation, Proformatique");
+MODULE_DESCRIPTION("General Purpose I/O Pin Driver");
+MODULE_LICENSE("Dual BSD/GPL");
+MODULE_VERSION("1.0.0");
+
+struct drvr_data g_drvr_data;
+
+#define debug(code) if(code < 0) printk(#code " FAILE\n");
+void gpio_test(void)
+{
+ debug(gpio_set_to_gpio(21));
+
+ debug(gpio_set_direction(21, GPIO_OUTPUT));
+ printk("HIGH\n");
+ debug(gpio_set_level(21, GPIO_HIGH));
+ msleep(1000);
+ printk("BLINK\n");
+ debug(gpio_set_blink(21, 1));
+ msleep(1000);
+ debug(gpio_set_blink(21, 0));
+ printk("LOW\n");
+ debug(gpio_set_level(21, GPIO_LOW));
+ msleep(1000);
+
+}
+
+/*****************************************************************************
+ Description:
+ Entry point for the driver.
+
+ Parameters:
+ none
+
+ Returns:
+ 0 => success
+ < 0 => error
+******************************************************************************/
+int gpio_init(void)
+{
+ struct pci_dev *pdev = NULL;
+
+ g_drvr_data.mem_base = 0;
+ g_drvr_data.mem_resrvd = 0;
+
+ /* Get dev struct for the LPC device. The GPIO BAR is located in the
+ LPC device config space */
+ pdev = pci_get_device(LPC_VENDOR_ID, LPC_DEVICE_ID, NULL);
+
+ if (!pdev) {
+ printk("%s:gpio_init-Could not find pci device\n", DRIVERNAME);
+ goto Exit_Error;
+ }
+
+ /* Get base address from the LPC configuration space. */
+ pci_read_config_dword(pdev, GPIO_BAR_OFFSET, &(g_drvr_data.mem_base));
+
+ /* remove the lsb which indicates io memory */
+ g_drvr_data.mem_base -= 1;
+
+ printk("base addr %x\n", g_drvr_data.mem_base);
+
+ /* release reference to device */
+ pci_dev_put(pdev);
+
+ /* obtain exclusive access to GPIO memory space */
+ if (!request_region(g_drvr_data.mem_base, GPIO_MEM_SIZE, DRIVERNAME)) {
+ printk("%s:gpio_init-IO memory region cannot be accessed\n",
+ DRIVERNAME);
+ goto Exit_Error;
+ }
+
+ /* indicate memory space reserved */
+ g_drvr_data.mem_resrvd = 1;
+
+ /* set the addrs in the i/o memory addr structure */
+ set_reg_addrs(g_drvr_data.mem_base);
+
+ gpio_test();
+
+ goto Exit;
+
+ Exit_Error:
+ printk("%s:gpio_init-Initialization failed\n", DRIVERNAME);
+ gpio_close();
+ return -ENODEV;
+
+ Exit:
+ printk("%s:gpio_init-Initialization complete\n", DRIVERNAME);
+ return 0;
+}
+
+/*****************************************************************************
+ Description:
+ This function is called when the driver is unloaded from memory.
+
+ Parameters:
+ none
+
+ Returns:
+ none
+******************************************************************************/
+void gpio_close(void)
+{
+ /* release the reserved IO memory space */
+ if ( g_drvr_data.mem_resrvd )
+ {
+ release_region(g_drvr_data.mem_base, GPIO_MEM_SIZE);
+ }
+
+ printk("%s:gpio_close-Driver unload complete\n", DRIVERNAME);
+}
+
+int gpio_set_to_gpio_(int signal, int gpio)
+{
+ u32 bitstr, io_addr;
+
+ if(signal >= MAX_GPIO_SIGNALS)
+ return -EINVAL;
+
+ /* set register to use */
+ signal < (MAX_GPIO_SIGNALS/SEL) ?
+ (io_addr = g_drvr_data.regs.gpio_use_sel) :
+ (io_addr = g_drvr_data.regs.gpio_use_sel2);
+
+ /* get the register contents */
+ bitstr = inl(io_addr);
+
+ if(gpio)
+ /* set bit to use pin for gpio */
+ set_bit(signal%GPIO_REG_BITS, (void*)&bitstr);
+ else
+ /* clear bit to use pin for alternative function */
+ clear_bit(signal%GPIO_REG_BITS, (void*)&bitstr);
+
+ /* write the modified string back to the gpio register */
+ outl(bitstr, io_addr);
+
+ return 0;
+}
+int gpio_set_to_gpio(int signal) { return gpio_set_to_gpio_(signal, 1); }
+int gpio_set_to_alternative(int signal) { return gpio_set_to_gpio_(signal, 0); }
+
+int gpio_set_direction(int signal, int direction)
+{
+ u32 bitstr, io_addr;
+
+ if(signal >= MAX_GPIO_SIGNALS)
+ return -EINVAL;
+
+ /* set register to use */
+ signal < (MAX_GPIO_SIGNALS/SEL) ?
+ (io_addr = g_drvr_data.regs.gp_io_sel) :
+ (io_addr = g_drvr_data.regs.gp_io_sel2);
+
+ /* get the register contents */
+ bitstr = inl(io_addr);
+
+ if ( direction == GPIO_OUTPUT )
+ /* clear bit to use pin as output */
+ clear_bit(signal%GPIO_REG_BITS, (void*)&bitstr);
+ else
+ /* set bit to use pin as input */
+ set_bit(signal%GPIO_REG_BITS, (void*)&bitstr);
+
+ /* write the modified string back to the gpio register */
+ outl(bitstr, io_addr);
+
+ return 0;
+}
+
+int gpio_set_level(int signal, int high)
+{
+ u32 bitstr, io_addr;
+
+ if(signal >= MAX_GPIO_SIGNALS)
+ return -EINVAL;
+
+ signal < (MAX_GPIO_SIGNALS/LVL) ?
+ (io_addr = g_drvr_data.regs.gp_lvl) :
+ (io_addr = g_drvr_data.regs.gp_lvl2);
+
+ /* get the register contents */
+ bitstr = inl(io_addr);
+
+ if(high)
+ /* write a 1 to output pin */
+ set_bit(signal%GPIO_REG_BITS, (void*)&bitstr);
+ else
+ /* write a 0 to output pin */
+ clear_bit(signal%GPIO_REG_BITS, (void*)&bitstr);
+
+ /* write the modified string back to the gpio register */
+ outl(bitstr, io_addr);
+
+ return 0;
+}
+
+/* Returns a positive number if the signal is high, 0 if the signal is low, and
+ * a negative number for errors
+ */
+int gpio_get_level(int signal)
+{
+ u32 bitstr, io_addr;
+
+ if(signal >= MAX_GPIO_SIGNALS)
+ return -EINVAL;
+
+ /* set register to use */
+ signal < (MAX_GPIO_SIGNALS/LVL) ?
+ (io_addr = g_drvr_data.regs.gp_lvl) :
+ (io_addr = g_drvr_data.regs.gp_lvl2);
+
+ /* get the register contents */
+ bitstr = inl(io_addr);
+
+ return test_bit(signal%GPIO_REG_BITS, (void*)&bitstr) ? 1 : 0;
+}
+
+int gpio_set_blink(int signal, int blink)
+{
+ u32 bitstr;
+
+ if(signal >= MAX_GPIO_SIGNALS)
+ return -EINVAL;
+
+ bitstr = inl(g_drvr_data.regs.gpo_blink);
+
+ if(blink)
+ /* set pin to blink mode */
+ set_bit(signal%GPIO_REG_BITS, (void*)&bitstr);
+ else
+ /* set pin to non-blink mode */
+ clear_bit(signal%GPIO_REG_BITS, (void*)&bitstr);
+
+ /* write the modified string back to the gpio register */
+ outl(bitstr, g_drvr_data.regs.gpo_blink);
+
+ return 0;
+}
+
+int gpio_inverted_input(int signal, int inverted)
+{
+ u32 bitstr;
+
+ if(signal >= MAX_GPIO_SIGNALS)
+ return -EINVAL;
+
+ bitstr = inl(g_drvr_data.regs.gpi_inv);
+
+ if(inverted)
+ /* set pin to inverted mode */
+ set_bit(signal%GPIO_REG_BITS, (void*)&bitstr);
+ else
+ /* set pin to noninverted mode */
+ clear_bit(signal%GPIO_REG_BITS, (void*)&bitstr);
+
+ /* write the modified string back to the gpio register */
+ outl(bitstr, g_drvr_data.regs.gpi_inv);
+
+ return 0;
+}
+
+const struct gpio_regs* gpio_regs(void)
+{
+ return &g_drvr_data.regs;
+}
+
+/*****************************************************************************
+ Description:
+ Set i/o memory ports.
+
+ Parameters:
+ addr start address of gpio registers
+
+ Returns:
+ void
+
+******************************************************************************/
+void set_reg_addrs(unsigned int addr)
+{
+ g_drvr_data.regs.gpio_use_sel = addr + GPIO_USE_SEL;
+ g_drvr_data.regs.gp_io_sel = addr + GP_IO_SEL;
+ g_drvr_data.regs.gp_lvl = addr + GP_LVL;
+ g_drvr_data.regs.gpo_blink = addr + GPO_BLINK;
+ g_drvr_data.regs.gpi_inv = addr + GPI_INV;
+ g_drvr_data.regs.gpio_use_sel2 = addr + GPIO_USE_SEL2;
+ g_drvr_data.regs.gp_io_sel2 = addr + GP_IO_SEL2;
+ g_drvr_data.regs.gp_lvl2 = addr + GP_LVL2;
+}
+
+
+/*****************************************************************************
+ Description:
+ Creates a string that reflects the current state of a gpio signal.
+
+ Parameters:
+ Signal signal number to return info on
+ pBuff string buff to hold returned signal info
+
+ Returns:
+ 0 => success
+ < 0 => error
+
+******************************************************************************/
+int gpio_getpininfo(int Signal, char *pBuff)
+{
+ unsigned int data;
+
+ /* make sure passed in signal is within max */
+ if (Signal >= MAX_GPIO_SIGNALS) {
+ printk("%s:gpio_getpininfo-signal value is out of bounds "
+ "(%d)\n", DRIVERNAME, Signal);
+ return -1;
+ }
+
+ sprintf(pBuff, "Signal# %d - ", Signal);
+
+ /* get current use setting: alternative or gpio */
+
+ strcat(pBuff, "Use setting:");
+
+ Signal < (MAX_GPIO_SIGNALS / SEL) ?
+ (data = inl(g_drvr_data.regs.gpio_use_sel)) :
+ (data = inl(g_drvr_data.regs.gpio_use_sel2));
+
+ /* if set as gpio */
+ if (test_bit(Signal % GPIO_REG_BITS, (void *)&data)) {
+ strcat(pBuff, "gpio");
+ } else {
+ strcat(pBuff, "alternative");
+ }
+
+ strcat(pBuff, ", ");
+
+ /* get current io setting: input or output */
+
+ strcat(pBuff, "IO setting:");
+
+ Signal < (MAX_GPIO_SIGNALS / SEL) ?
+ (data = inl(g_drvr_data.regs.gp_io_sel)) :
+ (data = inl(g_drvr_data.regs.gp_io_sel2));
+
+ /* if set as input */
+ if (test_bit(Signal % GPIO_REG_BITS, (void *)&data)) {
+ strcat(pBuff, "input");
+ } else {
+ strcat(pBuff, "output");
+ }
+
+ strcat(pBuff, ", ");
+
+ /* get current pin level: high or low */
+
+ strcat(pBuff, "Level:");
+
+ Signal < (MAX_GPIO_SIGNALS / LVL) ?
+ (data = inl(g_drvr_data.regs.gp_lvl)) :
+ (data = inl(g_drvr_data.regs.gp_lvl2));
+
+ /* if high */
+ if (test_bit(Signal % GPIO_REG_BITS, (void *)&data)) {
+ strcat(pBuff, "high");
+ } else {
+ strcat(pBuff, "low");
+ }
+
+ strcat(pBuff, ", ");
+
+ /* get blink setting */
+
+ strcat(pBuff, "Blink:");
+
+ data = inl(g_drvr_data.regs.gpo_blink);
+
+ /* current setting: on or off */
+ if (test_bit(Signal % GPIO_REG_BITS, (void *)&data)) {
+ strcat(pBuff, "on");
+ } else {
+ strcat(pBuff, "off");
+ }
+
+ strcat(pBuff, ", ");
+
+ /* get inversion setting */
+
+ strcat(pBuff, "Inversion:");
+
+ data = inl(g_drvr_data.regs.gpi_inv);
+
+ /* current setting: inverted or noninverted */
+ if (test_bit(Signal % GPIO_REG_BITS, (void *)&data)) {
+ strcat(pBuff, "on");
+ } else {
+ strcat(pBuff, "off");
+ }
+
+ return 0;
+}
+
+module_init(gpio_init);
+module_exit(gpio_close);
+
+EXPORT_SYMBOL(gpio_set_to_gpio);
+EXPORT_SYMBOL(gpio_set_to_alternative);
+EXPORT_SYMBOL(gpio_set_direction);
+EXPORT_SYMBOL(gpio_set_level);
+EXPORT_SYMBOL(gpio_get_level);
+EXPORT_SYMBOL(gpio_set_blink);
+EXPORT_SYMBOL(gpio_inverted_input);
+EXPORT_SYMBOL(gpio_regs);
+
diff --git a/gpio/gpio.h b/gpio/gpio.h
new file mode 100644
index 0000000..44ae744
--- /dev/null
+++ b/gpio/gpio.h
@@ -0,0 +1,130 @@
+
+/*
+ * This file is provided under a dual BSD/GPLv2 license. When using or
+ * redistributing this file, you may do so under either license.
+ *
+ * GPL LICENSE SUMMARY
+ *
+ * Copyright(c) 2007,2008,2009 Intel Corporation. All rights reserved.
+ *
+ * This program is free software; you can redistribute it and/or modify
+ * it under the terms of version 2 of the GNU General Public License as
+ * published by the Free Software Foundation.
+ *
+ * This program is distributed in the hope that it will be useful, but
+ * WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
+ * General Public License for more details.
+ *
+ * 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., 51 Franklin St - Fifth Floor, Boston, MA 02110-1301 USA.
+ * The full GNU General Public License is included in this distribution
+ * in the file called LICENSE.GPL.
+ *
+ * Contact Information:
+ * Intel Corporation
+ *
+ * BSD LICENSE
+ *
+ * Copyright(c) 2007,2008,2009 Intel Corporation. All rights reserved.
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * * Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * * 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.
+ * * Neither the name of Intel Corporation nor the names of its
+ * contributors may be used to endorse or promote products derived
+ * from this software without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS 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 COPYRIGHT
+ * OWNER 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.
+ *
+ *
+ * version: Embedded.L.1.0.3-144
+ */
+
+/*****************************************************************************
+ * Module name:
+ * gpio
+ *
+ * Abstract:
+ * This header file is to be included by the gpio.c file only.
+ *
+ * Revision:
+ * TBD
+ *
+ *****************************************************************************/
+
+#ifndef GPIO_H
+#define GPIO_H
+
+#include <linux/module.h>
+#include <linux/kernel.h>
+#include <linux/socket.h>
+#include <linux/poll.h>
+#include <linux/init.h>
+#include <linux/fs.h>
+#include <linux/errno.h>
+#include <linux/types.h>
+#include <linux/proc_fs.h>
+#include <linux/fcntl.h>
+#include <linux/interrupt.h>
+#include <asm/system.h>
+#include <asm/uaccess.h>
+#include <linux/pci.h>
+
+#include "common.h"
+
+#define DRIVERNAME "gpio_ref"
+
+
+/******************************************************************************
+
+ Description:
+ This structure contains data that is used for most driver operations.
+
+ *****************************************************************************/
+struct drvr_data
+{
+ struct gpio_regs regs;
+ void *mem_virt;
+ unsigned int mem_base;
+ unsigned int mem_resrvd;
+};
+
+enum gpio_direction { GPIO_INPUT, GPIO_OUTPUT };
+enum gpio_level { GPIO_LOW, GPIO_HIGH };
+
+int gpio_set_to_gpio(int signal);
+int gpio_set_to_alternative(int signal);
+int gpio_set_direction(int signal, int direction);
+int gpio_set_level(int signal, int level);
+int gpio_get_level(int signal);
+int gpio_set_blink(int signal, int blink);
+int gpio_inverted_input(int signal, int inverted);
+const struct gpio_regs* gpio_regs(void);
+
+int gpio_init(void);
+void gpio_close(void);
+int gpio_getpininfo(int Signal, char *pBuff);
+void set_reg_addrs(unsigned int addr);
+
+#endif
+