summaryrefslogtreecommitdiff
path: root/drivers
diff options
context:
space:
mode:
Diffstat (limited to 'drivers')
-rwxr-xr-xdrivers/input/touchscreen/Kconfig20
-rwxr-xr-xdrivers/input/touchscreen/Makefile2
-rw-r--r--drivers/input/touchscreen/colibri-vf50-ts.c413
-rw-r--r--drivers/input/touchscreen/fusion_F0710A.c502
-rw-r--r--drivers/input/touchscreen/fusion_F0710A.h87
-rw-r--r--drivers/misc/mvf_adc.c381
-rw-r--r--drivers/mtd/nand/fsl_nfc.c129
-rw-r--r--drivers/mtd/nand/nand_ids.c1
-rw-r--r--drivers/net/Kconfig7
-rwxr-xr-xdrivers/net/fec.c10
-rw-r--r--drivers/net/phy/micrel.c10
-rw-r--r--drivers/spi/spi_mvf_dspi.c49
-rw-r--r--drivers/tty/serial/mvf.c23
-rw-r--r--drivers/video/mvf_dcu.c277
14 files changed, 1675 insertions, 236 deletions
diff --git a/drivers/input/touchscreen/Kconfig b/drivers/input/touchscreen/Kconfig
index dcd283c11eaa..482013b2225f 100755
--- a/drivers/input/touchscreen/Kconfig
+++ b/drivers/input/touchscreen/Kconfig
@@ -777,4 +777,24 @@ config TOUCHSCREEN_CRTOUCH
To compile this driver as a module, choose M here: the
module will be called crtouch_ts.
+
+config TOUCHSCREEN_COLIBRI_VF50
+ tristate "Toradex Colibri on board touchscreen driver"
+ depends on ARCH_MVF && MVF_ADC
+ help
+ Say Y here if you have a Colibri VF50 and plan to use
+ the on-board provided 4-wire touchscreen driver.
+
+ If unsure, say N.
+
+ To compile this driver as a module, choose M here: the
+ module will be called colibri_vf50_ts.
+
+config TOUCHSCREEN_FUSION_F0710A
+ tristate "TouchRevolution Fusion F0710A Touchscreens"
+ depends on I2C
+ help
+ Say Y here if you want to support the multi-touch input driver for
+ the TouchRevolution Fusion 7 and 10 panels.
+
endif
diff --git a/drivers/input/touchscreen/Makefile b/drivers/input/touchscreen/Makefile
index efed4c9c3adc..66b42836bc7e 100755
--- a/drivers/input/touchscreen/Makefile
+++ b/drivers/input/touchscreen/Makefile
@@ -66,3 +66,5 @@ obj-$(CONFIG_TOUCHSCREEN_TPS6507X) += tps6507x-ts.o
obj-$(CONFIG_TOUCHSCREEN_MAX11801) += max11801_ts.o
obj-$(CONFIG_TOUCHSCREEN_EGALAX) += egalax_ts.o
obj-$(CONFIG_TOUCHSCREEN_CRTOUCH) += crtouch_ts.o
+obj-$(CONFIG_TOUCHSCREEN_COLIBRI_VF50) += colibri-vf50-ts.o
+obj-$(CONFIG_TOUCHSCREEN_FUSION_F0710A) += fusion_F0710A.o
diff --git a/drivers/input/touchscreen/colibri-vf50-ts.c b/drivers/input/touchscreen/colibri-vf50-ts.c
new file mode 100644
index 000000000000..bc42253f778b
--- /dev/null
+++ b/drivers/input/touchscreen/colibri-vf50-ts.c
@@ -0,0 +1,413 @@
+/* Copyright 2013 Toradex AG
+ *
+ * Toradex Colibri VF50 Touchscreen driver
+ *
+ * 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.
+*/
+
+#include <linux/module.h>
+#include <linux/kernel.h>
+#include <linux/platform_device.h>
+#include <linux/sched.h>
+#include <linux/list.h>
+#include <linux/slab.h>
+#include <linux/err.h>
+#include <linux/clk.h>
+#include <linux/interrupt.h>
+#include <linux/uaccess.h>
+#include <linux/miscdevice.h>
+#include <linux/mvf_adc.h>
+#include <linux/device.h>
+#include <linux/cdev.h>
+#include <linux/input.h>
+#include <linux/delay.h>
+#include <linux/gpio.h>
+#include <mach/colibri-ts.h>
+
+#define DRIVER_NAME "colibri-vf50-ts"
+#define DRV_VERSION "1.0"
+
+#define MVF_ADC_MAX ((1 << 12) - 1)
+
+#define COLI_TOUCH_MIN_DELAY_US 1000
+#define COLI_TOUCH_MAX_DELAY_US 2000
+
+struct adc_touch_device {
+ struct platform_device *pdev;
+
+ bool stop_touchscreen;
+
+ int pen_irq;
+ struct input_dev *ts_input;
+ struct workqueue_struct *ts_workqueue;
+ struct work_struct ts_work;
+};
+
+struct adc_touch_device *touch;
+
+/*
+ * Enables given plates and measures touch parameters using ADC
+ */
+static int adc_ts_measure(int plate_p, int plate_m, int adc, int adc_channel)
+{
+ int i, value = 0;
+ gpio_set_value(plate_p, 0); /* Low active */
+ gpio_set_value(plate_m, 1); /* High active */
+
+ /* Use hrtimer sleep since msleep sleeps 10ms+ */
+ usleep_range(COLI_TOUCH_MIN_DELAY_US, COLI_TOUCH_MAX_DELAY_US);
+
+ for (i = 0; i < 5; i++) {
+ int ret = mvf_adc_register_and_convert(adc, adc_channel);
+ if (ret < 0)
+ return -EINVAL;
+
+ value += ret;
+ }
+
+ value /= 5;
+
+ gpio_set_value(plate_p, 1);
+ gpio_set_value(plate_m, 0);
+
+ return value;
+}
+
+/*
+ * Enable touch detection using falling edge detection on XM
+ */
+static void adc_ts_enable_touch_detection(struct adc_touch_device *adc_ts)
+{
+ struct colibri_ts_platform_data *pdata = adc_ts->pdev->dev.platform_data;
+
+ /* Enable plate YM (needs to be strong GND, high active) */
+ gpio_set_value(pdata->gpio_ym, 1);
+
+ /* Let the platform mux to GPIO in order to enable Pull-Up on GPIO */
+ if (pdata->mux_pen_interrupt)
+ pdata->mux_pen_interrupt(adc_ts->pdev);
+}
+
+/*
+ * ADC touch screen sampling worker function
+ */
+static void adc_ts_work(struct work_struct *ts_work)
+{
+ struct adc_touch_device *adc_ts = container_of(ts_work,
+ struct adc_touch_device, ts_work);
+ struct device *dev = &adc_ts->pdev->dev;
+ struct colibri_ts_platform_data *pdata = adc_ts->pdev->dev.platform_data;
+ int val_x, val_y, val_z1, val_z2, val_p = 0;
+
+ struct adc_feature feature = {
+ .channel = ADC0,
+ .clk_sel = ADCIOC_BUSCLK_SET,
+ .clk_div_num = 1,
+ .res_mode = 12,
+ .sam_time = 6,
+ .lp_con = ADCIOC_LPOFF_SET,
+ .hs_oper = ADCIOC_HSOFF_SET,
+ .vol_ref = ADCIOC_VR_VREF_SET,
+ .tri_sel = ADCIOC_SOFTTS_SET,
+ .ha_sel = ADCIOC_HA_SET,
+ .ha_sam = 8,
+ .do_ena = ADCIOC_DOEOFF_SET,
+ .ac_ena = ADCIOC_ADACKENOFF_SET,
+ .dma_ena = ADCIDC_DMAOFF_SET,
+ .cc_ena = ADCIOC_CCEOFF_SET,
+ .compare_func_ena = ADCIOC_ACFEOFF_SET,
+ .range_ena = ADCIOC_ACRENOFF_SET,
+ .greater_ena = ADCIOC_ACFGTOFF_SET,
+ .result0 = 0,
+ .result1 = 0,
+ };
+
+ mvf_adc_initiate(0);
+ mvf_adc_set(0, &feature);
+
+ mvf_adc_initiate(1);
+ mvf_adc_set(1, &feature);
+
+ while (!adc_ts->stop_touchscreen)
+ {
+ /* X-Direction */
+ val_x = adc_ts_measure(pdata->gpio_xp, pdata->gpio_xm, 1, 0);
+ if (val_x < 0)
+ continue;
+
+ /* Y-Direction */
+ val_y = adc_ts_measure(pdata->gpio_yp, pdata->gpio_ym, 0, 0);
+ if (val_y < 0)
+ continue;
+
+ /* Touch pressure
+ * Measure on XP/YM
+ */
+ val_z1 = adc_ts_measure(pdata->gpio_yp, pdata->gpio_xm, 0, 1);
+ if (val_z1 < 0)
+ continue;
+ val_z2 = adc_ts_measure(pdata->gpio_yp, pdata->gpio_xm, 1, 2);
+ if (val_z2 < 0)
+ continue;
+
+ /* According to datasheet of our touchscreen,
+ * resistance on X axis is 400~1200..
+ */
+ /* Validate signal (avoid calculation using noise) */
+ if (val_z1 > 64 && val_x > 64) {
+ /* Calculate resistance between the plates
+ * lower resistance means higher pressure */
+ int r_x = (1000 * val_x) / MVF_ADC_MAX;
+ val_p = (r_x * val_z2) / val_z1 - r_x;
+ } else {
+ val_p = 2000;
+ }
+
+ dev_dbg(dev, "Measured values: x: %d, y: %d, z1: %d, z2: %d, "
+ "p: %d\n", val_x, val_y, val_z1, val_z2, val_p);
+
+ /*
+ * If touch pressure is too low, stop measuring and reenable
+ * touch detection
+ */
+ if (val_p > 1800)
+ break;
+
+ /* Report touch position and sleep for next measurement */
+ input_report_abs(adc_ts->ts_input, ABS_X, MVF_ADC_MAX - val_x);
+ input_report_abs(adc_ts->ts_input, ABS_Y, MVF_ADC_MAX - val_y);
+ input_report_abs(adc_ts->ts_input, ABS_PRESSURE, 2000 - val_p);
+ input_report_key(adc_ts->ts_input, BTN_TOUCH, 1);
+ input_sync(adc_ts->ts_input);
+
+ msleep(10);
+ }
+
+ /* Report no more touch, reenable touch detection */
+ input_report_abs(adc_ts->ts_input, ABS_PRESSURE, 0);
+ input_report_key(adc_ts->ts_input, BTN_TOUCH, 0);
+ input_sync(adc_ts->ts_input);
+
+ /* Wait the pull-up to be stable on high */
+ adc_ts_enable_touch_detection(adc_ts);
+ msleep(10);
+
+ /* Reenable IRQ to detect touch */
+ enable_irq(adc_ts->pen_irq);
+
+ dev_dbg(dev, "Reenabled touch detection interrupt\n");
+}
+
+static irqreturn_t adc_tc_touched(int irq, void *dev_id)
+{
+ struct adc_touch_device *adc_ts = (struct adc_touch_device *)dev_id;
+ struct device *dev = &adc_ts->pdev->dev;
+ struct colibri_ts_platform_data *pdata = adc_ts->pdev->dev.platform_data;
+
+ dev_dbg(dev, "Touch detected, start worker thread\n");
+
+ /* Stop IRQ */
+ disable_irq_nosync(irq);
+
+ /* Disable the touch detection plates */
+ gpio_set_value(pdata->gpio_ym, 0);
+
+ /* Let the platform mux to GPIO in order to enable Pull-Up on GPIO */
+ if (pdata->mux_adc)
+ pdata->mux_adc(adc_ts->pdev);
+
+ /* Start worker thread */
+ queue_work(adc_ts->ts_workqueue, &adc_ts->ts_work);
+
+ return IRQ_HANDLED;
+}
+
+static int adc_ts_open(struct input_dev *dev_input)
+{
+ int ret;
+ struct adc_touch_device *adc_ts = input_get_drvdata(dev_input);
+ struct device *dev = &adc_ts->pdev->dev;
+ struct colibri_ts_platform_data *pdata = adc_ts->pdev->dev.platform_data;
+
+ dev_dbg(dev, "Input device %s opened, starting touch detection\n",
+ dev_input->name);
+
+ adc_ts->stop_touchscreen = false;
+
+ /* Initialize GPIOs, leave FETs closed by default */
+ gpio_direction_output(pdata->gpio_xp, 1); /* Low active */
+ gpio_direction_output(pdata->gpio_xm, 0); /* High active */
+ gpio_direction_output(pdata->gpio_yp, 1); /* Low active */
+ gpio_direction_output(pdata->gpio_ym, 0); /* High active */
+
+ /* Mux detection before request IRQ, wait for pull-up to settle */
+ adc_ts_enable_touch_detection(adc_ts);
+ msleep(10);
+
+ adc_ts->pen_irq = gpio_to_irq(pdata->gpio_pen_detect);
+ if (adc_ts->pen_irq < 0) {
+ dev_err(dev, "Unable to get IRQ for GPIO %d\n",
+ pdata->gpio_pen_detect);
+ return adc_ts->pen_irq;
+ }
+
+ ret = request_irq(adc_ts->pen_irq, adc_tc_touched, IRQF_TRIGGER_FALLING,
+ "touch detected", adc_ts);
+ if (ret < 0) {
+ dev_err(dev, "Unable to request IRQ %d\n", adc_ts->pen_irq);
+ return ret;
+ }
+
+ return 0;
+}
+
+static void adc_ts_close(struct input_dev *dev_input)
+{
+ struct adc_touch_device *adc_ts = input_get_drvdata(dev_input);
+ struct device *dev = &adc_ts->pdev->dev;
+
+ free_irq(adc_ts->pen_irq, adc_ts);
+
+ adc_ts->stop_touchscreen = true;
+
+ /* Wait until touchscreen thread finishes any possible remnants. */
+ cancel_work_sync(&adc_ts->ts_work);
+
+ dev_dbg(dev, "Input device %s closed, disable touch detection\n",
+ dev_input->name);
+}
+
+
+static int __devinit adc_ts_probe(struct platform_device *pdev)
+{
+ int ret = 0;
+ struct device *dev = &pdev->dev;
+ struct input_dev *input;
+ struct adc_touch_device *adc_ts;
+ struct colibri_ts_platform_data *pdata = pdev->dev.platform_data;
+
+ adc_ts = kzalloc(sizeof(struct adc_touch_device), GFP_KERNEL);
+ if (!adc_ts) {
+ dev_err(dev, "Failed to allocate TS device!\n");
+ return -ENOMEM;
+ }
+
+ adc_ts->pdev = pdev;
+
+ input = input_allocate_device();
+ if (!input) {
+ dev_err(dev, "Failed to allocate TS input device!\n");
+ ret = -ENOMEM;
+ goto err_input_allocate;
+ }
+
+ input->name = DRIVER_NAME;
+ input->id.bustype = BUS_HOST;
+ input->dev.parent = dev;
+ input->open = adc_ts_open;
+ input->close = adc_ts_close;
+
+ __set_bit(EV_ABS, input->evbit);
+ __set_bit(EV_KEY, input->evbit);
+ __set_bit(BTN_TOUCH, input->keybit);
+ input_set_abs_params(input, ABS_X, 0, MVF_ADC_MAX, 0, 0);
+ input_set_abs_params(input, ABS_Y, 0, MVF_ADC_MAX, 0, 0);
+ input_set_abs_params(input, ABS_PRESSURE, 0, MVF_ADC_MAX, 0, 0);
+
+ adc_ts->ts_input = input;
+ input_set_drvdata(input, adc_ts);
+ ret = input_register_device(input);
+ if (ret) {
+ dev_err(dev, "failed to register input device\n");
+ goto err;
+ }
+
+ /* Create workqueue for ADC sampling and calculation */
+ INIT_WORK(&adc_ts->ts_work, adc_ts_work);
+ adc_ts->ts_workqueue = create_singlethread_workqueue("mvf-adc-touch");
+
+ if (!adc_ts->ts_workqueue) {
+ dev_err(dev, "failed to create workqueue");
+ goto err;
+ }
+
+ /* Request GPIOs for FETs and touch detection */
+ ret = gpio_request(pdata->gpio_xp, "Touchscreen XP");
+ if (ret)
+ goto err;
+ ret = gpio_request(pdata->gpio_xm, "Touchscreen XM");
+ if (ret)
+ goto err;
+ ret = gpio_request(pdata->gpio_yp, "Touchscreen YP");
+ if (ret)
+ goto err;
+ ret = gpio_request(pdata->gpio_ym, "Touchscreen YM");
+ if (ret)
+ goto err;
+ ret = gpio_request(pdata->gpio_pen_detect, "Pen/Touch detect");
+ if (ret)
+ goto err;
+ ret = gpio_request(pdata->gpio_pen_detect_pullup,
+ "Pen/Touch detect pull-up");
+ if (ret)
+ goto err;
+
+ dev_info(dev, "attached driver successfully\n");
+
+ return 0;
+err:
+ input_free_device(touch->ts_input);
+
+err_input_allocate:
+ kfree(adc_ts);
+
+ return ret;
+}
+
+static int __devexit adc_ts_remove(struct platform_device *pdev)
+{
+ struct adc_touch_device *adc_ts = platform_get_drvdata(pdev);
+
+ input_unregister_device(adc_ts->ts_input);
+
+ destroy_workqueue(adc_ts->ts_workqueue);
+ kfree(adc_ts->ts_input);
+ kfree(adc_ts);
+
+ return 0;
+}
+
+static struct platform_driver adc_ts_driver = {
+ .driver = {
+ .name = DRIVER_NAME,
+ .owner = THIS_MODULE,
+ },
+ .probe = adc_ts_probe,
+ .remove = __devexit_p(adc_ts_remove),
+};
+
+static int __init adc_ts_init(void)
+{
+ int ret;
+
+ ret = platform_driver_register(&adc_ts_driver);
+ if (ret)
+ printk(KERN_ERR "%s: failed to add adc touchscreen driver\n",
+ __func__);
+
+ return ret;
+}
+
+static void __exit adc_ts_exit(void)
+{
+ platform_driver_unregister(&adc_ts_driver);
+}
+module_init(adc_ts_init);
+module_exit(adc_ts_exit);
+
+MODULE_AUTHOR("Stefan Agner");
+MODULE_DESCRIPTION("Colibri VF50 Touchscreen driver");
+MODULE_LICENSE("GPL v2");
+MODULE_VERSION(DRV_VERSION);
diff --git a/drivers/input/touchscreen/fusion_F0710A.c b/drivers/input/touchscreen/fusion_F0710A.c
new file mode 100644
index 000000000000..05bbdf5e8c5b
--- /dev/null
+++ b/drivers/input/touchscreen/fusion_F0710A.c
@@ -0,0 +1,502 @@
+/*
+ * "fusion_F0710A" touchscreen driver
+ *
+ * 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/module.h>
+#include <linux/init.h>
+#include <linux/input.h>
+#include <linux/interrupt.h>
+#include <linux/platform_device.h>
+#include <linux/workqueue.h>
+#include <linux/i2c.h>
+#include <linux/delay.h>
+#include <asm/irq.h>
+#include <linux/gpio.h>
+#include <linux/input/fusion_F0710A.h>
+
+#include "fusion_F0710A.h"
+
+#define DRV_NAME "fusion_F0710A"
+
+
+static struct fusion_F0710A_data fusion_F0710A;
+
+static unsigned short normal_i2c[] = { fusion_F0710A_I2C_SLAVE_ADDR, I2C_CLIENT_END };
+
+//I2C_CLIENT_INSMOD;
+
+static int fusion_F0710A_write_u8(u8 addr, u8 data)
+{
+ return i2c_smbus_write_byte_data(fusion_F0710A.client, addr, data);
+}
+
+static int fusion_F0710A_read_u8(u8 addr)
+{
+ return i2c_smbus_read_byte_data(fusion_F0710A.client, addr);
+}
+
+static int fusion_F0710A_read_block(u8 addr, u8 len, u8 *data)
+{
+#if 0
+ /* When i2c_smbus_read_i2c_block_data() takes a block length parameter, we can do
+ * this. lm-sensors lists hints this has been fixed, but I can't tell whether it
+ * was or will be merged upstream. */
+
+ return i2c_smbus_read_i2c_block_data(&fusion_F0710A.client, addr, data);
+#else
+ u8 msgbuf0[1] = { addr };
+ u16 slave = fusion_F0710A.client->addr;
+ u16 flags = fusion_F0710A.client->flags;
+ struct i2c_msg msg[2] = { { slave, flags, 1, msgbuf0 },
+ { slave, flags | I2C_M_RD, len, data }
+ };
+
+ return i2c_transfer(fusion_F0710A.client->adapter, msg, ARRAY_SIZE(msg));
+#endif
+}
+
+
+static int fusion_F0710A_register_input(void)
+{
+ int ret;
+ struct input_dev *dev;
+
+ dev = fusion_F0710A.input = input_allocate_device();
+ if (dev == NULL)
+ return -ENOMEM;
+
+ dev->name = "fusion_F0710A";
+
+ set_bit(EV_KEY, dev->evbit);
+ set_bit(EV_ABS, dev->evbit);
+
+ input_set_abs_params(dev, ABS_MT_POSITION_X, 0, fusion_F0710A.info.xres-1, 0, 0);
+ input_set_abs_params(dev, ABS_MT_POSITION_Y, 0, fusion_F0710A.info.yres-1, 0, 0);
+ input_set_abs_params(dev, ABS_MT_TOUCH_MAJOR, 0, 255, 0, 0);
+ input_set_abs_params(dev, ABS_MT_WIDTH_MAJOR, 0, 15, 0, 0);
+
+ input_set_abs_params(dev, ABS_X, 0, fusion_F0710A.info.xres-1, 0, 0);
+ input_set_abs_params(dev, ABS_Y, 0, fusion_F0710A.info.yres-1, 0, 0);
+ input_set_abs_params(dev, ABS_PRESSURE, 0, 255, 0, 0);
+
+ ret = input_register_device(dev);
+ if (ret < 0)
+ goto bail1;
+
+ return 0;
+
+bail1:
+ input_free_device(dev);
+ return ret;
+}
+
+#define WC_RETRY_COUNT 3
+static int fusion_F0710A_write_complete(void)
+{
+ int ret, i;
+
+ for(i=0; i<WC_RETRY_COUNT; i++)
+ {
+ ret = fusion_F0710A_write_u8(fusion_F0710A_SCAN_COMPLETE, 0);
+ if(ret == 0)
+ break;
+ else
+ dev_err(&fusion_F0710A.client->dev, "Write complete failed(%d): %d\n", i, ret);
+ }
+
+ return ret;
+}
+
+#define DATA_START fusion_F0710A_DATA_INFO
+#define DATA_END fusion_F0710A_SEC_TIDTS
+#define DATA_LEN (DATA_END - DATA_START + 1)
+#define DATA_OFF(x) ((x) - DATA_START)
+
+static int fusion_F0710A_read_sensor(void)
+{
+ int ret;
+ u8 data[DATA_LEN];
+
+#define DATA(x) (data[DATA_OFF(x)])
+ /* To ensure data coherency, read the sensor with a single transaction. */
+ ret = fusion_F0710A_read_block(DATA_START, DATA_LEN, data);
+ if (ret < 0) {
+ dev_err(&fusion_F0710A.client->dev,
+ "Read block failed: %d\n", ret);
+
+ return ret;
+ }
+
+ fusion_F0710A.f_num = DATA(fusion_F0710A_DATA_INFO)&0x03;
+
+ fusion_F0710A.y1 = DATA(fusion_F0710A_POS_X1_HI) << 8;
+ fusion_F0710A.y1 |= DATA(fusion_F0710A_POS_X1_LO);
+ fusion_F0710A.x1 = DATA(fusion_F0710A_POS_Y1_HI) << 8;
+ fusion_F0710A.x1 |= DATA(fusion_F0710A_POS_Y1_LO);
+ fusion_F0710A.z1 = DATA(fusion_F0710A_FIR_PRESS);
+ fusion_F0710A.tip1 = DATA(fusion_F0710A_FIR_TIDTS)&0x0f;
+ fusion_F0710A.tid1 = (DATA(fusion_F0710A_FIR_TIDTS)&0xf0)>>4;
+
+
+ fusion_F0710A.y2 = DATA(fusion_F0710A_POS_X2_HI) << 8;
+ fusion_F0710A.y2 |= DATA(fusion_F0710A_POS_X2_LO);
+ fusion_F0710A.x2 = DATA(fusion_F0710A_POS_Y2_HI) << 8;
+ fusion_F0710A.x2 |= DATA(fusion_F0710A_POS_Y2_LO);
+ fusion_F0710A.z2 = DATA(fusion_F0710A_SEC_PRESS);
+ fusion_F0710A.tip2 = DATA(fusion_F0710A_SEC_TIDTS)&0x0f;
+ fusion_F0710A.tid2 =(DATA(fusion_F0710A_SEC_TIDTS)&0xf0)>>4;
+#undef DATA
+
+ return 0;
+}
+
+#define val_cut_max(x, max, reverse) \
+do \
+{ \
+ if(x > max) \
+ x = max; \
+ if(reverse) \
+ x = (max) - (x); \
+} \
+while(0)
+
+static void fusion_F0710A_wq(struct work_struct *work)
+{
+ struct input_dev *dev = fusion_F0710A.input;
+ int save_points = 0;
+ int x1 = 0, y1 = 0, z1 = 0, x2 = 0, y2 = 0, z2 = 0;
+
+ if (fusion_F0710A_read_sensor() < 0)
+ goto restore_irq;
+
+#ifdef DEBUG
+ printk(KERN_DEBUG "tip1, tid1, x1, y1, z1 (%x,%x,%d,%d,%d); tip2, tid2, x2, y2, z2 (%x,%x,%d,%d,%d)\n",
+ fusion_F0710A.tip1, fusion_F0710A.tid1, fusion_F0710A.x1, fusion_F0710A.y1, fusion_F0710A.z1,
+ fusion_F0710A.tip2, fusion_F0710A.tid2, fusion_F0710A.x2, fusion_F0710A.y2, fusion_F0710A.z2);
+#endif /* DEBUG */
+
+ val_cut_max(fusion_F0710A.x1, fusion_F0710A.info.xres-1, fusion_F0710A.info.xy_reverse);
+ val_cut_max(fusion_F0710A.y1, fusion_F0710A.info.yres-1, fusion_F0710A.info.xy_reverse);
+ val_cut_max(fusion_F0710A.x2, fusion_F0710A.info.xres-1, fusion_F0710A.info.xy_reverse);
+ val_cut_max(fusion_F0710A.y2, fusion_F0710A.info.yres-1, fusion_F0710A.info.xy_reverse);
+
+ if(fusion_F0710A.tip1 == 1)
+ {
+ if(fusion_F0710A.tid1 == 1)
+ {
+ /* first point */
+ x1 = fusion_F0710A.x1;
+ y1 = fusion_F0710A.y1;
+ z1 = fusion_F0710A.z1;
+ save_points |= fusion_F0710A_SAVE_PT1;
+ }
+ else if(fusion_F0710A.tid1 == 2)
+ {
+ /* second point ABS_DISTANCE second point pressure, BTN_2 second point touch */
+ x2 = fusion_F0710A.x1;
+ y2 = fusion_F0710A.y1;
+ z2 = fusion_F0710A.z1;
+ save_points |= fusion_F0710A_SAVE_PT2;
+ }
+ }
+
+ if(fusion_F0710A.tip2 == 1)
+ {
+ if(fusion_F0710A.tid2 == 2)
+ {
+ /* second point ABS_DISTANCE second point pressure, BTN_2 second point touch */
+ x2 = fusion_F0710A.x2;
+ y2 = fusion_F0710A.y2;
+ z2 = fusion_F0710A.z2;
+ save_points |= fusion_F0710A_SAVE_PT2;
+ }
+ else if(fusion_F0710A.tid2 == 1)/* maybe this will never happen */
+ {
+ /* first point */
+ x1 = fusion_F0710A.x2;
+ y1 = fusion_F0710A.y2;
+ z1 = fusion_F0710A.z2;
+ save_points |= fusion_F0710A_SAVE_PT1;
+ }
+ }
+
+ input_report_abs(dev, ABS_MT_TOUCH_MAJOR, z1);
+ input_report_abs(dev, ABS_MT_WIDTH_MAJOR, 1);
+ input_report_abs(dev, ABS_MT_POSITION_X, x1);
+ input_report_abs(dev, ABS_MT_POSITION_Y, y1);
+ input_mt_sync(dev);
+ input_report_abs(dev, ABS_MT_TOUCH_MAJOR, z2);
+ input_report_abs(dev, ABS_MT_WIDTH_MAJOR, 2);
+ input_report_abs(dev, ABS_MT_POSITION_X, x2);
+ input_report_abs(dev, ABS_MT_POSITION_Y, y2);
+ input_mt_sync(dev);
+
+ input_report_abs(dev, ABS_X, x1);
+ input_report_abs(dev, ABS_Y, y1);
+ input_report_abs(dev, ABS_PRESSURE, z1);
+ input_report_key(dev, BTN_TOUCH, fusion_F0710A.tip1);
+
+ input_sync(dev);
+
+restore_irq:
+ enable_irq(fusion_F0710A.client->irq);
+
+ /* Clear fusion_F0710A interrupt */
+ fusion_F0710A_write_complete();
+}
+static DECLARE_WORK(fusion_F0710A_work, fusion_F0710A_wq);
+
+static irqreturn_t fusion_F0710A_interrupt(int irq, void *dev_id)
+{
+ disable_irq_nosync(fusion_F0710A.client->irq);
+
+ queue_work(fusion_F0710A.workq, &fusion_F0710A_work);
+
+ return IRQ_HANDLED;
+}
+
+const static u8* g_ver_product[4] = {
+ "10Z8", "70Z7", "43Z6", ""
+};
+
+static int fusion_F0710A_probe(struct i2c_client *i2c, const struct i2c_device_id *id)
+{
+ struct fusion_f0710a_init_data *pdata = i2c->dev.platform_data;
+ int ret;
+ u8 ver_product, ver_id;
+ u32 version;
+
+ if (pdata == NULL)
+ {
+ dev_err(&i2c->dev, "No platform data for Fusion driver\n");
+ return -ENODEV;
+ }
+
+ /* Request pinmuxing, if necessary */
+ if (pdata->pinmux_fusion_pins != NULL)
+ {
+ ret = pdata->pinmux_fusion_pins();
+ if (ret < 0) {
+ dev_err(&i2c->dev, "muxing GPIOs failed\n");
+ return -ENODEV;
+ }
+ }
+
+ if ((gpio_request(pdata->gpio_int, "SO-DIMM 28 (Iris X16-38 Pen)") == 0) &&
+ (gpio_direction_input(pdata->gpio_int) == 0)) {
+ gpio_export(pdata->gpio_int, 0);
+ } else {
+ dev_warn(&i2c->dev, "Could not obtain GPIO for Fusion pen down\n");
+ return -ENODEV;
+ }
+
+ if ((gpio_request(pdata->gpio_reset, "SO-DIMM 30 (Iris X16-39 RST)") == 0) &&
+ (gpio_direction_output(pdata->gpio_reset, 1) == 0)) {
+
+ /* Generate a 0 => 1 edge explicitly, and wait for startup... */
+ gpio_set_value(pdata->gpio_reset, 0);
+ msleep(10);
+ gpio_set_value(pdata->gpio_reset, 1);
+ /* Wait for startup (up to 125ms according to datasheet) */
+ msleep(125);
+
+ gpio_export(pdata->gpio_reset, 0);
+ } else {
+ dev_warn(&i2c->dev, "Could not obtain GPIO for Fusion reset\n");
+ ret = -ENODEV;
+ goto bail0;
+ }
+
+ /* Use Pen Down GPIO as sampling interrupt */
+ i2c->irq = gpio_to_irq(pdata->gpio_int);
+
+ if(!i2c->irq)
+ {
+ dev_err(&i2c->dev, "fusion_F0710A irq < 0 \n");
+ ret = -ENOMEM;
+ goto bail1;
+ }
+
+ /* Attach the I2C client */
+ fusion_F0710A.client = i2c;
+ i2c_set_clientdata(i2c, &fusion_F0710A);
+
+ dev_info(&i2c->dev, "Touchscreen registered with bus id (%d) with slave address 0x%x\n",
+ i2c_adapter_id(fusion_F0710A.client->adapter), fusion_F0710A.client->addr);
+
+ /* Read out a lot of registers */
+ ret = fusion_F0710A_read_u8(fusion_F0710A_VIESION_INFO_LO);
+ if (ret < 0) {
+ dev_err(&i2c->dev, "query failed: %d\n", ret);
+ goto bail1;
+ }
+ ver_product = (((u8)ret) & 0xc0) >> 6;
+ version = (10 + ((((u32)ret)&0x30) >> 4)) * 100000;
+ version += (((u32)ret)&0xf) * 1000;
+ /* Read out a lot of registers */
+ ret = fusion_F0710A_read_u8(fusion_F0710A_VIESION_INFO);
+ if (ret < 0) {
+ dev_err(&i2c->dev, "query failed: %d\n", ret);
+ goto bail1;
+ }
+ ver_id = ((u8)(ret) & 0x6) >> 1;
+ version += ((((u32)ret) & 0xf8) >> 3) * 10;
+ version += (((u32)ret) & 0x1) + 1; /* 0 is build 1, 1 is build 2 */
+ dev_info(&i2c->dev, "version product %s(%d)\n", g_ver_product[ver_product] ,ver_product);
+ dev_info(&i2c->dev, "version id %s(%d)\n", ver_id ? "1.4" : "1.0", ver_id);
+ dev_info(&i2c->dev, "version series (%d)\n", version);
+
+ switch(ver_product)
+ {
+ case fusion_F0710A_VIESION_07: /* 7 inch */
+ fusion_F0710A.info.xres = fusion_F0710A07_XMAX;
+ fusion_F0710A.info.yres = fusion_F0710A07_YMAX;
+ fusion_F0710A.info.xy_reverse = fusion_F0710A07_REV;
+ break;
+ case fusion_F0710A_VIESION_43: /* 4.3 inch */
+ fusion_F0710A.info.xres = fusion_F0710A43_XMAX;
+ fusion_F0710A.info.yres = fusion_F0710A43_YMAX;
+ fusion_F0710A.info.xy_reverse = fusion_F0710A43_REV;
+ break;
+ default: /* fusion_F0710A_VIESION_10 10 inch */
+ fusion_F0710A.info.xres = fusion_F0710A10_XMAX;
+ fusion_F0710A.info.yres = fusion_F0710A10_YMAX;
+ fusion_F0710A.info.xy_reverse = fusion_F0710A10_REV;
+ break;
+ }
+
+ /* Register the input device. */
+ ret = fusion_F0710A_register_input();
+ if (ret < 0) {
+ dev_err(&i2c->dev, "can't register input: %d\n", ret);
+ goto bail1;
+ }
+
+ /* Create a worker thread */
+ fusion_F0710A.workq = create_singlethread_workqueue(DRV_NAME);
+ if (fusion_F0710A.workq == NULL) {
+ dev_err(&i2c->dev, "can't create work queue\n");
+ ret = -ENOMEM;
+ goto bail2;
+ }
+
+
+ /* Register for the interrupt and enable it. Our handler will
+ * start getting invoked after this call. */
+ ret = request_irq(i2c->irq, fusion_F0710A_interrupt, IRQF_TRIGGER_RISING,
+ i2c->name, &fusion_F0710A);
+ if (ret < 0) {
+ dev_err(&i2c->dev, "can't get irq %d: %d\n", i2c->irq, ret);
+ goto bail3;
+ }
+ /* clear the irq first */
+ ret = fusion_F0710A_write_u8(fusion_F0710A_SCAN_COMPLETE, 0);
+ if (ret < 0) {
+ dev_err(&i2c->dev, "Clear irq failed: %d\n", ret);
+ goto bail4;
+ }
+
+ return 0;
+
+bail4:
+ free_irq(i2c->irq, &fusion_F0710A);
+
+bail3:
+ destroy_workqueue(fusion_F0710A.workq);
+ fusion_F0710A.workq = NULL;
+
+bail2:
+ input_unregister_device(fusion_F0710A.input);
+bail1:
+ gpio_free(pdata->gpio_reset);
+bail0:
+ gpio_free(pdata->gpio_int);
+
+ return ret;
+}
+
+#ifdef CONFIG_PM_SLEEP
+static int fusion_F0710A_suspend(struct device *dev)
+{
+ struct i2c_client *i2c = to_i2c_client(dev);
+ disable_irq(i2c->irq);
+ flush_workqueue(fusion_F0710A.workq);
+
+ return 0;
+}
+
+static int fusion_F0710A_resume(struct device *dev)
+{
+ struct i2c_client *i2c = to_i2c_client(dev);
+ enable_irq(i2c->irq);
+
+ return 0;
+}
+#endif
+
+static int fusion_F0710A_remove(struct i2c_client *i2c)
+{
+ struct fusion_f0710a_init_data *pdata = i2c->dev.platform_data;
+
+ gpio_free(pdata->gpio_int);
+ gpio_free(pdata->gpio_reset);
+ destroy_workqueue(fusion_F0710A.workq);
+ free_irq(i2c->irq, &fusion_F0710A);
+ input_unregister_device(fusion_F0710A.input);
+ i2c_set_clientdata(i2c, NULL);
+
+ dev_info(&i2c->dev, "driver removed\n");
+
+ return 0;
+}
+
+static struct i2c_device_id fusion_F0710A_id[] = {
+ {"fusion_F0710A", 0},
+ {},
+};
+
+static const struct dev_pm_ops fusion_F0710A_pm_ops = {
+ SET_SYSTEM_SLEEP_PM_OPS(fusion_F0710A_suspend, fusion_F0710A_resume)
+};
+
+static struct i2c_driver fusion_F0710A_i2c_drv = {
+ .driver = {
+ .owner = THIS_MODULE,
+ .name = DRV_NAME,
+ .pm = &fusion_F0710A_pm_ops,
+ },
+ .probe = fusion_F0710A_probe,
+ .remove = fusion_F0710A_remove,
+ .id_table = fusion_F0710A_id,
+ .address_list = normal_i2c,
+};
+
+static int __init fusion_F0710A_init( void )
+{
+ int ret;
+
+ memset(&fusion_F0710A, 0, sizeof(fusion_F0710A));
+
+ /* Probe for fusion_F0710A on I2C. */
+ ret = i2c_add_driver(&fusion_F0710A_i2c_drv);
+ if (ret < 0) {
+ printk(KERN_WARNING DRV_NAME " can't add i2c driver: %d\n", ret);
+ }
+
+ return ret;
+}
+
+static void __exit fusion_F0710A_exit( void )
+{
+ i2c_del_driver(&fusion_F0710A_i2c_drv);
+}
+module_init(fusion_F0710A_init);
+module_exit(fusion_F0710A_exit);
+
+MODULE_DESCRIPTION("fusion_F0710A Touchscreen Driver");
+MODULE_LICENSE("GPL");
+
diff --git a/drivers/input/touchscreen/fusion_F0710A.h b/drivers/input/touchscreen/fusion_F0710A.h
new file mode 100644
index 000000000000..85f8210345a9
--- /dev/null
+++ b/drivers/input/touchscreen/fusion_F0710A.h
@@ -0,0 +1,87 @@
+/*
+ * "fusion_F0710A" touchscreen driver
+ *
+ * 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.
+ */
+
+/* I2C slave address */
+#define fusion_F0710A_I2C_SLAVE_ADDR 0x10
+
+/* I2C registers */
+#define fusion_F0710A_DATA_INFO 0x00
+
+/* First Point*/
+#define fusion_F0710A_POS_X1_HI 0x01 /* 16-bit register, MSB */
+#define fusion_F0710A_POS_X1_LO 0x02 /* 16-bit register, LSB */
+#define fusion_F0710A_POS_Y1_HI 0x03 /* 16-bit register, MSB */
+#define fusion_F0710A_POS_Y1_LO 0x04 /* 16-bit register, LSB */
+#define fusion_F0710A_FIR_PRESS 0X05
+#define fusion_F0710A_FIR_TIDTS 0X06
+
+/* Second Point */
+#define fusion_F0710A_POS_X2_HI 0x07 /* 16-bit register, MSB */
+#define fusion_F0710A_POS_X2_LO 0x08 /* 16-bit register, LSB */
+#define fusion_F0710A_POS_Y2_HI 0x09 /* 16-bit register, MSB */
+#define fusion_F0710A_POS_Y2_LO 0x0A /* 16-bit register, LSB */
+#define fusion_F0710A_SEC_PRESS 0x0B
+#define fusion_F0710A_SEC_TIDTS 0x0C
+
+#define fusion_F0710A_VIESION_INFO_LO 0X0E
+#define fusion_F0710A_VIESION_INFO 0X0F
+
+#define fusion_F0710A_RESET 0x10
+#define fusion_F0710A_SCAN_COMPLETE 0x11
+
+
+#define fusion_F0710A_VIESION_10 0
+#define fusion_F0710A_VIESION_07 1
+#define fusion_F0710A_VIESION_43 2
+
+/* fusion_F0710A 10 inch panel */
+#define fusion_F0710A10_XMAX 2275
+#define fusion_F0710A10_YMAX 1275
+#define fusion_F0710A10_REV 1
+
+/* fusion_F0710A 7 inch panel */
+#define fusion_F0710A07_XMAX 1500
+#define fusion_F0710A07_YMAX 900
+#define fusion_F0710A07_REV 0
+
+/* fusion_F0710A 4.3 inch panel */
+#define fusion_F0710A43_XMAX 900
+#define fusion_F0710A43_YMAX 500
+#define fusion_F0710A43_REV 0
+
+#define fusion_F0710A_SAVE_PT1 0x1
+#define fusion_F0710A_SAVE_PT2 0x2
+
+
+
+/* fusion_F0710A touch screen information */
+struct fusion_F0710A_info {
+ int xres; /* x resolution */
+ int yres; /* y resolution */
+ int xy_reverse; /* if need reverse in the x,y value x=xres-1-x, y=yres-1-y*/
+};
+
+struct fusion_F0710A_data {
+ struct fusion_F0710A_info info;
+ struct i2c_client *client;
+ struct workqueue_struct *workq;
+ struct input_dev *input;
+ u16 x1;
+ u16 y1;
+ u8 z1;
+ u8 tip1;
+ u8 tid1;
+ u16 x2;
+ u16 y2;
+ u8 z2;
+ u8 tip2;
+ u8 tid2;
+ u8 f_num;
+ u8 save_points;
+};
+
diff --git a/drivers/misc/mvf_adc.c b/drivers/misc/mvf_adc.c
index 63e0f95804f9..662d76667bdc 100644
--- a/drivers/misc/mvf_adc.c
+++ b/drivers/misc/mvf_adc.c
@@ -1,4 +1,5 @@
/* Copyright 2012 Freescale Semiconductor, Inc.
+ * Copyright 2013 Toradex AG
*
* Freescale Faraday Quad ADC driver
*
@@ -24,13 +25,20 @@
#include <linux/mvf_adc.h>
#include <linux/device.h>
#include <linux/cdev.h>
+#include <linux/hwmon.h>
+#include <linux/hwmon-sysfs.h>
#define DRIVER_NAME "mvf-adc"
-#define DRV_VERSION "1.0"
+#define DRV_VERSION "1.2"
+
+#define MVF_ADC_MAX_DEVICES 4
+#define MVF_ADC_MAX ((1 << 12) - 1)
/*
* wait_event_interruptible(wait_queue_head_t suspendq, int suspend_flag)
*/
+static struct class *adc_class;
+static int mvf_adc_major;
struct adc_client {
struct platform_device *pdev;
@@ -46,27 +54,29 @@ static DECLARE_COMPLETION(adc_tsi);
struct adc_device {
struct platform_device *pdev;
- struct platform_device *owner;
+ struct device *hwmon_dev;
struct clk *clk;
struct adc_client *cur;
void __iomem *regs;
spinlock_t lock;
+ struct device *dev;
+ struct cdev cdev;
+
int irq;
};
+static struct adc_device *adc_devices[MVF_ADC_MAX_DEVICES];
+
struct data {
unsigned int res_value;
bool flag;
};
-struct data data_array[7];
-
-static struct adc_device *adc_dev;
+struct data data_array[32];
#define adc_dbg(_adc, msg...) dev_dbg(&(_adc)->pdev->dev, msg)
-static int res_proc(void);
struct adc_client *adc_register(struct platform_device *pdev,
unsigned char channel);
@@ -95,32 +105,7 @@ static void adc_try(struct adc_device *adc)
}
}
-/* channel and sample */
-int adc_start(struct adc_client *client,
- unsigned int channel, unsigned int nr_samples)
-{
- struct adc_device *adc = adc_dev;
- unsigned long flags;
-
- if (!adc) {
- printk(KERN_ERR "%s: failed to find adc\n", __func__);
- return -EINVAL;
- }
-
-
- spin_lock_irqsave(&adc->lock, flags);
-
- client->channel = channel;
-
- if (!adc->cur)
- adc_try(adc_dev);
-
- spin_unlock_irqrestore(&adc->lock, flags);
-
- return 0;
-}
-
-int adc_initiate(struct adc_device *adc_dev)
+static int adc_initiate(struct adc_device *adc_dev)
{
unsigned long reg, tmp, pin;
struct adc_device *adc = adc_dev;
@@ -176,7 +161,6 @@ static int adc_set(struct adc_device *adc_dev, struct adc_feature *adc_fea)
default:
return -EINVAL;
}
- writel(con, adc->regs+ADC_CFG);
break;
@@ -200,7 +184,6 @@ static int adc_set(struct adc_device *adc_dev, struct adc_feature *adc_fea)
default:
return -EINVAL;
}
- writel(con, adc->regs+ADC_CFG);
break;
@@ -224,7 +207,6 @@ static int adc_set(struct adc_device *adc_dev, struct adc_feature *adc_fea)
default:
return -EINVAL;
}
- writel(con, adc->regs+ADC_CFG);
break;
default:
@@ -249,7 +231,6 @@ static int adc_set(struct adc_device *adc_dev, struct adc_feature *adc_fea)
adc_fea->res_mode);
return -EINVAL;
}
- writel(con, adc->regs+ADC_CFG);
/* Defines the sample time duration */
/* clear 4, 9-8 */
@@ -284,20 +265,17 @@ static int adc_set(struct adc_device *adc_dev, struct adc_feature *adc_fea)
adc_fea->sam_time);
return -EINVAL;
}
- writel(con, adc->regs+ADC_CFG);
/* low power configuration */
/* */
switch (adc_fea->lp_con) {
case ADCIOC_LPOFF_SET:
con &= ~CLEAR_ADLPC_BIT;
- writel(con, adc->regs+ADC_CFG);
break;
case ADCIOC_LPON_SET:
con &= ~CLEAR_ADLPC_BIT;
con |= ADLPC_EN;
- writel(con, adc->regs+ADC_CFG);
break;
default:
return -EINVAL;
@@ -308,34 +286,28 @@ static int adc_set(struct adc_device *adc_dev, struct adc_feature *adc_fea)
case ADCIOC_HSON_SET:
con &= ~CLEAR_ADHSC_BIT;
con |= ADHSC_EN;
- writel(con, adc->regs+ADC_CFG);
break;
case ADCIOC_HSOFF_SET:
con &= ~CLEAR_ADHSC_BIT;
- writel(con, adc->regs+ADC_CFG);
break;
default:
return -EINVAL;
}
-
/* voltage reference*/
switch (adc_fea->vol_ref) {
case ADCIOC_VR_VREF_SET:
con &= ~CLEAR_REFSEL_BIT;
- writel(con, adc->regs+ADC_CFG);
break;
case ADCIOC_VR_VALT_SET:
con &= ~CLEAR_REFSEL_BIT;
con |= REFSEL_VALT;
- writel(con, adc->regs+ADC_CFG);
break;
case ADCIOC_VR_VBG_SET:
con &= ~CLEAR_REFSEL_BIT;
con |= REFSEL_VBG;
- writel(con, adc->regs+ADC_CFG);
break;
default:
return -EINVAL;
@@ -345,13 +317,11 @@ static int adc_set(struct adc_device *adc_dev, struct adc_feature *adc_fea)
switch (adc_fea->tri_sel) {
case ADCIOC_SOFTTS_SET:
con &= ~CLEAR_ADTRG_BIT;
- writel(con, adc->regs+ADC_CFG);
break;
case ADCIOC_HARDTS_SET:
con &= ~CLEAR_ADTRG_BIT;
con |= ADTRG_HARD;
- writel(con, adc->regs+ADC_CFG);
break;
default:
return -EINVAL;
@@ -360,8 +330,8 @@ static int adc_set(struct adc_device *adc_dev, struct adc_feature *adc_fea)
/* hardware average select */
switch (adc_fea->ha_sel) {
case ADCIOC_HA_DIS:
+ con &= ~CLEAR_AVGS_BIT;
res &= ~CLEAR_AVGE_BIT;
- writel(con, adc->regs+ADC_GC);
break;
case ADCIOC_HA_SET:
@@ -383,8 +353,6 @@ static int adc_set(struct adc_device *adc_dev, struct adc_feature *adc_fea)
}
res &= ~CLEAR_AVGE_BIT;
res |= AVGEN;
- writel(con, adc->regs+ADC_CFG);
- writel(res, adc->regs+ADC_GC);
break;
default:
@@ -394,13 +362,11 @@ static int adc_set(struct adc_device *adc_dev, struct adc_feature *adc_fea)
/* data overwrite enable */
switch (adc_fea->do_ena) {
case ADCIOC_DOEON_SET:
- con &= ~CLEAR_OVWREN_BIT;
- writel(con, adc->regs+ADC_CFG);
+ con |= OVWREN;
break;
case ADCIOC_DOEOFF_SET:
- con |= OVWREN;
- writel(con, adc->regs+ADC_CFG);
+ con &= ~CLEAR_OVWREN_BIT;
break;
default:
return -EINVAL;
@@ -410,13 +376,11 @@ static int adc_set(struct adc_device *adc_dev, struct adc_feature *adc_fea)
switch (adc_fea->ac_ena) {
case ADCIOC_ADACKENON_SET:
res &= ~CLEAR_ADACKEN_BIT;
- writel(res, adc->regs+ADC_GC);
+ res |= ADACKEN;
break;
case ADCIOC_ADACKENOFF_SET:
res &= ~CLEAR_ADACKEN_BIT;
- res |= ADACKEN;
- writel(res, adc->regs+ADC_GC);
break;
default:
return -EINVAL;
@@ -426,13 +390,11 @@ static int adc_set(struct adc_device *adc_dev, struct adc_feature *adc_fea)
switch (adc_fea->dma_ena) {
case ADCIDC_DMAON_SET:
res &= ~CLEAR_DMAEN_BIT;
- writel(res, adc->regs+ADC_GC);
+ res |= DMAEN;
break;
case ADCIDC_DMAOFF_SET:
res &= ~CLEAR_DMAEN_BIT;
- res |= DMAEN;
- writel(res, adc->regs+ADC_GC);
break;
default:
return -EINVAL;
@@ -442,13 +404,11 @@ static int adc_set(struct adc_device *adc_dev, struct adc_feature *adc_fea)
switch (adc_fea->cc_ena) {
case ADCIOC_CCEOFF_SET:
res &= ~CLEAR_ADCO_BIT;
- writel(res, adc->regs+ADC_GC);
break;
case ADCIOC_CCEON_SET:
res &= ~CLEAR_ADCO_BIT;
res |= ADCON;
- writel(res, adc->regs+ADC_GC);
break;
default:
return -EINVAL;
@@ -459,12 +419,10 @@ static int adc_set(struct adc_device *adc_dev, struct adc_feature *adc_fea)
case ADCIOC_ACFEON_SET:
res &= ~CLEAR_ACFE_BIT;
res |= ACFE;
- writel(res, adc->regs+ADC_GC);
break;
case ADCIOC_ACFEOFF_SET:
res &= ~CLEAR_ACFE_BIT;
- writel(res, adc->regs+ADC_GC);
break;
default:
return -EINVAL;
@@ -475,12 +433,10 @@ static int adc_set(struct adc_device *adc_dev, struct adc_feature *adc_fea)
case ADCIOC_ACFGTON_SET:
res &= ~CLEAR_ACFGT_BIT;
res |= ACFGT;
- writel(res, adc->regs+ADC_GC);
break;
case ADCIOC_ACFGTOFF_SET:
res &= ~CLEAR_ACFGT_BIT;
- writel(res, adc->regs+ADC_GC);
break;
default:
return -EINVAL;
@@ -491,22 +447,175 @@ static int adc_set(struct adc_device *adc_dev, struct adc_feature *adc_fea)
case ADCIOC_ACRENON_SET:
res &= ~CLEAR_ACREN_BIT;
res |= ACREN;
- writel(res, adc->regs+ADC_GC);
break;
case ADCIOC_ACRENOFF_SET:
res &= ~CLEAR_ACREN_BIT;
- writel(res, adc->regs+ADC_GC);
break;
default: return -ENOTTY;
}
+
+ /* write register once */
+ writel(con, adc->regs+ADC_CFG);
+ writel(res, adc->regs+ADC_GC);
+
+ return 0;
+}
+
+static int adc_convert_wait(struct adc_device *adc_dev, unsigned char channel)
+{
+ INIT_COMPLETION(adc_tsi);
+ adc_try(adc_dev);
+ wait_for_completion(&adc_tsi);
+
+ if (!data_array[channel].flag)
+ return -EINVAL;
+
+ data_array[channel].flag = 0;
+ return data_array[channel].res_value;
+}
+
+/**
+ * mvf_adc_initiate - Initiate a given ADC converter
+ *
+ * @adc: ADC block to initiate
+ */
+int mvf_adc_initiate(unsigned int adc)
+{
+ return adc_initiate(adc_devices[adc]);
+}
+EXPORT_SYMBOL(mvf_adc_initiate);
+
+/**
+ * mvf_adc_set - Configure a given ADC converter
+ *
+ * @adc: ADC block to configure
+ * @adc_fea: Features to enable
+ *
+ * Returns zero on success, error number otherwise
+ */
+int mvf_adc_set(unsigned int adc, struct adc_feature *adc_fea)
+{
+ return adc_set(adc_devices[adc], adc_fea);
+}
+EXPORT_SYMBOL(mvf_adc_set);
+
+/**
+ * mvf_adc_register_and_convert - Register a client and start a convertion
+ *
+ * @adc: ADC block
+ * @channel: Channel to convert
+ *
+ * Returns converted value or error code
+ */
+int mvf_adc_register_and_convert(unsigned int adc, unsigned char channel)
+{
+ struct adc_client *client;
+ int result;
+
+ /* Register client... */
+ client = adc_register(adc_devices[adc]->pdev, channel);
+ if (!client)
+ return -ENOMEM;
+
+ /* Start convertion */
+ result = adc_convert_wait(adc_devices[adc], channel);
+
+ /* Free client */
+ kfree(client);
+
+ return result;
+}
+EXPORT_SYMBOL(mvf_adc_register_and_convert);
+
+/* Temperature sensor (hwmon) */
+
+static ssize_t adc_show_temp(struct device *dev,
+ struct device_attribute *dev_attr, char *buf)
+{
+ struct adc_device *adc_dev = dev_get_drvdata(dev);
+ struct adc_client *client;
+ unsigned char channel = 26;
+ int temperature;
+ int ret;
+
+ struct adc_feature feature = {
+ .channel = ADC26,
+ .clk_sel = ADCIOC_BUSCLK_SET,
+ .clk_div_num = 1,
+ .res_mode = 12,
+ .sam_time = 6,
+ .lp_con = ADCIOC_LPOFF_SET,
+ .hs_oper = ADCIOC_HSOFF_SET,
+ .vol_ref = ADCIOC_VR_VREF_SET,
+ .tri_sel = ADCIOC_SOFTTS_SET,
+ .ha_sel = ADCIOC_HA_SET,
+ .ha_sam = 8,
+ .do_ena = ADCIOC_DOEOFF_SET,
+ .ac_ena = ADCIOC_ADACKENOFF_SET,
+ .dma_ena = ADCIDC_DMAOFF_SET,
+ .cc_ena = ADCIOC_CCEOFF_SET,
+ .compare_func_ena = ADCIOC_ACFEOFF_SET,
+ .range_ena = ADCIOC_ACRENOFF_SET,
+ .greater_ena = ADCIOC_ACFGTOFF_SET,
+ .result0 = 0,
+ .result1 = 0,
+ };
+
+ /* Initialize device */
+ adc_initiate(adc_dev);
+ ret = adc_set(adc_dev, &feature);
+ if (ret)
+ return ret;
+
+ /* Register client... */
+ client = adc_register(adc_dev->pdev, channel);
+ if (!client)
+ return -ENOMEM;
+
+ /* Do the ADC convertion of the temperature channel */
+ temperature = adc_convert_wait(adc_dev, channel);
+
+ /*
+ * Calculate in degree celsius times 1000)
+ * Using sensor slope of 1.84 mV/°C and
+ * V at 25°C of 696mv
+ */
+ temperature = 25000 - (temperature - 864) * 1000000 / 1840;
+
+ /* Free client */
+ kfree(client);
+
+ return sprintf(buf, "%d\n", temperature);
+}
+
+static SENSOR_DEVICE_ATTR(temp1_input, S_IRUGO, adc_show_temp, NULL, 0);
+
+static struct attribute *mvf_adc_attributes[] = {
+ &sensor_dev_attr_temp1_input.dev_attr.attr,
+ NULL
+};
+
+static const struct attribute_group mvf_adc_group = {
+ .attrs = mvf_adc_attributes,
+};
+
+
+static int adc_open(struct inode *inode, struct file *file)
+{
+ struct adc_device *dev = container_of(inode->i_cdev,
+ struct adc_device, cdev);
+
+ file->private_data = dev;
+
return 0;
}
static long adc_ioctl(struct file *file, unsigned int cmd,
unsigned long arg)
{
+ struct adc_device *adc_dev = file->private_data;
void __user *argp = (void __user *)arg;
struct adc_feature feature;
int channel;
@@ -515,18 +624,19 @@ static long adc_ioctl(struct file *file, unsigned int cmd,
return -ENOTTY;
if (copy_from_user(&feature, (struct adc_feature *)argp,
- sizeof(feature))) {
+ sizeof(feature)))
return -EFAULT;
- }
+
+ if (feature.channel > 31)
+ return -EINVAL;
switch (cmd) {
case ADC_INIT:
- adc_initiate(adc_dev);
+ return adc_initiate(adc_dev);
break;
case ADC_CONFIGURATION:
-
- adc_set(adc_dev, &feature);
+ return adc_set(adc_dev, &feature);
break;
case ADC_REG_CLIENT:
@@ -535,13 +645,8 @@ static long adc_ioctl(struct file *file, unsigned int cmd,
break;
case ADC_CONVERT:
- INIT_COMPLETION(adc_tsi);
- adc_try(adc_dev);
- wait_for_completion_interruptible(&adc_tsi);
- if (data_array[feature.channel].flag) {
- feature.result0 = data_array[feature.channel].res_value;
- data_array[feature.channel].flag = 0;
- }
+ feature.result0 = adc_convert_wait(adc_dev, feature.channel);
+
if (copy_to_user((struct adc_feature *)argp, &feature,
sizeof(feature)))
return -EFAULT;
@@ -581,26 +686,6 @@ struct adc_client *adc_register(struct platform_device *pdev,
return client;
}
-
-/*result process */
-static int res_proc(void)
-{
- int con, res;
- struct adc_device *adc = adc_dev;
- con = readl(adc->regs + ADC_CFG);
-
- if ((con & (1 << 2)) == 0) {
- if ((con & (1 << 3)) == 1)
- res = (0xFFF & readl(adc->regs + ADC_R0));
- else
- res = (0xFF & readl(adc->regs + ADC_R0));
- } else
- res = (0x3FF & readl(adc->regs + ADC_R0));
-
- return readl(adc->regs + ADC_R0);
- return res;
-}
-
static irqreturn_t adc_irq(int irq, void *pw)
{
int coco;
@@ -614,7 +699,8 @@ static irqreturn_t adc_irq(int irq, void *pw)
coco = readl(adc->regs + ADC_HS);
if (coco & 1) {
- data_array[client->channel].res_value = res_proc();
+ data_array[client->channel].res_value =
+ readl(adc->regs + ADC_R0);
data_array[client->channel].flag = 1;
complete(&adc_tsi);
}
@@ -625,8 +711,8 @@ exit:
static const struct file_operations adc_fops = {
.owner = THIS_MODULE,
+ .open = adc_open,
.unlocked_ioctl = adc_ioctl,
- .open = NULL,
.read = NULL,
};
@@ -636,11 +722,8 @@ static int __devinit adc_probe(struct platform_device *pdev)
struct device *dev = &pdev->dev;
struct adc_device *adc;
struct resource *regs;
- struct cdev *adc_cdev;
- static struct class *adc_class;
+ dev_t devt;
int ret;
- dev_t id;
-
adc = kzalloc(sizeof(struct adc_device), GFP_KERNEL);
if (adc == NULL) {
@@ -686,34 +769,52 @@ static int __devinit adc_probe(struct platform_device *pdev)
goto err_clk;
}
- /* Obtain device numbers and register char device */
- ret = alloc_chrdev_region(&id, 0, 1, "mvf-adc");
+ /* clk enable */
+ clk_enable(adc->clk);
+
+ /* Save device structure by Platform device ID for touch */
+ adc_devices[pdev->id] = adc;
+
+ /* Register temperature sensor */
+ ret = sysfs_create_group(&pdev->dev.kobj, &mvf_adc_group);
if (ret < 0)
- return ret;
+ goto err_clk;
+
+ adc->hwmon_dev = hwmon_device_register(&pdev->dev);
+ if (IS_ERR(adc->hwmon_dev)) {
+ ret = PTR_ERR(adc->hwmon_dev);
+ dev_err(dev, "class registration failed (%d)\n", ret);
+ goto err_sysfs;
+ }
- adc_cdev = cdev_alloc();
- adc_cdev->ops = &adc_fops;
- adc_cdev->owner = THIS_MODULE;
- ret = cdev_add(adc_cdev, id, 1);
+ /* Create character device for ADC */
+ cdev_init(&adc->cdev, &adc_fops);
+ adc->cdev.owner = THIS_MODULE;
+ devt = MKDEV(mvf_adc_major, pdev->id);
+ ret = cdev_add(&adc->cdev, devt, 1);
if (ret < 0)
- return ret;
+ goto err_sysfs;
- adc_class = class_create(THIS_MODULE, "mvf-adc.0");
- if (IS_ERR(adc_class))
- return -1;
+ adc->dev = device_create(adc_class, &pdev->dev, devt,
+ NULL, "mvf-adc.%d", pdev->id);
+ if (IS_ERR(adc->dev)) {
+ dev_err(dev, "failed to create device\n");
+ goto err_cdev;
+ }
- device_create(adc_class, NULL, id, NULL, "mvf-adc.0");
- /* clk enable */
- clk_enable(adc->clk);
/* Associated structures */
platform_set_drvdata(pdev, adc);
- adc_dev = adc;
-
dev_info(dev, "attached adc driver\n");
return 0;
+err_cdev:
+ cdev_del(&adc->cdev);
+
+err_sysfs:
+ sysfs_remove_group(&pdev->dev.kobj, &mvf_adc_group);
+
err_clk:
clk_put(adc->clk);
@@ -728,12 +829,22 @@ err_alloc:
static int __devexit adc_remove(struct platform_device *pdev)
{
+ struct device *dev = &pdev->dev;
struct adc_device *adc = platform_get_drvdata(pdev);
+ dev_info(dev, "remove adc driver\n");
+
+ hwmon_device_unregister(adc->hwmon_dev);
+ sysfs_remove_group(&pdev->dev.kobj, &mvf_adc_group);
+
+ device_destroy(adc_class, adc->dev->devt);
+ cdev_del(&adc->cdev);
+
iounmap(adc->regs);
free_irq(adc->irq, adc);
clk_disable(adc->clk);
clk_put(adc->clk);
+ adc_devices[pdev->id] = NULL;
kfree(adc);
return 0;
@@ -751,21 +862,45 @@ static struct platform_driver adc_driver = {
static int __init adc_init(void)
{
int ret;
+ dev_t dev;
+
+ adc_class = class_create(THIS_MODULE, "mvf-adc");
+ if (IS_ERR(adc_class)) {
+ ret = PTR_ERR(adc_class);
+ printk(KERN_ERR "%s: can't register mvf-adc class\n",__func__);
+ goto err;
+ }
+
+ /* Obtain device numbers and register char device */
+ ret = alloc_chrdev_region(&dev, 0, MVF_ADC_MAX_DEVICES, "mvf-adc");
+ if (ret)
+ {
+ printk(KERN_ERR "%s: can't register character device\n",
+ __func__);
+ goto err_class;
+ }
+ mvf_adc_major = MAJOR(dev);
+
ret = platform_driver_register(&adc_driver);
if (ret)
printk(KERN_ERR "%s: failed to add adc driver\n", __func__);
+ return 0;
+err_class:
+ class_destroy(adc_class);
+err:
return ret;
}
static void __exit adc_exit(void)
{
platform_driver_unregister(&adc_driver);
+ class_destroy(adc_class);
}
module_init(adc_init);
module_exit(adc_exit);
-MODULE_AUTHOR("Xiaojun Wang");
+MODULE_AUTHOR("Xiaojun Wang, Stefan Agner");
MODULE_DESCRIPTION("Vybrid ADC driver");
MODULE_LICENSE("GPL v2");
MODULE_VERSION(DRV_VERSION);
diff --git a/drivers/mtd/nand/fsl_nfc.c b/drivers/mtd/nand/fsl_nfc.c
index f84c785e4383..27562653956a 100644
--- a/drivers/mtd/nand/fsl_nfc.c
+++ b/drivers/mtd/nand/fsl_nfc.c
@@ -27,6 +27,7 @@
#include <linux/slab.h>
#include <asm/fsl_nfc.h>
#include <mach/hardware.h>
+#include <mach/mxc_nand.h>
#ifdef CONFIG_COLDFIRE
#include <asm/mcfsim.h>
@@ -351,39 +352,20 @@ fsl_nfc_addr_cycle(struct mtd_info *mtd, int column, int page)
CONFIG_PAGE_CNT_SHIFT, 0x1);
}
-/* Control chips select signal on m54418twr board */
static void
nfc_select_chip(struct mtd_info *mtd, int chip)
{
-#ifdef CONFIG_COLDFIRE
- if (chip < 0) {
- MCF_GPIO_PAR_FBCTL &= (MCF_GPIO_PAR_FBCTL_ALE_MASK &
- MCF_GPIO_PAR_FBCTL_TA_MASK);
- MCF_GPIO_PAR_FBCTL |= MCF_GPIO_PAR_FBCTL_ALE_FB_TS |
- MCF_GPIO_PAR_FBCTL_TA_TA;
-
- MCF_GPIO_PAR_BE =
- MCF_GPIO_PAR_BE_BE3_BE3 | MCF_GPIO_PAR_BE_BE2_BE2 |
- MCF_GPIO_PAR_BE_BE1_BE1 | MCF_GPIO_PAR_BE_BE0_BE0;
-
- MCF_GPIO_PAR_CS &= ~MCF_GPIO_PAR_CS_CS1_NFC_CE;
- MCF_GPIO_PAR_CS |= MCF_GPIO_PAR_CS_CS0_CS0;
- return;
- }
+ nfc_set_field(mtd, NFC_ROW_ADDR, ROW_ADDR_CHIP_SEL_RB_MASK,
+ ROW_ADDR_CHIP_SEL_RB_SHIFT, 1);
- MCF_GPIO_PAR_FBCTL &= (MCF_GPIO_PAR_FBCTL_ALE_MASK &
- MCF_GPIO_PAR_FBCTL_TA_MASK);
- MCF_GPIO_PAR_FBCTL |= MCF_GPIO_PAR_FBCTL_ALE_FB_ALE |
- MCF_GPIO_PAR_FBCTL_TA_NFC_RB;
- MCF_GPIO_PAR_BE = MCF_GPIO_PAR_BE_BE3_FB_A1 |
- MCF_GPIO_PAR_BE_BE2_FB_A0 |
- MCF_GPIO_PAR_BE_BE1_BE1 | MCF_GPIO_PAR_BE_BE0_BE0;
-
- MCF_GPIO_PAR_CS &= (MCF_GPIO_PAR_BE_BE3_MASK &
- MCF_GPIO_PAR_BE_BE2_MASK);
- MCF_GPIO_PAR_CS |= MCF_GPIO_PAR_CS_CS1_NFC_CE;
- return;
-#endif
+ if (chip == 0)
+ nfc_set_field(mtd, NFC_ROW_ADDR, ROW_ADDR_CHIP_SEL_MASK,
+ ROW_ADDR_CHIP_SEL_SHIFT, 1);
+ else if (chip == 1)
+ nfc_set_field(mtd, NFC_ROW_ADDR, ROW_ADDR_CHIP_SEL_MASK,
+ ROW_ADDR_CHIP_SEL_SHIFT, 2);
+ else
+ nfc_clear(mtd, NFC_ROW_ADDR, ROW_ADDR_CHIP_SEL_MASK);
}
/* Read NAND Ready/Busy signal */
@@ -423,19 +405,8 @@ fsl_nfc_command(struct mtd_info *mtd, unsigned command,
CONFIG_ECC_MODE_MASK,
CONFIG_ECC_MODE_SHIFT, ECC_BYPASS);
- if (!(page%0x40)) {
- nfc_set_field(mtd, NFC_FLASH_CONFIG,
- CONFIG_ECC_MODE_MASK,
- CONFIG_ECC_MODE_SHIFT, ECC_BYPASS);
- }
-
switch (command) {
case NAND_CMD_PAGEPROG:
- if (!(prv->page%0x40))
- nfc_set_field(mtd, NFC_FLASH_CONFIG,
- CONFIG_ECC_MODE_MASK,
- CONFIG_ECC_MODE_SHIFT, ECC_BYPASS);
-
fsl_nfc_send_cmd(mtd,
PROGRAM_PAGE_CMD_BYTE1,
PROGRAM_PAGE_CMD_BYTE2,
@@ -663,25 +634,55 @@ fsl_nfc_read_word(struct mtd_info *mtd)
return tmp;
}
-#if 0
-static void fsl_nfc_check_ecc_status(struct mtd_info *mtd)
+static int nfc_calculate_ecc(struct mtd_info *mtd, const u_char *dat,
+ u_char *ecc_code)
+{
+ return 0;
+}
+
+/* Count the number of 0's in buff upto max_bits */
+static int count_written_bits(uint8_t *buff, int size, int max_bits)
+{
+ int k, written_bits = 0;
+
+ for (k = 0; k < size; k++) {
+ written_bits += hweight8(~buff[k]);
+ if (written_bits > max_bits)
+ break;
+ }
+
+ return written_bits;
+}
+
+static int fsl_nfc_check_ecc_status(struct mtd_info *mtd, u_char *dat)
{
struct nand_chip *chip = mtd->priv;
struct fsl_nfc_prv *prv = chip->priv;
- u8 ecc_status, ecc_count;
+ u32 ecc_status;
+ u8 ecc_count;
+ int flip;
- ecc_status = *(u8 *)(prv->regs + ECC_SRAM_ADDR * 8 + 7);
+ /*
+ * ECC status is stored at NFC_CFG[ECCADD] +4 for
+ * little-endian and +7 for big-endian SOC. Access as 32 bits
+ * and use low byte.
+ */
+ ecc_status = __raw_readl(prv->regs + ECC_SRAM_ADDR * 8 + 4);
ecc_count = ecc_status & ECC_ERR_COUNT;
- if (ecc_status & ECC_STATUS_MASK) {
- /*mtd->ecc_stats.failed++;*/
- printk("ECC failed to correct all errors!\n");
- } else if (ecc_count) {
- /*mtd->ecc_stats.corrected += ecc_count;*/
- printk(KERN_INFO"ECC corrected %d errors\n", ecc_count);
+ if (!(ecc_status & ECC_STATUS_MASK))
+ return ecc_count;
+
+ /* If 'ecc_count' zero or less then buffer is all 0xff or erased. */
+ flip = count_written_bits(dat, chip->ecc.size, ecc_count);
+
+
+ if (flip > ecc_count) {
+ printk("ECC failed to correct all errors (%08x)\n", ecc_status);
+ return -1;
}
+ return 0;
}
-#endif
static void
copy_from_to_spare(struct mtd_info *mtd, void *pbuf, int len, int wr)
@@ -748,12 +749,19 @@ static int fsl_nfc_write_oob(struct mtd_info *mtd, struct nand_chip *chip,
static int fsl_nfc_read_page(struct mtd_info *mtd, struct nand_chip *chip,
uint8_t *buf, int page)
{
+ int stat;
struct fsl_nfc_prv *prv = chip->priv;
- /*fsl_nfc_check_ecc_status(mtd);*/
memcpy_fromio((void *)buf, prv->regs + NFC_MAIN_AREA(0),
mtd->writesize);
copy_from_to_spare(mtd, chip->oob_poi, mtd->oobsize, 0);
+
+ stat = fsl_nfc_check_ecc_status(mtd, buf);
+ if (stat < 0)
+ mtd->ecc_stats.failed++;
+ else
+ mtd->ecc_stats.corrected += stat;
+
return 0;
}
@@ -787,6 +795,7 @@ fsl_nfc_probe(struct platform_device *pdev)
struct resource *res;
struct mtd_info *mtd;
struct mtd_partition *parts;
+ struct mxc_nand_platform_data *pdata = pdev->dev.platform_data;
struct nand_chip *chip;
unsigned long regs_paddr, regs_size;
int retval = 0;
@@ -830,7 +839,7 @@ fsl_nfc_probe(struct platform_device *pdev)
return -ENOMEM;
}
- mtd->name = "NAND";
+ mtd->name = "fsl_nfc";
mtd->writesize = 2048;
mtd->oobsize = 64;
@@ -842,7 +851,11 @@ fsl_nfc_probe(struct platform_device *pdev)
chip->write_buf = fsl_nfc_write_buf;
chip->verify_buf = fsl_nfc_verify_buf;
chip->options = NAND_NO_AUTOINCR | NAND_USE_FLASH_BBT |
- NAND_BUSWIDTH_16 | NAND_CACHEPRG;
+ NAND_CACHEPRG;
+
+ /* NAND bus width determines access funtions used by upper layer */
+ if (pdata->width == 2)
+ chip->options |= NAND_BUSWIDTH_16;
chip->select_chip = nfc_select_chip;
@@ -917,9 +930,11 @@ fsl_nfc_probe(struct platform_device *pdev)
CONFIG_FAST_FLASH_SHIFT, 1);
#endif
- nfc_set_field(mtd, NFC_FLASH_CONFIG,
- CONFIG_16BIT_MASK,
- CONFIG_16BIT_SHIFT, 1);
+ /* Flash mode width (BITWIDTH) required for 16-bit access */
+ if (pdata->width == 2)
+ nfc_set_field(mtd, NFC_FLASH_CONFIG,
+ CONFIG_16BIT_MASK,
+ CONFIG_16BIT_SHIFT, 1);
/* Detect NAND chips */
if (nand_scan(mtd, 1)) {
diff --git a/drivers/mtd/nand/nand_ids.c b/drivers/mtd/nand/nand_ids.c
index 251cb84b4d5f..a08fd7d07523 100644
--- a/drivers/mtd/nand/nand_ids.c
+++ b/drivers/mtd/nand/nand_ids.c
@@ -178,6 +178,7 @@ struct nand_manufacturers nand_manuf_ids[] = {
{NAND_MFR_AMD, "AMD"},
{NAND_MFR_SANDISK, "SanDisk"},
{NAND_MFR_INTEL, "Intel"},
+ {NAND_MFR_EON, "Eon"},
{0x0, "Unknown"}
};
diff --git a/drivers/net/Kconfig b/drivers/net/Kconfig
index de2905a67e76..31da73894a70 100644
--- a/drivers/net/Kconfig
+++ b/drivers/net/Kconfig
@@ -1951,6 +1951,13 @@ config FEC
Say Y here if you want to use the built-in 10/100 Fast ethernet
controller on some Motorola ColdFire and Freescale i.MX processors.
+config FEC0
+ bool "First FEC ethernet controller (of Vybrid and ColdFire)"
+ depends on FEC && (ARCH_MVF || M54455 || M5441X)
+ help
+ Say Y here if you want to use the first built-in 10/100 Fast
+ ethernet controller on Vybrid and some ColdFire processors.
+
config FEC1
bool "Second FEC ethernet controller (of Vybrid and ColdFire)"
depends on FEC && (ARCH_MVF || M54455 || M5441X)
diff --git a/drivers/net/fec.c b/drivers/net/fec.c
index 73f3f2b49a61..bcd02e5cfaf0 100755
--- a/drivers/net/fec.c
+++ b/drivers/net/fec.c
@@ -692,8 +692,14 @@ static void __inline__ fec_get_mac(struct net_device *ndev)
memcpy(ndev->dev_addr, iap, ETH_ALEN);
/* Adjust MAC if using macaddr */
+#if CONFIG_COLIBRI_VF
+ /* Add 0x100000 to the first MAC address to get the second */
+ if (iap == macaddr)
+ ndev->dev_addr[3] = macaddr[3] + (fep->pdev->id * 0x10);
+#else
if (iap == macaddr)
ndev->dev_addr[ETH_ALEN-1] = macaddr[ETH_ALEN-1] + fep->pdev->id;
+#endif /* !CONFIG_COLIBRI_VF */
}
/* ------------------------------------------------------------------------- */
@@ -876,6 +882,7 @@ static int fec_enet_mii_init(struct platform_device *pdev)
platform_get_device_id(fep->pdev);
int err = -ENXIO, i;
+#if !defined(CONFIG_COLIBRI_VF)
/*
* The dual fec interfaces are not equivalent with enet-mac.
* Here are the differences:
@@ -897,6 +904,7 @@ static int fec_enet_mii_init(struct platform_device *pdev)
fep->mii_bus = fec0_mii_bus;
return 0;
}
+#endif /* !CONFIG_COLIBRI_VF */
fep->mii_timeout = 0;
@@ -940,9 +948,11 @@ static int fec_enet_mii_init(struct platform_device *pdev)
if (mdiobus_register(fep->mii_bus))
goto err_out_free_mdio_irq;
+#if !defined(CONFIG_COLIBRI_VF)
/* save fec0 mii_bus */
if (id_entry->driver_data & FEC_QUIRK_ENET_MAC)
fec0_mii_bus = fep->mii_bus;
+#endif /* !CONFIG_COLIBRI_VF */
return 0;
diff --git a/drivers/net/phy/micrel.c b/drivers/net/phy/micrel.c
index 1d18fdbebf6c..5b1f5ea977b7 100644
--- a/drivers/net/phy/micrel.c
+++ b/drivers/net/phy/micrel.c
@@ -125,6 +125,8 @@ static struct phy_driver ks8737_driver = {
.read_status = genphy_read_status,
.ack_interrupt = kszphy_ack_interrupt,
.config_intr = ks8737_config_intr,
+ .suspend = genphy_suspend,
+ .resume = genphy_resume,
.driver = { .owner = THIS_MODULE,},
};
@@ -140,6 +142,8 @@ static struct phy_driver ks8041_driver = {
.read_status = genphy_read_status,
.ack_interrupt = kszphy_ack_interrupt,
.config_intr = kszphy_config_intr,
+ .suspend = genphy_suspend,
+ .resume = genphy_resume,
.driver = { .owner = THIS_MODULE,},
};
@@ -155,6 +159,8 @@ static struct phy_driver ks8051_driver = {
.read_status = genphy_read_status,
.ack_interrupt = kszphy_ack_interrupt,
.config_intr = kszphy_config_intr,
+ .suspend = genphy_suspend,
+ .resume = genphy_resume,
.driver = { .owner = THIS_MODULE,},
};
@@ -169,6 +175,8 @@ static struct phy_driver ks8001_driver = {
.read_status = genphy_read_status,
.ack_interrupt = kszphy_ack_interrupt,
.config_intr = kszphy_config_intr,
+ .suspend = genphy_suspend,
+ .resume = genphy_resume,
.driver = { .owner = THIS_MODULE,},
};
@@ -184,6 +192,8 @@ static struct phy_driver ksz9021_driver = {
.read_status = genphy_read_status,
.ack_interrupt = kszphy_ack_interrupt,
.config_intr = ksz9021_config_intr,
+ .suspend = genphy_suspend,
+ .resume = genphy_resume,
.driver = { .owner = THIS_MODULE, },
};
diff --git a/drivers/spi/spi_mvf_dspi.c b/drivers/spi/spi_mvf_dspi.c
index a394659a3b02..203999285e57 100644
--- a/drivers/spi/spi_mvf_dspi.c
+++ b/drivers/spi/spi_mvf_dspi.c
@@ -54,8 +54,6 @@
#if defined(CONFIG_SPI_MVF_DSPI_EDMA)
#define SPI_DSPI_EDMA
#define EDMA_BUFSIZE_KMALLOC (DSPI_FIFO_SIZE * 4)
-#define DSPI_DMA_RX_TCD DMA_MUX_DSPI0_RX
-#define DSPI_DMA_TX_TCD DMA_MUX_DSPI0_TX
#endif
struct DSPI_MCR {
@@ -207,7 +205,8 @@ static inline void set_16bit_transfer_mode(struct spi_mvf_data *spi_mvf)
writel(temp, spi_mvf->base + SPI_CTAR(spi_mvf->cs));
}
-static unsigned char hz_to_spi_baud(int pbr, int dbr, int speed_hz)
+static unsigned char hz_to_spi_baud(struct spi_mvf_data *spi_mvf,
+ int pbr, int dbr, int speed_hz)
{
/* Valid baud rate pre-scaler values */
int pbr_tbl[4] = {2, 3, 5, 7};
@@ -215,14 +214,14 @@ static unsigned char hz_to_spi_baud(int pbr, int dbr, int speed_hz)
16, 32, 64, 128,
256, 512, 1024, 2048,
4096, 8192, 16384, 32768 };
- int temp, index = 0;
+ int temp, pclk, index = 0;
/* table indexes out of range, go slow */
if ((pbr < 0) || (pbr > 3) || (dbr < 0) || (dbr > 1))
return 15;
- /* cpu core clk need to check */
- temp = ((((66000000 / 2) / pbr_tbl[pbr]) * (1 + dbr)) / speed_hz);
+ pclk = clk_get_rate(clk_get_parent(spi_mvf->clk));
+ temp = (((pclk / pbr_tbl[pbr]) * (1 + dbr)) / speed_hz);
while (temp > brs[index])
if (index++ >= 15)
@@ -309,7 +308,7 @@ static int write(struct spi_mvf_data *spi_mvf)
if (tx_count > 0) {
mcf_edma_set_tcd_params(spi_mvf->tx_chan,
spi_mvf->edma_tx_buf_pa,
- 0x4002c034,
+ (u32)(spi_mvf->base + SPI_PUSHR),
MCF_EDMA_TCD_ATTR_SSIZE_32BIT
| MCF_EDMA_TCD_ATTR_DSIZE_32BIT,
4, /* soff */
@@ -324,7 +323,7 @@ static int write(struct spi_mvf_data *spi_mvf)
0); /* enable sg */
mcf_edma_set_tcd_params(spi_mvf->rx_chan,
- 0x4002c038,
+ (u32)(spi_mvf->base + SPI_POPR),
spi_mvf->edma_rx_buf_pa,
MCF_EDMA_TCD_ATTR_SSIZE_32BIT
| MCF_EDMA_TCD_ATTR_DSIZE_32BIT,
@@ -572,7 +571,7 @@ static void pump_transfers(unsigned long data)
if (transfer->speed_hz)
writel((chip->ctar_val & ~0xf) |
- hz_to_spi_baud(chip->ctar.pbr, chip->ctar.dbr,
+ hz_to_spi_baud(spi_mvf, chip->ctar.pbr, chip->ctar.dbr,
transfer->speed_hz),
spi_mvf->base + SPI_CTAR(spi_mvf->cs));
@@ -659,6 +658,7 @@ static int transfer(struct spi_device *spi, struct spi_message *msg)
static int setup(struct spi_device *spi)
{
+ struct spi_mvf_data *spi_mvf = spi_master_get_devdata(spi->master);
struct chip_data *chip;
struct spi_mvf_chip *chip_info
= (struct spi_mvf_chip *)spi->controller_data;
@@ -702,8 +702,8 @@ static int setup(struct spi_device *spi)
chip->void_write_data = chip_info->void_write_data;
if (spi->max_speed_hz != 0)
- chip_info->br = hz_to_spi_baud(chip_info->pbr, chip_info->dbr,
- spi->max_speed_hz);
+ chip_info->br = hz_to_spi_baud(spi_mvf, chip_info->pbr,
+ chip_info->dbr, spi->max_speed_hz);
chip->ctar.cpha = (spi->mode & SPI_CPHA) ? 1 : 0;
chip->ctar.cpol = (spi->mode & SPI_CPOL) ? 1 : 0;
@@ -825,6 +825,9 @@ static int spi_mvf_probe(struct platform_device *pdev)
struct spi_mvf_data *spi_mvf;
struct resource *res;
int ret = 0;
+#if defined(SPI_DSPI_EDMA)
+ int rx_channel, tx_channel;
+#endif
int i;
platform_info = dev_get_platdata(&pdev->dev);
@@ -843,6 +846,7 @@ static int spi_mvf_probe(struct platform_device *pdev)
INIT_LIST_HEAD(&spi_mvf->queue);
spin_lock_init(&spi_mvf->lock);
+ master->mode_bits = SPI_CPHA | SPI_CPOL | SPI_LSB_FIRST;
master->bus_num = platform_info->bus_num;
master->num_chipselect = platform_info->num_chipselect;
master->cleanup = cleanup;
@@ -869,7 +873,7 @@ static int spi_mvf_probe(struct platform_device *pdev)
spi_mvf->base = ioremap(res->start, resource_size(res));
if (!spi_mvf->base) {
- ret = EINVAL;
+ ret = -EINVAL;
goto out_error_release_mem;
}
@@ -904,6 +908,7 @@ static int spi_mvf_probe(struct platform_device *pdev)
spi_mvf->clk = clk_get(&pdev->dev, "dspi_clk");
if (IS_ERR(spi_mvf->clk)) {
dev_err(&pdev->dev, "unable to get clock\n");
+ ret = -EINVAL;
goto out_error_irq_alloc;
}
clk_enable(spi_mvf->clk);
@@ -929,7 +934,23 @@ static int spi_mvf_probe(struct platform_device *pdev)
spi_mvf->edma_tx_buf, spi_mvf->edma_tx_buf_pa,
spi_mvf->edma_rx_buf, spi_mvf->edma_rx_buf_pa);
- spi_mvf->tx_chan = mcf_edma_request_channel(DSPI_DMA_TX_TCD,
+ /* TODO: move this to platform data */
+ switch (pdev->id) {
+ case 0:
+ rx_channel = DMA_MUX_DSPI0_RX;
+ tx_channel = DMA_MUX_DSPI0_TX;
+ break;
+ case 1:
+ rx_channel = DMA_MUX_DSPI1_RX;
+ tx_channel = DMA_MUX_DSPI1_TX;
+ break;
+ default:
+ dev_err(&pdev->dev, "unknown device id, no eDMA channels\n");
+ ret = -EINVAL;
+ goto out_error_queue_alloc;
+ }
+
+ spi_mvf->tx_chan = mcf_edma_request_channel(tx_channel,
edma_tx_handler, NULL, 0x00, pdev, NULL, DRIVER_NAME);
if (spi_mvf->tx_chan < 0) {
dev_err(&pdev->dev, "eDMA transmit channel request\n");
@@ -942,7 +963,7 @@ static int spi_mvf_probe(struct platform_device *pdev)
* by SPI communicate machnisim, i.e, is half duplex mode, that is
* whether read or write, we need write data out to get we wanted.
*/
- spi_mvf->rx_chan = mcf_edma_request_channel(DSPI_DMA_RX_TCD,
+ spi_mvf->rx_chan = mcf_edma_request_channel(rx_channel,
edma_rx_handler, NULL, 0x06, pdev, NULL, DRIVER_NAME);
if (spi_mvf->rx_chan < 0) {
dev_err(&pdev->dev, "eDAM receive channel request\n");
diff --git a/drivers/tty/serial/mvf.c b/drivers/tty/serial/mvf.c
index 0ea0181cd455..a174b63e2225 100644
--- a/drivers/tty/serial/mvf.c
+++ b/drivers/tty/serial/mvf.c
@@ -97,7 +97,7 @@ struct imx_port {
void *rx_buf;
unsigned char *tx_buf;
unsigned int rx_bytes, tx_bytes;
- struct work_struct tsk_rx, tsk_dma_tx;
+ struct work_struct tsk_dma_tx;
unsigned int dma_tx_nents;
bool dma_is_rxing, dma_is_txing;
wait_queue_head_t dma_wait;
@@ -368,17 +368,6 @@ out:
return IRQ_HANDLED;
}
-static void rx_work(struct work_struct *w)
-{
- struct imx_port *sport = container_of(w, struct imx_port, tsk_rx);
- struct tty_struct *tty = sport->port.state->port.tty;
-
- if (sport->rx_bytes) {
- tty_flip_buffer_push(tty);
- sport->rx_bytes = 0;
- }
-}
-
static irqreturn_t imx_rxint(int irq, void *dev_id)
{
struct imx_port *sport = dev_id;
@@ -450,6 +439,7 @@ out:
tty_flip_buffer_push(tty);
sport->rx_bytes = 0;
}
+
return IRQ_HANDLED;
}
@@ -553,6 +543,10 @@ static int imx_setup_watermark(struct imx_port *sport, unsigned int mode)
MXC_UARTCR2_RIE | MXC_UARTCR2_RE);
writeb(cr2, sport->port.membase + MXC_UARTCR2);
+ /* Clear pending receive interrupt if needed */
+ while (readb(sport->port.membase + MXC_UARTSR1) & MXC_UARTSR1_RDRF)
+ val = readb(sport->port.membase + MXC_UARTDR);
+
val = TXTL;
writeb(val, sport->port.membase + MXC_UARTTWFIFO);
val = RXTL;
@@ -564,6 +558,7 @@ static int imx_setup_watermark(struct imx_port *sport, unsigned int mode)
MXC_UARTPFIFO_TXFIFOSIZE_MASK) + 1);
sport->rx_fifo_size = 0x1 << (((val >> MXC_UARTPFIFO_RXFIFOSIZE_OFF) &
MXC_UARTPFIFO_RXFIFOSIZE_MASK) + 1);
+
writeb(val | MXC_UARTPFIFO_TXFE | MXC_UARTPFIFO_RXFE,
sport->port.membase + MXC_UARTPFIFO);
@@ -588,10 +583,8 @@ static int imx_startup(struct uart_port *port)
struct tty_struct *tty;
struct imxuart_platform_data *pdata = port->dev->platform_data;
-#ifndef CONFIG_SERIAL_CORE_CONSOLE
if (sport->fifo_en)
imx_setup_watermark(sport, 0);
-#endif
/*
* Allocate the IRQ(s)
@@ -616,9 +609,7 @@ static int imx_startup(struct uart_port *port)
temp |= MXC_UARTCR5_TDMAS;
writeb(temp, sport->port.membase + MXC_UARTCR5);
- sport->port.flags |= UPF_LOW_LATENCY;
INIT_WORK(&sport->tsk_dma_tx, dma_tx_work);
- INIT_WORK(&sport->tsk_rx, rx_work);
init_waitqueue_head(&sport->dma_wait);
}
diff --git a/drivers/video/mvf_dcu.c b/drivers/video/mvf_dcu.c
index 036097b77fcb..9eed2135dd31 100644
--- a/drivers/video/mvf_dcu.c
+++ b/drivers/video/mvf_dcu.c
@@ -38,6 +38,7 @@
#define DRIVER_NAME "mvf-dcu"
static struct fb_videomode __devinitdata mvf_dcu_default_mode = {
+#if !defined(CONFIG_COLIBRI_VF)
.xres = 480,
.yres = 272,
.left_margin = 2,
@@ -46,8 +47,23 @@ static struct fb_videomode __devinitdata mvf_dcu_default_mode = {
.lower_margin = 1,
.hsync_len = 41,
.vsync_len = 2,
- .sync = FB_SYNC_COMP_HIGH_ACT | FB_SYNC_VERT_HIGH_ACT,
+ .sync = FB_SYNC_HOR_HIGH_ACT | FB_SYNC_VERT_HIGH_ACT,
.vmode = FB_VMODE_NONINTERLACED,
+#else /* !CONFIG_COLIBRI_VF */
+ .refresh = 60,
+ .xres = 640,
+ .yres = 480,
+ /* pixel clock period in picoseconds (25.18 MHz) */
+ .pixclock = 38000,
+ .left_margin = 48,
+ .right_margin = 16,
+ .upper_margin = 31,
+ .lower_margin = 11,
+ .hsync_len = 96,
+ .vsync_len = 2,
+ .sync = 0,
+ .vmode = FB_VMODE_NONINTERLACED,
+#endif /* !CONFIG_COLIBRI_VF */
};
static struct fb_videomode __devinitdata mvf_dcu_mode_db[] = {
@@ -61,7 +77,93 @@ static struct fb_videomode __devinitdata mvf_dcu_mode_db[] = {
.lower_margin = 1,
.hsync_len = 41,
.vsync_len = 2,
- .sync = FB_SYNC_COMP_HIGH_ACT | FB_SYNC_VERT_HIGH_ACT,
+ .sync = FB_SYNC_HOR_HIGH_ACT | FB_SYNC_VERT_HIGH_ACT,
+ .vmode = FB_VMODE_NONINTERLACED,
+ },
+ {
+ /* 640x480p 60hz: EIA/CEA-861-B Format 1 */
+ .name = "640x480",
+ .refresh = 60,
+ .xres = 640,
+ .yres = 480,
+ /* pixel clock period in picoseconds (25.18 MHz) */
+ .pixclock = 38000,
+ .left_margin = 48,
+ .right_margin = 16,
+ .upper_margin = 31,
+ .lower_margin = 11,
+ .hsync_len = 96,
+ .vsync_len = 2,
+ .sync = 0,
+ .vmode = FB_VMODE_NONINTERLACED,
+ },
+ {
+ /* 800x480@60 (e.g. EDT ET070080DH6) */
+ .name = "800x480",
+ .refresh = 60,
+ .xres = 800,
+ .yres = 480,
+ /* pixel clock period in picoseconds (33.26 MHz) */
+ .pixclock = 30066,
+ .left_margin = 216,
+ .right_margin = 40,
+ .upper_margin = 35,
+ .lower_margin = 10,
+ .hsync_len = 128,
+ .vsync_len = 2,
+ .sync = 0,
+ .vmode = FB_VMODE_NONINTERLACED,
+ },
+ {
+ /* 800x600@60 */
+ .name = "800x600",
+ .refresh = 60,
+ .xres = 800,
+ .yres = 600,
+ /* pixel clock period in picoseconds (40 MHz) */
+ .pixclock = 25000,
+ .left_margin = 88,
+ .right_margin = 40,
+ .upper_margin = 23,
+ .lower_margin = 1,
+ .hsync_len = 128,
+ .vsync_len = 4,
+ .sync = FB_SYNC_HOR_HIGH_ACT | FB_SYNC_VERT_HIGH_ACT,
+ .vmode = FB_VMODE_NONINTERLACED,
+ },
+ {
+ /* TouchRevolution Fusion 10 aka Chunghwa Picture Tubes
+ CLAA101NC05 10.1 inch 1024x600 single channel LVDS panel */
+ .name = "1024x600",
+ .refresh = 60,
+ .xres = 1024,
+ .yres = 600,
+ /* pixel clock period in picoseconds (48 MHz) */
+ .pixclock = 20833,
+ .left_margin = 104,
+ .right_margin = 43,
+ .upper_margin = 24,
+ .lower_margin = 20,
+ .hsync_len = 5,
+ .vsync_len = 5,
+ .sync = 0,
+ .vmode = FB_VMODE_NONINTERLACED,
+ },
+ {
+ /* 1024x768@60 */
+ .name = "1024x768",
+ .refresh = 60,
+ .xres = 1024,
+ .yres = 768,
+ /* pixel clock period in picoseconds (65 MHz) */
+ .pixclock = 15385,
+ .left_margin = 160,
+ .right_margin = 24,
+ .upper_margin = 29,
+ .lower_margin = 3,
+ .hsync_len = 136,
+ .vsync_len = 6,
+ .sync = 0,
.vmode = FB_VMODE_NONINTERLACED,
},
};
@@ -76,6 +178,8 @@ struct mvf_dcu_fb_data {
unsigned int irq;
struct clk *clk;
int fb_enabled;
+ int clock_pol;
+ int default_bpp;
};
struct mfb_info {
@@ -84,12 +188,11 @@ struct mfb_info {
char *id;
int registered;
int blank;
- char *mode_str;
- int default_bpp;
unsigned long pseudo_palette[16];
struct dcu_layer_desc *layer_desc;
int cursor_reset;
unsigned char g_alpha;
+ unsigned char blend;
unsigned int count;
int x_layer_d; /* layer display x offset to physical screen */
int y_layer_d; /* layer display y offset to physical screen */
@@ -103,6 +206,7 @@ static struct mfb_info mfb_template[] = {
.id = "Layer0",
.registered = 0,
.g_alpha = 0xff,
+ .blend = 0,
.count = 0,
.x_layer_d = 0,
.y_layer_d = 0,
@@ -113,6 +217,7 @@ static struct mfb_info mfb_template[] = {
.id = "Layer1",
.registered = 0,
.g_alpha = 0xff,
+ .blend = 0,
.count = 0,
.x_layer_d = 50,
.y_layer_d = 50,
@@ -123,6 +228,7 @@ static struct mfb_info mfb_template[] = {
.id = "Layer2",
.registered = 0,
.g_alpha = 0xff,
+ .blend = 0,
.count = 0,
.x_layer_d = 100,
.y_layer_d = 100,
@@ -133,6 +239,7 @@ static struct mfb_info mfb_template[] = {
.id = "Layer3",
.registered = 0,
.g_alpha = 0xff,
+ .blend = 0,
.count = 0,
.x_layer_d = 150,
.y_layer_d = 150,
@@ -270,8 +377,6 @@ static void adjust_layer_size_position(struct fb_var_screeninfo *var,
static int mvf_dcu_check_var(struct fb_var_screeninfo *var,
struct fb_info *info)
{
- struct mfb_info *mfbi = info->par;
-
if (var->xres_virtual < var->xres)
var->xres_virtual = var->xres;
if (var->yres_virtual < var->yres)
@@ -291,7 +396,7 @@ static int mvf_dcu_check_var(struct fb_var_screeninfo *var,
if ((var->bits_per_pixel != 32) && (var->bits_per_pixel != 24) &&
(var->bits_per_pixel != 16))
- var->bits_per_pixel = mfbi->default_bpp;
+ var->bits_per_pixel = 16;
switch (var->bits_per_pixel) {
case 16:
@@ -375,11 +480,36 @@ static void set_fix(struct fb_info *info)
fix->ypanstep = 1;
}
+static int calc_div_ratio(struct fb_info *info)
+{
+ struct mfb_info *mfbi = info->par;
+ struct mvf_dcu_fb_data *dcufb = mfbi->parent;
+ unsigned long dcu_clk;
+ unsigned long long tmp;
+
+ /*
+ * Calculation could be done more precisly when we take parent clock
+ * into account too. We can change between 452MHz and 480MHz (see
+ * arch/arm/mach-mvf/clock.c
+ */
+ dcu_clk = clk_get_rate(dcufb->clk);
+ tmp = info->var.pixclock * (unsigned long long)dcu_clk;
+
+ do_div(tmp, 1000000);
+
+ if (do_div(tmp, 1000000) > 500000)
+ tmp++;
+
+ tmp = tmp - 1;
+ return tmp;
+}
+
static void update_lcdc(struct fb_info *info)
{
struct fb_var_screeninfo *var = &info->var;
struct mfb_info *mfbi = info->par;
struct mvf_dcu_fb_data *dcu = mfbi->parent;
+ unsigned int ratio;
if (mfbi->type == DCU_TYPE_OFF) {
mvf_dcu_disable_panel(info);
@@ -417,11 +547,12 @@ static void update_lcdc(struct fb_info *info)
writel(DCU_MODE_BLEND_ITER(3) | DCU_MODE_RASTER_EN(1),
dcu->base + DCU_DCU_MODE);
- writel(9, dcu->base + DCU_DIV_RATIO);
+ ratio = calc_div_ratio(info);
+ writel(ratio, dcu->base + DCU_DIV_RATIO);
+
+ /* Set various clock polarity (DCUx_SYNPOL) */
+ writel(dcu->clock_pol, dcu->base + DCU_SYN_POL);
- writel(DCU_SYN_POL_INV_PXCK(0) | DCU_SYN_POL_NEG(0) |
- DCU_SYN_POL_INV_VS(1) | DCU_SYN_POL_INV_HS(1),
- dcu->base + DCU_SYN_POL);
writel(DCU_THRESHOLD_LS_BF_VS(0x3) | DCU_THRESHOLD_OUT_BUF_HIGH(0x78) |
DCU_THRESHOLD_OUT_BUF_LOW(0), dcu->base + DCU_THRESHOLD);
@@ -519,11 +650,24 @@ static int mvf_dcu_set_par(struct fb_info *info)
layer_desc->posx = mfbi->x_layer_d;
layer_desc->posy = mfbi->y_layer_d;
- layer_desc->blend = 0x01;
+ switch (var->bits_per_pixel) {
+ case 16:
+ layer_desc->bpp = BPP_16_RGB565;
+ break;
+ case 24:
+ layer_desc->bpp = BPP_24;
+ break;
+ case 32:
+ layer_desc->bpp = BPP_32_ARGB8888;
+ break;
+ default:
+ printk(KERN_ERR "Unable to support other bpp now\n");
+ }
+
+ layer_desc->blend = mfbi->blend;
layer_desc->chroma_key_en = 0;
layer_desc->lut_offset = 0;
layer_desc->rle_en = 0;
- layer_desc->bpp = BPP_24;
layer_desc->trans = mfbi->g_alpha;
layer_desc->safety_en = 0;
layer_desc->data_sel_clut = 0;
@@ -624,9 +768,8 @@ static int mvf_dcu_pan_display(struct fb_var_screeninfo *var,
static int mvf_dcu_blank(int blank_mode, struct fb_info *info)
{
- struct mfb_info *mfbi = info->par;
-
#ifdef CONFIG_MVF_DCU_BLANKING_TEST
+ struct mfb_info *mfbi = info->par;
mfbi->blank = blank_mode;
switch (blank_mode) {
@@ -686,6 +829,7 @@ static int mvf_dcu_ioctl(struct fb_info *info, unsigned int cmd,
case MFB_SET_ALPHA:
if (copy_from_user(&global_alpha, buf, sizeof(global_alpha)))
return -EFAULT;
+ mfbi->blend = 1;
mfbi->g_alpha = global_alpha;
mvf_dcu_check_var(&info->var, info);
mvf_dcu_set_par(info);
@@ -815,15 +959,6 @@ static int init_fbinfo(struct fb_info *info)
static int __devinit install_fb(struct fb_info *info)
{
struct mfb_info *mfbi = info->par;
- struct fb_videomode *db = mvf_dcu_mode_db;
- unsigned int dbsize = ARRAY_SIZE(mvf_dcu_mode_db);
- int rc;
-
- if (init_fbinfo(info))
- return -EINVAL;
-
- rc = fb_find_mode(&info->var, info, mfbi->mode_str, db, dbsize,
- &mvf_dcu_default_mode, mfbi->default_bpp);
if (mvf_dcu_check_var(&info->var, info)) {
printk(KERN_ERR "fb_check_var failed");
@@ -942,6 +1077,68 @@ static int mvf_dcu_resume(struct platform_device *pdev)
#define mvf_dcu_resume NULL
#endif
+static int parse_opt(struct mvf_dcu_fb_data *dcu, char *this_opt)
+{
+ if (!strncmp(this_opt, "hsync:", 6)) {
+ /* Inverted logic
+ * hsync:0 => active low => INV_HS(1)
+ * hsync:1 => active high => INV_HS(0)
+ */
+ if (simple_strtoul(this_opt+6, NULL, 0) == 0)
+ dcu->clock_pol |= DCU_SYN_POL_INV_HS(1);
+ else
+ dcu->clock_pol &= ~DCU_SYN_POL_INV_HS(1);
+ return 0;
+ } else if (!strncmp(this_opt, "vsync:", 6)) {
+ /* Inverted logic
+ * vsync:0 => active low => INV_VS(1)
+ * vsync:1 => active high => INV_VS(0)
+ */
+ if (simple_strtoul(this_opt+6, NULL, 0) == 0)
+ dcu->clock_pol |= DCU_SYN_POL_INV_VS(1);
+ else
+ dcu->clock_pol &= ~DCU_SYN_POL_INV_VS(1);
+ return 0;
+ } else if (!strncmp(this_opt, "pixclockpol:", 12)) {
+ /* Inverted logic too, altough, datasheet seems to
+ * be wrong here! (1 => Display samples data on
+ * _falling_ edge)
+ * pixclockpol:0 => falling edge => INV_PXCK(1)
+ * pixclockpol:1 => rising edge => INV_PXCK(0)
+ */
+ if (simple_strtoul(this_opt+12, NULL, 0) == 0)
+ dcu->clock_pol |= DCU_SYN_POL_INV_PXCK(1);
+ else
+ dcu->clock_pol &= ~DCU_SYN_POL_INV_PXCK(1);
+ return 0;
+ }
+
+ return -1;
+}
+
+static int mvf_dcu_parse_options(struct mvf_dcu_fb_data *dcu,
+ struct fb_info *info, char *option)
+{
+ char *this_opt;
+ struct fb_videomode *db = mvf_dcu_mode_db;
+ unsigned int dbsize = ARRAY_SIZE(mvf_dcu_mode_db);
+ int ret = 0;
+
+ while ((this_opt = strsep(&option, ",")) != NULL) {
+ /* Parse driver specific arguments */
+ if (parse_opt(dcu, this_opt) == 0)
+ continue;
+
+ /* No valid driver specific argument, has to be mode */
+ ret = fb_find_mode(&info->var, info, this_opt, db, dbsize,
+ &mvf_dcu_default_mode, dcu->default_bpp);
+ if (ret < 0)
+ return ret;
+ }
+ return 0;
+}
+
+
static int __devinit mvf_dcu_probe(struct platform_device *pdev)
{
struct mvf_dcu_platform_data *plat_data = pdev->dev.platform_data;
@@ -950,11 +1147,24 @@ static int __devinit mvf_dcu_probe(struct platform_device *pdev)
struct resource *res;
int ret = 0;
int i;
+ char *option = NULL;
dcu = kmalloc(sizeof(struct mvf_dcu_fb_data), GFP_KERNEL);
if (!dcu)
return -ENOMEM;
+ fb_get_options("dcufb", &option);
+
+ if (option != NULL) {
+ printk(KERN_INFO "dcufb: parse cmd options: %s\n", option);
+ } else {
+ option = plat_data->mode_str;
+ printk(KERN_INFO "dcufb: use default mode: %s\n", option);
+ }
+
+ if (!strcmp(option, "off"))
+ return -ENODEV;
+
for (i = 0; i < ARRAY_SIZE(dcu->mvf_dcu_info); i++) {
dcu->mvf_dcu_info[i] =
framebuffer_alloc(sizeof(struct mfb_info),
@@ -967,8 +1177,21 @@ static int __devinit mvf_dcu_probe(struct platform_device *pdev)
mfbi = dcu->mvf_dcu_info[i]->par;
memcpy(mfbi, &mfb_template[i], sizeof(struct mfb_info));
mfbi->parent = dcu;
- mfbi->mode_str = plat_data->mode_str;
- mfbi->default_bpp = plat_data->default_bpp;
+ if (init_fbinfo(dcu->mvf_dcu_info[i])) {
+ ret = -EINVAL;
+ goto failed_alloc_framebuffer;
+ }
+ }
+
+ dcu->default_bpp = plat_data->default_bpp;
+ dcu->clock_pol = DCU_SYN_POL_INV_HS(1) | DCU_SYN_POL_INV_VS(1) |
+ DCU_SYN_POL_INV_PXCK(1);
+
+ /* Use framebuffer of first layer to store display mode */
+ ret = mvf_dcu_parse_options(dcu, dcu->mvf_dcu_info[0], option);
+ if (ret < 0) {
+ ret = -EINVAL;
+ goto failed_alloc_framebuffer;
}
res = platform_get_resource(pdev, IORESOURCE_MEM, 0);
@@ -1003,9 +1226,11 @@ static int __devinit mvf_dcu_probe(struct platform_device *pdev)
goto failed_get_resource;
}
+#if !defined(CONFIG_COLIBRI_VF)
gpio_request_one(DCU_LCD_ENABLE_PIN, GPIOF_OUT_INIT_LOW, "DCU");
msleep(2);
gpio_set_value(DCU_LCD_ENABLE_PIN, 1);
+#endif
writel(0x20000000, MVF_IO_ADDRESS(MVF_TCON0_BASE_ADDR));