linux(七):I2C(touch screen)

        本文主要探讨210触摸屏驱动相关知识。

I2C子系统
        
i2c子系统组成部分:I2C核心,I2C总线驱动,I2C设备驱动
        I2C核心:I2C总线驱动和设备驱动注册注销方法
        I2C总线驱动:I2C适配器(I2C控制器)控制,用于I2C读写时序(I2C_adapter、i2c_algorithm)
        I2C设备驱动:I2C适配器与CPU交换数据(i2c_driver、i2c_client)


 


结构体

struct i2c_adapter {
    struct module *owner;
    unsigned int id;
    unsigned int class;          /* classes to allow probing for */
    const struct i2c_algorithm *algo; /* the algorithm to access the bus */
    void *algo_data;

    /* data fields that are valid for all devices    */
    struct rt_mutex bus_lock;

    int timeout;            /* in jiffies */
    int retries;
    struct device dev;        /* the adapter device */

    int nr;
    char name[48];
    struct completion dev_released;

    struct list_head userspace_clients;
};

        int nr;;i2c适配器id号
        unsigned int class;i2c适配器适配器类(/sys/class/i2c-adapter)
        const struct i2c_algorithm *algo;void *algo_data;i2c适配器通信方法
        struct device dev;i2c适配器设备
        char name[48];i2c适配器名称
        struct list_head userspace_clients;挂接与适配器匹配成功的从设备i2c_client的链表头
用于i2c适配器描述(I2C控制器)

struct i2c_algorithm {
    
    int (*master_xfer)(struct i2c_adapter *adap, struct i2c_msg *msgs,
               int num);
    int (*smbus_xfer) (struct i2c_adapter *adap, u16 addr,
               unsigned short flags, char read_write,
               u8 command, int size, union i2c_smbus_data *data);

    /* To determine what the adapter supports */
    u32 (*functionality) (struct i2c_adapter *);
};

        master_xfer:I2C传输时序,传输i2c_msg
        master_xfer_atomic:同上,用于访问电源管理芯片
        smbus_xfer:实现SMBus传输
        smbus_xfer_atomic:用来访问电源管理芯片
        functionality:返回flags(I2C_FUNC_*)
        用于i2c通信方法描述

struct i2c_client {
    unsigned short flags;        /* div., see below        */
    unsigned short addr;        /* chip address - NOTE: 7bit    */
                    /* addresses are stored in the    */
                    /* _LOWER_ 7 bits        */
    char name[I2C_NAME_SIZE];
    struct i2c_adapter *adapter;    /* the adapter we sit on    */
    struct i2c_driver *driver;    /* and our access routines    */
    struct device dev;        /* the device structure        */
    int irq;            /* irq issued by device        */
    struct list_head detected;
};

        unsigned short flags;i2c设备特性标志位
        unsigned short addr;i2c设备地址
        char name[I2C_NAME_SIZE];i2c设备名
        struct i2c_adapter *adapter;与次设备匹配成功的适配器
        struct i2c_driver *driver;与次设备匹配成功的设备驱动
        struct device dev;i2c设备
        int irq;次设备中断引脚
        struct list_head detected;挂接到匹配成功的i2c_driver链表头上 
        用于i2c次设备描述

struct i2c_driver {
    unsigned int class;

    /* Notifies the driver that a new bus has appeared or is about to be
     * removed. You should avoid using this if you can, it will probably
     * be removed in a near future.
     */
    int (*attach_adapter)(struct i2c_adapter *);
    int (*detach_adapter)(struct i2c_adapter *);

    /* Standard driver model interfaces */
    int (*probe)(struct i2c_client *, const struct i2c_device_id *);
    int (*remove)(struct i2c_client *);

    /* driver model interfaces that don't relate to enumeration  */
    void (*shutdown)(struct i2c_client *);
    int (*suspend)(struct i2c_client *, pm_message_t mesg);
    int (*resume)(struct i2c_client *);

    /* Alert callback, for example for the SMBus alert protocol.
     * The format and meaning of the data value depends on the protocol.
     * For the SMBus alert protocol, there is a single bit of data passed
     * as the alert response's low bit ("event flag").
     */
    void (*alert)(struct i2c_client *, unsigned int data);

    /* a ioctl like command that can be used to perform specific functions
     * with the device.
     */
    int (*command)(struct i2c_client *client, unsigned int cmd, void *arg);

    struct device_driver driver;
    const struct i2c_device_id *id_table;

    /* Device detection callback for automatic device creation */
    int (*detect)(struct i2c_client *, struct i2c_board_info *);
    const unsigned short *address_list;
    struct list_head clients;
};

        unsigned int class;i2c设备驱动所支持的i2c设备的类型
        int (*attach_adapter)(struct i2c_adapter *);匹配适配器
        int (*probe)(struct i2c_client *, const struct i2c_device_id *); 设备驱动层probe函数
        int (*remove)(struct i2c_client *);设备驱动卸载函数
        const struct i2c_device_id *id_table;设备驱动的id_table(匹配驱动)   
        const unsigned short *address_list;驱动支持设备的地址数组
        struct list_head clients;挂接与i2c_driver匹配成功的i2c_client(设备)
        用于描述设备驱动

struct i2c_board_info {
    char        type[I2C_NAME_SIZE];
    unsigned short    flags;
    unsigned short    addr;
    void        *platform_data;
    struct dev_archdata    *archdata;
#ifdef CONFIG_OF
    struct device_node *of_node;
#endif
    int        irq;
};

        char  type[I2C_NAME_SIZE];i2c设备名字(i2c_client.name)
        unsigned short    flags;i2c_client.flags
        unsigned short    addr;i2c_client.addr
        void  *platform_data;i2c_client.dev.platform_data
        struct dev_archdata    *archdata;i2c_client.dev.archdata
        int  irq;i2c_client.irq
        描述设备信息结构体

struct i2c_msg {
    __u16 addr;           /*次设备地址 */
    __u16 flags;          /* 标志位*/
#define I2C_M_TEN           0x0010    /* 设置设备地址是10bit */
#define I2C_M_RD            0x0001    /* 设置i2c控制器为接收方,否则为发送方 */
#define I2C_M_NOSTART       0x4000    
#define I2C_M_REV_DIR_ADDR  0x2000    /* 设置将读写标志位反转 */
#define I2C_M_IGNORE_NAK    0x1000    /* 设置i2c_msg忽略I2C器件的ack和nack信号 */
#define I2C_M_NO_RD_ACK     0x0800    /* 设置读操作中主机不用ACK */
#define I2C_M_RECV_LEN      0x0400    
    __u16 len;                        /* 数据长度 */
    __u8 *buf;                        /* 数据缓冲区指针 */
};

i2c CORE

postcore_initcall(i2c_init);
module_exit(i2c_exit);
static int __init i2c_init(void)
{
    int retval;

    retval = bus_register(&i2c_bus_type);
    if (retval)
        return retval;
#ifdef CONFIG_I2C_COMPAT
    i2c_adapter_compat_class = class_compat_register("i2c-adapter");
    if (!i2c_adapter_compat_class) {
        retval = -ENOMEM;
        goto bus_err;
    }
#endif
    retval = i2c_add_driver(&dummy_driver);
    if (retval)
        goto class_err;
    return 0;

class_err:
#ifdef CONFIG_I2C_COMPAT
    class_compat_unregister(i2c_adapter_compat_class);
bus_err:
#endif
    bus_unregister(&i2c_bus_type);
    return retval;
}
struct bus_type i2c_bus_type = {
    .name        = "i2c",
    .match        = i2c_device_match,
    .probe        = i2c_device_probe,
    .remove        = i2c_device_remove,
    .shutdown    = i2c_device_shutdown,
    .pm        = &i2c_device_pm_ops,
};
static int i2c_device_match(struct device *dev, struct device_driver *drv)
{
    struct i2c_client    *client = i2c_verify_client(dev);
    struct i2c_driver    *driver;

    if (!client)
        return 0;

    driver = to_i2c_driver(drv);
    /* match on an id table if there is one */
    if (driver->id_table)
        return i2c_match_id(driver->id_table, client) != NULL;

    return 0;
}

static int i2c_device_probe(struct device *dev)
{
    struct i2c_client    *client = i2c_verify_client(dev);
    struct i2c_driver    *driver;
    int status;

    if (!client)
        return 0;

    driver = to_i2c_driver(dev->driver);
    if (!driver->probe || !driver->id_table)
        return -ENODEV;
    client->driver = driver;
    if (!device_can_wakeup(&client->dev))
        device_init_wakeup(&client->dev,
                    client->flags & I2C_CLIENT_WAKE);
    dev_dbg(dev, "probe\n");

    status = driver->probe(client, i2c_match_id(driver->id_table, client));
    if (status) {
        client->driver = NULL;
        i2c_set_clientdata(client, NULL);
    }
    return status;
}

        i2c_match_id通过设备与设备驱动名字和i2c_device_id依次匹配,总线层的probe为设备client层的probe

注册接口
int i2c_add_adapter(struct i2c_adapter *adapter);
int i2c_add_numbered_adapter(struct i2c_adapter *adap);
注册adapter,都调用i2c_register_adapter,i2c_add_adapter自动分配适配器编号,i2c_add_numbered_adapter指定编号
static inline int i2c_add_driver(struct i2c_driver *driver);注册driver
struct i2c_client *i2c_new_device(struct i2c_adapter *adap, struct i2c_board_info const *info);注册client
static int i2c_register_adapter(struct i2c_adapter *adap)
{
    int res = 0, dummy;

    /* Can't register until after driver model init */
    if (unlikely(WARN_ON(!i2c_bus_type.p))) {
        res = -EAGAIN;
        goto out_list;
    }

    rt_mutex_init(&adap->bus_lock);
    INIT_LIST_HEAD(&adap->userspace_clients);

    /* Set default timeout to 1 second if not already set */
    if (adap->timeout == 0)
        adap->timeout = HZ;

    dev_set_name(&adap->dev, "i2c-%d", adap->nr);
    adap->dev.bus = &i2c_bus_type;
    adap->dev.type = &i2c_adapter_type;
    res = device_register(&adap->dev);
    if (res)
        goto out_list;

    dev_dbg(&adap->dev, "adapter [%s] registered\n", adap->name);

#ifdef CONFIG_I2C_COMPAT
    res = class_compat_create_link(i2c_adapter_compat_class, &adap->dev,
                       adap->dev.parent);
    if (res)
        dev_warn(&adap->dev,
             "Failed to create compatibility class link\n");
#endif

    /* create pre-declared device nodes */
    if (adap->nr < __i2c_first_dynamic_bus_num)
        i2c_scan_static_board_info(adap);

    /* Notify drivers */
    mutex_lock(&core_lock);
    dummy = bus_for_each_drv(&i2c_bus_type, NULL, adap,
                 __process_new_adapter);
    mutex_unlock(&core_lock);

    return 0;

out_list:
    mutex_lock(&core_lock);
    idr_remove(&i2c_adapter_idr, adap->nr);
    mutex_unlock(&core_lock);
    return res;
}
static void i2c_scan_static_board_info(struct i2c_adapter *adapter)
{
    struct i2c_devinfo    *devinfo;

    down_read(&__i2c_board_lock);
    list_for_each_entry(devinfo, &__i2c_board_list, list) {
        if (devinfo->busnum == adapter->nr
                && !i2c_new_device(adapter,
                        &devinfo->board_info))
            dev_err(&adapter->dev,
                "Can't create device at 0x%02x\n",
                devinfo->board_info.addr);
    }
    up_read(&__i2c_board_lock);
}
int i2c_register_driver(struct module *owner, struct i2c_driver *driver)
{
    int res;

    /* Can't register until after driver model init */
    if (unlikely(WARN_ON(!i2c_bus_type.p)))
        return -EAGAIN;

    /* add the driver to the list of i2c drivers in the driver core */
    driver->driver.owner = owner;
    driver->driver.bus = &i2c_bus_type;

    /* When registration returns, the driver core
     * will have called probe() for all matching-but-unbound devices.
     */
    res = driver_register(&driver->driver);
    if (res)
        return res;

    pr_debug("i2c-core: driver [%s] registered\n", driver->driver.name);

    INIT_LIST_HEAD(&driver->clients);
    /* Walk the adapters that are already present */
    mutex_lock(&core_lock);
    bus_for_each_dev(&i2c_bus_type, NULL, driver, __process_new_driver);
    mutex_unlock(&core_lock);

    return 0;
}

         i2c_scan_static_board_info(adap);用于注册设备
        遍历 __i2c_board_list上的i2c_devinfo结构体,比较i2c_devinfo->busnum与适配的编号,匹配则调用i2c_new_device注册
        i2c_new_device是在系统启动时在smdkc110_machine_init注册i2c次设备
        smdkc110_machine_init-->platform_add_devices-->s3c_i2c1_set_platdata-->i2c_register_board_info

i2c driver

subsys_initcall(i2c_adap_s3c_init);
static int __init i2c_adap_s3c_init(void)
{
    return platform_driver_register(&s3c24xx_i2c_driver);
}

MODULE_DEVICE_TABLE(platform, s3c24xx_driver_ids);

static struct platform_driver s3c24xx_i2c_driver = {
    .probe        = s3c24xx_i2c_probe,
    .remove        = s3c24xx_i2c_remove,
    .id_table    = s3c24xx_driver_ids,
    .driver        = {
        .owner    = THIS_MODULE,
        .name    = "s3c-i2c",
        .pm    = S3C24XX_DEV_PM_OPS,
    },
};
static int s3c24xx_i2c_probe(struct platform_device *pdev)
{
    struct s3c24xx_i2c *i2c;               //   次结构体是三星对本SoC中的i2c控制器的一个描述,是一个用来在多文件中进行数据传递的全局结构体
    struct s3c2410_platform_i2c *pdata;    //   此结构体用来表示平台设备的私有数据
    struct resource *res;
    int ret;
 
    pdata = pdev->dev.platform_data;       //  获取到平台设备层中的平台数据
    if (!pdata) {
        dev_err(&pdev->dev, "no platform data\n");
        return -EINVAL;
    }
 
    i2c = kzalloc(sizeof(struct s3c24xx_i2c), GFP_KERNEL); //  给s3c24xx_i2c类型指针申请分配内存空间
    if (!i2c) {
        dev_err(&pdev->dev, "no memory for state\n");
        return -ENOMEM;
    }
 
//   以下主要是对s3c24xx_i2c 结构体中的i2c_adapter变量的一个填充
    strlcpy(i2c->adap.name, "s3c2410-i2c", sizeof(i2c->adap.name)); //  设置适配器的名字    s3c2410-i2c
    i2c->adap.owner   = THIS_MODULE;
    i2c->adap.algo    = &s3c24xx_i2c_algorithm;                     //  通信算法
    i2c->adap.retries = 2;
    i2c->adap.class   = I2C_CLASS_HWMON | I2C_CLASS_SPD;            //  该适配器所支持的次设备类有哪些
    i2c->tx_setup     = 50;
 
    spin_lock_init(&i2c->lock);       //  初始化互斥锁
    init_waitqueue_head(&i2c->wait);  //  初始化工作队列
 
    /* find the clock and enable it */
 
    i2c->dev = &pdev->dev;            //  通过s3c24xx_i2c->dev 指针指向平台设备的device结构体
    i2c->clk = clk_get(&pdev->dev, "i2c");
 
    if (IS_ERR(i2c->clk)) {
        dev_err(&pdev->dev, "cannot get clock\n");
        ret = -ENOENT;
        goto err_noclk;
    }
 
    dev_dbg(&pdev->dev, "clock source %p\n", i2c->clk);
 
    clk_enable(i2c->clk);             //  使能时钟
 
    /* map the registers */
 
    res = platform_get_resource(pdev, IORESOURCE_MEM, 0);  //  获取平台设备资源
    if (res == NULL) {
        dev_err(&pdev->dev, "cannot find IO resource\n");
        ret = -ENOENT;
        goto err_clk;
    }
 
    i2c->ioarea = request_mem_region(res->start, resource_size(res), //  物理地址到虚拟地址的映射请求
                     pdev->name);
 
    if (i2c->ioarea == NULL) {
        dev_err(&pdev->dev, "cannot request IO\n");
        ret = -ENXIO;
        goto err_clk;
    }
 
    i2c->regs = ioremap(res->start, resource_size(res));    //  地址映射
 
    if (i2c->regs == NULL) {
        dev_err(&pdev->dev, "cannot map IO\n");
        ret = -ENXIO;
        goto err_ioarea;
    }
 
    dev_dbg(&pdev->dev, "registers %p (%p, %p)\n",
        i2c->regs, i2c->ioarea, res);
 
    /* setup info block for the i2c core */
 
    i2c->adap.algo_data = i2c;          //  将s3c24xx_i2c 结构体变量作为s3c24xx_i2c中内置的i2c_adapter适配器中的私有数据
    i2c->adap.dev.parent = &pdev->dev;  //  指定适配器设备的父设备是平台设备device :   /sys/devices/platform/s3c2410-i2cn这个目录下
 
    /* initialise the i2c controller */
 
    ret = s3c24xx_i2c_init(i2c);        //  i2c控制器(适配器)    寄存器相关的配置
    if (ret != 0)
        goto err_iomap;
 
    /* find the IRQ for this unit (note, this relies on the init call to
     * ensure no current IRQs pending
     */
    i2c->irq = ret = platform_get_irq(pdev, 0); //  获取平台设备中的i2c中断号(这个中断是I2C控制器产生的中断)
    if (ret <= 0) {
        dev_err(&pdev->dev, "cannot find IRQ\n");
        goto err_iomap;
    }
 
    ret = request_irq(i2c->irq, s3c24xx_i2c_irq, IRQF_DISABLED,  //  申请中断
              dev_name(&pdev->dev), i2c);
 
    if (ret != 0) {
        dev_err(&pdev->dev, "cannot claim IRQ %d\n", i2c->irq);
        goto err_iomap;
    }
 
    ret = s3c24xx_i2c_register_cpufreq(i2c);   //  这个不清楚
    if (ret < 0) {
        dev_err(&pdev->dev, "failed to register cpufreq notifier\n");
        goto err_irq;
    }
 
    /* Note, previous versions of the driver used i2c_add_adapter()
     * to add the bus at any number. We now pass the bus number via
     * the platform data, so if unset it will now default to always
     * being bus 0.
     */
    i2c->adap.nr = pdata->bus_num;              //  确定i2c主机(适配器)的编号
 
    ret = i2c_add_numbered_adapter(&i2c->adap); //  向i2c核心注册i2c适配器  /sys/devices/platform/s3c2410-i2cn/s3c2410-i2c   因为在函数内会将 i2c-%d作为适配器的名字
    if (ret < 0) {
        dev_err(&pdev->dev, "failed to add bus to i2c core\n");
        goto err_cpufreq;
    }
 
    platform_set_drvdata(pdev, i2c);   //  将s3c24xx_i2c变量作为平台设备私有数据中的设备驱动私有数据  dev->p->driver_data
                                       //  因为这个变量还会在本文件中其他函数中会用到了 
    clk_disable(i2c->clk);
 
    dev_info(&pdev->dev, "%s: S3C I2C adapter\n", dev_name(&i2c->adap.dev));
    return 0;
 
 err_cpufreq:
    s3c24xx_i2c_deregister_cpufreq(i2c);
 
 err_irq:
    free_irq(i2c->irq, i2c);
 
 err_iomap:
    iounmap(i2c->regs);
 
 err_ioarea:
    release_resource(i2c->ioarea);
    kfree(i2c->ioarea);
 
 err_clk:
    clk_disable(i2c->clk);
    clk_put(i2c->clk);
 
 err_noclk:
    kfree(i2c);
    return ret;
}

i2c client

        210使用I2C电容触摸屏(gslx680)

module_init(gsl_ts_init);
module_exit(gsl_ts_exit);
static int __init gsl_ts_init(void)
{
    int ret;
    print_info("==gsl_ts_init==\n");
    ret = i2c_add_driver(&gsl_ts_driver);
    print_info("ret=%d\n",ret);
    return ret;
}
static inline int i2c_add_driver(struct i2c_driver *driver)
{
    return i2c_register_driver(THIS_MODULE, driver);
}
MODULE_DEVICE_TABLE(i2c, gsl_ts_id);

static struct i2c_driver gsl_ts_driver = {
    .driver = {
        .name = GSLX680_I2C_NAME,
        .owner = THIS_MODULE,
    },
#ifndef CONFIG_HAS_EARLYSUSPEND
    .suspend    = gsl_ts_suspend,
    .resume    = gsl_ts_resume,
#endif
    .probe        = gsl_ts_probe,
    .remove        = __devexit_p(gsl_ts_remove),
    .id_table    = gsl_ts_id,
};
#define GSLX680_I2C_NAME     "gslX680"
#define GSLX680_I2C_ADDR     0x40
#define IRQ_PORT            IRQ_EINT(7)
#define GSL_DATA_REG        0x80
#define GSL_STATUS_REG        0xe0
#define GSL_PAGE_REG        0xf0
static int __devinit gsl_ts_probe(struct i2c_client *client,
            const struct i2c_device_id *id)
{
    struct gsl_ts *ts;      //  设备驱动层封装的一个全局结构体
    int rc;
 
    print_info("GSLX680 Enter %s\n", __func__);
    if (!i2c_check_functionality(client->adapter, I2C_FUNC_I2C)) {
        dev_err(&client->dev, "I2C functionality not supported\n");
        return -ENODEV;
    }
 
    ts = kzalloc(sizeof(*ts), GFP_KERNEL);  //  给 gsl_ts类型的指针申请分配内存
    if (!ts)
        return -ENOMEM;
    print_info("==kzalloc success=\n");
 
    ts->client = client;                    //  通过gsl_ts->client指针去指向传进来的i2c次设备i2c_client
    i2c_set_clientdata(client, ts);         //  将gsl_ts作为i2c次设备的私有数据区中的设备驱动私有数据
    ts->device_id = id->driver_data;
 
    rc = gslX680_ts_init(client, ts);       //   初始化操作
    if (rc < 0) {
        dev_err(&client->dev, "GSLX680 init failed\n");
        goto error_mutex_destroy;
    }    
 
    gsl_client = client;       //  通过一个全局的i2c_client指针gsl_client去指向传进来的i2c次设备i2c_client
    
    gslX680_init();            //  gslX680 触摸屏相关的gpio初始化操作
    init_chip(ts->client);     //  gslX680触摸屏芯片相关的初始化操作
    check_mem_data(ts->client);
    
    rc=  request_irq(client->irq, gsl_ts_irq, IRQF_TRIGGER_RISING, client->name, ts); //  申请中断,这个中断是接在SoC的一个外部中断引脚上的
    if (rc < 0) {                                                                     // 当发生中断的时候表示有数据可以进行读取了,那么就会通知
        print_info( "gsl_probe: request irq failed\n");                               //  I2C主机去去读数据 
        goto error_req_irq_fail;
    }
 
    /* create debug attribute */
    //rc = device_create_file(&ts->input->dev, &dev_attr_debug_enable);
 
#ifdef CONFIG_HAS_EARLYSUSPEND
    ts->early_suspend.level = EARLY_SUSPEND_LEVEL_BLANK_SCREEN + 1;
    //ts->early_suspend.level = EARLY_SUSPEND_LEVEL_DISABLE_FB + 1;
    ts->early_suspend.suspend = gsl_ts_early_suspend;
    ts->early_suspend.resume = gsl_ts_late_resume;
    register_early_suspend(&ts->early_suspend);
#endif
 
 
#ifdef GSL_MONITOR
    print_info( "gsl_ts_probe () : queue gsl_monitor_workqueue\n");
 
    INIT_DELAYED_WORK(&gsl_monitor_work, gsl_monitor_worker);
    gsl_monitor_workqueue = create_singlethread_workqueue("gsl_monitor_workqueue");
    queue_delayed_work(gsl_monitor_workqueue, &gsl_monitor_work, 1000);
#endif
 
    print_info("[GSLX680] End %s\n", __func__);
 
    return 0;
 
//exit_set_irq_mode:    
error_req_irq_fail:
    free_irq(ts->irq, ts);    
 
error_mutex_destroy:
    input_free_device(ts->input);
    kfree(ts);
    return rc;
}

static int gslX680_ts_init(struct i2c_client *client, struct gsl_ts *ts)
{
    struct input_dev *input_device;            //   定义一个 input_dev 结构体指针
    int rc = 0;
    
    printk("[GSLX680] Enter %s\n", __func__);
 
    ts->dd = &devices[ts->device_id];
 
    if (ts->device_id == 0) {
        ts->dd->data_size = MAX_FINGERS * ts->dd->touch_bytes + ts->dd->touch_meta_data;
        ts->dd->touch_index = 0;
    }
 
    ts->touch_data = kzalloc(ts->dd->data_size, GFP_KERNEL);
    if (!ts->touch_data) {
        pr_err("%s: Unable to allocate memory\n", __func__);
        return -ENOMEM;
    }
 
    input_device = input_allocate_device();    //  给input_device指针申请分配内存
    if (!input_device) {
        rc = -ENOMEM;
        goto error_alloc_dev;
    }
 
    ts->input = input_device;                  //  通过gsl_ts->input指针去指向input输入设备
    input_device->name = GSLX680_I2C_NAME;     //  设置input设备的名字
    input_device->id.bustype = BUS_I2C;        //  设置input设备的总线类型
    input_device->dev.parent = &client->dev;   //  设置input设备的父设备:   /sys/devices/platform/s3c2410-i2cn/i2c-%d/%d-%04x
                                               //  但是通过后面的分析可知,最终不是这个父设备
    input_set_drvdata(input_device, ts);       //  将gsl_ts结构体作为input设备的私有数据区中的设备驱动数据
 
//   以下是对input_dev 输入设备的一些设置  设置input设备可以上报的事件类型
    set_bit(EV_ABS, input_device->evbit);
    set_bit(BTN_TOUCH, input_device->keybit);
    set_bit(EV_ABS, input_device->evbit);
    set_bit(EV_KEY, input_device->evbit);
    input_set_abs_params(input_device, ABS_X, 0, SCREEN_MAX_X, 0, 0);
    input_set_abs_params(input_device, ABS_Y, 0, SCREEN_MAX_Y, 0, 0);
    input_set_abs_params(input_device, ABS_PRESSURE, 0, 1, 0, 0);
#ifdef HAVE_TOUCH_KEY
    input_device->evbit[0] = BIT_MASK(EV_KEY);
    //input_device->evbit[0] = BIT_MASK(EV_SYN) | BIT_MASK(EV_KEY) | BIT_MASK(EV_ABS);
    for (i = 0; i < MAX_KEY_NUM; i++)
        set_bit(key_array[i], input_device->keybit);
#endif
    
    client->irq = IRQ_PORT;               //  触摸屏使用到的中断号
    ts->irq = client->irq;                //  
 
    ts->wq = create_singlethread_workqueue("kworkqueue_ts");
    if (!ts->wq) {
        dev_err(&client->dev, "Could not create workqueue\n");
        goto error_wq_create;
    }
    flush_workqueue(ts->wq);    
 
    INIT_WORK(&ts->work, gslX680_ts_worker);   //  初始化工作队列  当发生中断的时候在在中断处理函数中就会调用这个工作队列
                                               //  作为中断的下半部
    rc = input_register_device(input_device);  //   注册input设备
    if (rc)
        goto error_unreg_device;
 
    return 0;
 
error_unreg_device:
    destroy_workqueue(ts->wq);
error_wq_create:
    input_free_device(input_device);
error_alloc_dev:
    kfree(ts->touch_data);
    return rc;
}


        中断上半部是probe函数绑定gsl_ts_irq,下半部gslX680_ts_worker
        gslX680_ts_worker-->gsl_ts_read-->i2c_master_recv-->i2c_transfer-->adap->algo->master_xfer(adap, msgs, num)      
        gsl_ts_write-->i2c_master_send-->i2c_transfer-->adap->algo->master_xfer(adap, msgs, num)
        工作流程:触摸屏按下并-->触摸屏IC完成AD转换-->中断信号到I2C控制器-->I2C设备驱动层中断函数-->核心层调用I2C总线驱动层的通信算法到缓冲区


中断
        中断上下文不能和用户空间数据交互,不能交出CPU(不能休眠、不能schedule)
        中断上文中可处理其他更紧急事务
        中断下文处理策略:tasklet(小任务),workqueue(工作队列)
        任务急切且少在tasklet执行,所不急迫且任务多在workqueue中执行

demo1:

        使用中断上下文(tasklet,workqueue)实现按键捕获

        写应用程序捕获触摸屏反馈信息

button_tasklet_workqueue-x210.c

#include <linux/input.h> 
#include <linux/module.h> 
#include <linux/init.h>
#include <asm/irq.h> 
#include <asm/io.h>
#include <mach/irqs.h>
#include <linux/interrupt.h>
#include <linux/gpio.h>


#define BUTTON_IRQ      IRQ_EINT2

static struct input_dev *button_dev;

//void func(unsigned long data)
void func(struct work_struct *work)
{
        int flag;

        printk("bottom half\n");

        s3c_gpio_cfgpin(S5PV210_GPH0(2), S3C_GPIO_SFN(0x0));            // input模式
        flag = gpio_get_value(S5PV210_GPH0(2));
        s3c_gpio_cfgpin(S5PV210_GPH0(2), S3C_GPIO_SFN(0x0f));           // eint2模式

        input_report_key(button_dev, KEY_LEFT, !flag);
        input_sync(button_dev);
}

//DECLARE_TASKLET(button_tasklet, func, 0);
DECLARE_WORK(button_work, func);

static irqreturn_t button_interrupt(int irq, void *dummy) 
{ 
        printk("top half\n");

        //tasklet_schedule(&button_tasklet);
        schedule_work(&button_work);

        return IRQ_HANDLED; 
}

static int __init button_init(void) 
{ 
        int error;

        error = gpio_request(S5PV210_GPH0(2), "GPH0_2");
        if(error)
                printk("key-s5pv210: request gpio GPH0(2) fail");
        s3c_gpio_cfgpin(S5PV210_GPH0(2), S3C_GPIO_SFN(0x0f));           // eint2模式

        if (request_irq(BUTTON_IRQ, button_interrupt, IRQF_TRIGGER_FALLING | IRQF_TRIGGER_RISING, "button-x210", NULL)) 
        { 
                printk(KERN_ERR "key-s5pv210.c: Can't allocate irq %d\n", BUTTON_IRQ);
                goto err_free_gpio;
        }
        button_dev = input_allocate_device();
        if (!button_dev) 
        { 
                printk(KERN_ERR "key-s5pv210.c: Not enough memory\n");
                error = -ENOMEM;
                goto err_free_irq; 
        }

        button_dev->evbit[0] = BIT_MASK(EV_KEY);
        button_dev->keybit[BIT_WORD(KEY_LEFT)] = BIT_MASK(KEY_LEFT);

        error = input_register_device(button_dev);
        if (error) 
        { 
                printk(KERN_ERR "key-s5pv210.c: Failed to register device\n");
                goto err_free_dev; 
        }
        return 0;

err_free_dev:
        input_free_device(button_dev);
err_free_irq:
        free_irq(BUTTON_IRQ, button_interrupt);
        return error; 
err_free_gpio:
                gpio_free(S5PV210_GPH0(2));
        return error;
}

static void __exit button_exit(void) 
{ 
        input_unregister_device(button_dev); 
        input_free_device(button_dev);
        free_irq(BUTTON_IRQ, NULL);
        gpio_free(S5PV210_GPH0(2));
}

module_init(button_init); 
module_exit(button_exit); 
MODULE_LICENSE("GPL");
MODULE_AUTHOR("cxb");
MODULE_DESCRIPTION("button  module");
MODULE_ALIAS("button");

button.c 

#include <stdio.h>
#include <sys/types.h>
#include <sys/stat.h>
#include <fcntl.h>
#include <linux/input.h>
#include <string.h>
 
#define X210_KEY        "/dev/input/event2"
 
 
int main(void)
{
        int fd = -1, ret = -1;
        struct input_event ev;

        fd = open(X210_KEY, O_RDONLY);
        if (fd < 0)
        {
                perror("open");
                return -1;
        }

        while (1)
        {
                memset(&ev, 0, sizeof(struct input_event));
                ret = read(fd, &ev, sizeof(struct input_event));
                if (ret != sizeof(struct input_event))
                {
                        perror("read");
                        close(fd);
                        return -1;
                }

                printf("-------------------------\n");
                printf("type: %hd\n", ev.type);
                printf("code: %hd\n", ev.code);
                printf("value: %d\n", ev.value);
                printf("\n");
        }

        close(fd);

        return 0;
}

touchscreen.c 

#include <stdio.h>
#include <sys/types.h>
#include <sys/stat.h>
#include <fcntl.h>
#include <linux/input.h>
#include <string.h>
 
#define X210_TOUCHSCREEN        "/dev/input/event1"
 
 
int main(void)
{
        int fd = -1, ret = -1;
        struct input_event ev;

        fd = open(X210_TOUCHSCREEN, O_RDONLY);
        if (fd < 0)
        {
                perror("open");
                return -1;
        }

        while (1)
        {
                memset(&ev, 0, sizeof(struct input_event));
                ret = read(fd, &ev, sizeof(struct input_event));
                if (ret != sizeof(struct input_event))
                {
                        perror("read");
                        close(fd);
                        return -1;
                }

                printf("-------------------------\n");
                printf("type: %hd\n", ev.type);
                printf("code: %hd\n", ev.code);
                printf("value: %d\n", ev.value);
                printf("\n");
        }

        close(fd);

        return 0;
}

Makefile 

KERN_DIR = /root/kernel
 
obj-m   += button_tasklet_workqueue-x210.o
 
all:
         make -C $(KERN_DIR) M=`pwd` modules 
         arm-linux-gcc touchscreen.c -o touchscreen
         arm-linux-gcc button.c -o button
cp:
         cp *.ko touchscreen button /root/rootfs/driver -f
 
.PHONY: clean
clean:
         make -C $(KERN_DIR) M=`pwd` modules clean
         rm -rf touchscreen button

 结果如图所示:

button

touch screen 

  • 24
    点赞
  • 26
    收藏
    觉得还不错? 一键收藏
  • 0
    评论

“相关推荐”对你有帮助么?

  • 非常没帮助
  • 没帮助
  • 一般
  • 有帮助
  • 非常有帮助
提交
评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值