网上招聘网站开发报告百度网讯科技有限公司官网
本文主要探讨x210驱动的平台设备类型(platform)以及misc设备。
驱动模型
设备驱动模型:总线(bus type)、设备(device)和驱动(driver)
总线:虚拟总线用于挂接驱动驱动和设备
总线、设备、驱动关系:/sys/bus下的子目录对应不同总线,总线目录有设备、驱动目录和、总线属性文件
总线
struct bus_type {const char *name;struct bus_attribute *bus_attrs;struct device_attribute *dev_attrs;struct driver_attribute *drv_attrs;int (*match)(struct device *dev, struct device_driver *drv);int (*uevent)(struct device *dev, struct kobj_uevent_env *env);int (*probe)(struct device *dev);int (*remove)(struct device *dev);void (*shutdown)(struct device *dev);int (*suspend)(struct device *dev, pm_message_t state);int (*resume)(struct device *dev);const struct dev_pm_ops *pm;struct bus_type_private *p;
};
总线属性
struct bus_attribute {struct attribute attr;ssize_t (*show)(struct bus_type *bus, char *buf);ssize_t (*store)(struct bus_type *bus, const char *buf, size_t count);
};
设备属性
struct device_attribute {struct attribute attr;ssize_t (*show)(struct device *dev, struct device_attribute *attr,char *buf);ssize_t (*store)(struct device *dev, struct device_attribute *attr,const char *buf, size_t count);
};
驱动属性
struct driver_attribute {struct attribute attr;ssize_t (*show)(struct device_driver *driver, char *buf);ssize_t (*store)(struct device_driver *driver, const char *buf,size_t count);
};
公共属性结构体(show(read)和store(write)方法)
struct attribute {const char *name;struct module *owner;mode_t mode;
#ifdef CONFIG_DEBUG_LOCK_ALLOCstruct lock_class_key *key;struct lock_class_key skey;
#endif
};
总线示例
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,
};
name总线名称,struct bus_attribute,struct device_attribute,struct driver_attribut为总线,设备,驱动属性和方法
match为设备和驱动匹配函数,uevent内核向用户通知事件,probe探测函数,remove移除函数,shutdown关闭函数,suspend挂起,resume唤醒,struct dev_pm_ops *pm;电源管理,struct bus_type_private *p;私有数据
struct bus_type_private {struct kset subsys;struct kset *drivers_kset;struct kset *devices_kset;struct klist klist_devices;struct klist klist_drivers;struct blocking_notifier_head bus_notifier;unsigned int drivers_autoprobe:1;struct bus_type *bus;
};
struct kset subsys;总线子系统,kobj为子系统顶层目录
struct kset *drivers_kset;struct kset *devices_kset;挂载到该总线上的驱动和设备集合
struct klist klist_devices;struct klist klist_drivers;设备和驱动链表
unsigned int drivers_autoprobe:1;注册时自动探测设备
struct bus_type *bus;回指针
设备
struct device
{struct device *parent;struct device_private *p;struct kobject kobj;const char *init_name; /* initial name of the device */struct device_type *type;struct mutex mutex; /* mutex to synchronize calls to* its driver.*/struct bus_type *bus; /* type of bus device is on */struct device_driver *driver; /* which driver has allocated thisdevice */void *platform_data; /* Platform specific data, devicecore doesn't touch it */struct dev_pm_info power;#ifdef CONFIG_NUMAint numa_node; /* NUMA node this device is close to */
#endifu64 *dma_mask; /* dma mask (if dma'able device) */u64 coherent_dma_mask;/* Like dma_mask, but foralloc_coherent mappings asnot all hardware supports64 bit addresses for consistentallocations such descriptors. */struct device_dma_parameters *dma_parms;struct list_head dma_pools; /* dma pools (if dma'ble) */struct dma_coherent_mem *dma_mem; /* internal for coherent memoverride *//* arch specific additions */struct dev_archdata archdata;
#ifdef CONFIG_OFstruct device_node *of_node;
#endifdev_t devt; /* dev_t, creates the sysfs "dev" */spinlock_t devres_lock;struct list_head devres_head;struct klist_node knode_class;struct class *class;const struct attribute_group **groups; /* optional groups */void (*release)(struct device *dev);
}
device结构体用于描述设备
struct device *parent;父设备
struct device_private *p;私有数据
struct device_private {struct klist klist_children;struct klist_node knode_parent;struct klist_node knode_driver;struct klist_node knode_bus;void *driver_data;struct device *device;
};
const char *init_name;设备名
struct bus_type *bus;指向总线
struct device_type *type;设备处理函数
struct device_type {const char *name;const struct attribute_group **groups;int (*uevent)(struct device *dev, struct kobj_uevent_env *env);char *(*devnode)(struct device *dev, mode_t *mode);void (*release)(struct device *dev);const struct dev_pm_ops *pm;
};
struct device_driver *driver;设备驱动
struct kobject kobj;内嵌kobject
struct kobject {const char *name;struct list_head entry;struct kobject *parent;struct kset *kset;struct kobj_type *ktype;struct sysfs_dirent *sd;struct kref kref;unsigned int state_initialized:1;unsigned int state_in_sysfs:1;unsigned int state_add_uevent_sent:1;unsigned int state_remove_uevent_sent:1;unsigned int uevent_suppress:1;
};
void (*release)(struct device *dev);释放设备回调函数
dev_t devt;设备号
struct class *class;设备类类指针
void *platform_data;平台设备数据(gpio、中断号、设备名称等)
设备注册和注销
int device_register(struct device *dev);
void device_unregister(struct device *dev);
宏DEVICE_ATTR定义attribute结构
#define DEVICE_ATTR(_name, _mode, _show, _store) \
struct device_attribute dev_attr_##_name = __ATTR(_name, _mode, _show, _store)
创建和删除device目录下的属性文件
int device_create_file(struct device *dev,const struct device_attribute *attr);
void device_remove_file(struct device *dev,const struct device_attribute *attr);
驱动
struct device_driver {const char *name;struct bus_type *bus;struct module *owner;const char *mod_name; /* used for built-in modules */bool suppress_bind_attrs; /* disables bind/unbind via sysfs */#if defined(CONFIG_OF)const struct of_device_id *of_match_table;
#endifint (*probe) (struct device *dev);int (*remove) (struct device *dev);void (*shutdown) (struct device *dev);int (*suspend) (struct device *dev, pm_message_t state);int (*resume) (struct device *dev);const struct attribute_group **groups;const struct dev_pm_ops *pm;struct driver_private *p;
}
const char *name;驱动名字与设备名字相同总线match匹配函数才可对应找到
struct bus_type *bus;指向驱动总线
const char *mod_name;驱动模块名字
probe驱动探测方法(装载使用),remove删除驱动,shutdown关闭驱动方法,suspend挂起方法,resume唤醒方法
struct driver_private *p;设备驱动私有数据
struct driver_private {struct kobject kobj;struct klist klist_devices;struct klist_node knode_bus;struct module_kobject *mkobj;struct device_driver *driver;
};
const struct attribute_group **groups;驱动属性组
struct attribute_group {const char *name;mode_t (*is_visible)(struct kobject *,struct attribute *, int);struct attribute **attrs;
};
驱动程序注册和注销
int driver_register(struct device_driver *drv);
void driver_unregister(struct device_driver *drv);
驱动属性文件删除和创建
int driver_create_file(struct device_driver *drv, const struct driver_attribute *attr);
void driver_remove_file(struct device_driver *drv,const struct driver_attribute *attr);
platform(drivers/base/platform.c)
平台设备:wdt、i2c、i2s、rtc,adc等
CPU与外部通信:地址总线、专用接口
平台总线为地址总线式连接设备(soc内部外设)
平台设备(struct platform_device)
struct platform_device {const char * name;int id;struct device dev;u32 num_resources;struct resource * resource;const struct platform_device_id *id_entry;/* arch specific additions */struct pdev_archdata archdata;
};
name设备名,struct device dev;设备结构体
const struct platform_device_id *id_entry;设备ID表
struct pdev_archdata archdata;预留
struct resource * resource;资源数组
u32 num_resources;设备使用资源数量
struct resource {resource_size_t start;resource_size_t end;const char *name;unsigned long flags;struct resource *parent, *sibling, *child;
};
static struct resource s3c_wdt_resource[] = {[0] = {.start = S3C_PA_WDT,.end = S3C_PA_WDT + SZ_1M - 1,.flags = IORESOURCE_MEM,},[1] = {.start = IRQ_WDT,.end = IRQ_WDT,.flags = IORESOURCE_IRQ,}
};
start资源起始地址(WTCON),资源结束地址,name资源名,flags资源类型(IORESOURCE_MEM内存资源)
start资源起始地址(IRQ_WDT中断开始信号),资源结束地址(IRQ_WDT中断结束信号),flags资源类型(IORESOURCE_IRQ中断资源)
flags标志:I/O端口(IORESOURCE_IO)、内存资源(IORESOURCE_MEM)、中断号(IORESOURCE_IRQ)、DMA资源(IORESOURCE_DMA)
struct resource *parent, *sibling, *child;构建资源设备树
平台设备函数
int platform_device_add(struct platform_device *pdev);
void platform_device_del(struct platform_device *pdev);
int platform_device_register(struct platform_device *pdev);
void platform_device_unregister(struct platform_device *pdev);
struct resource *platform_get_resource(struct platform_device *dev,unsigned int type, unsigned int num);
平台设备驱动
struct platform_driver {int (*probe)(struct platform_device *);int (*remove)(struct platform_device *);void (*shutdown)(struct platform_device *);int (*suspend)(struct platform_device *, pm_message_t state);int (*resume)(struct platform_device *);struct device_driver driver;const struct platform_device_id *id_table;
};
struct device_driver driver;设备驱动结构体
const struct platform_device_id *id_table;设备ID表
probe驱动探测方法(装载使用),remove删除驱动,shutdown关闭驱动方法,suspend挂起方法,resume唤醒方法
平台驱动注册(probe)和注销(remove)
int platform_driver_register(struct platform_driver *drv);
void platform_driver_unregister(struct platform_driver *drv);
misc
杂项主设备号通常为10
设备类文件:/sys/class/misc
混杂设备
struct miscdevice {int minor;const char *name;const struct file_operations *fops;struct list_head list;struct device *parent;struct device *this_device;const char *nodename;mode_t mode;
};
minor次设备号,name设备名,fops设备操作函数,this_device当前设备指针
混杂设备的注册和注销
int misc_register(struct miscdevice * misc);
int misc_deregister(struct miscdevice *misc);
210蜂鸣器(x210-buzzer.c)
#include <linux/module.h>
#include <linux/kernel.h>
#include <linux/fs.h>
#include <linux/init.h>
#include <linux/delay.h>
#include <linux/poll.h>
#include <asm/irq.h>
#include <asm/io.h>
#include <linux/interrupt.h>
#include <asm/uaccess.h>
#include <mach/hardware.h>
#include <plat/regs-timer.h>
#include <mach/regs-irq.h>
#include <asm/mach/time.h>
#include <linux/clk.h>
#include <linux/cdev.h>
#include <linux/device.h>
#include <linux/miscdevice.h>
#include <linux/gpio.h>
#include <plat/gpio-cfg.h>//定义设备名
#define DEVICE_NAME "buzzer"//定义cmd
#define PWM_IOCTL_SET_FREQ 1
#define PWM_IOCTL_STOP 0//定义信号量
static struct semaphore lock;//初始化buzzer,设置频率
// TCFG0在Uboot中设置,这里不再重复设置
// Timer0输入频率Finput=pclk/(prescaler1+1)/MUX1=66M/16/16
// TCFG0 = tcnt = (pclk/16/16)/freq;
// PWM0输出频率Foutput =Finput/TCFG0= freq
static void PWM_Set_Freq( unsigned long freq )
{unsigned long tcon;unsigned long tcnt;unsigned long tcfg1;struct clk *clk_p;unsigned long pclk;//unsigned tmp;//设置GPD0_2为PWM输出s3c_gpio_cfgpin(S5PV210_GPD0(2), S3C_GPIO_SFN(2));tcon = __raw_readl(S3C2410_TCON);tcfg1 = __raw_readl(S3C2410_TCFG1);//mux = 1/16tcfg1 &= ~(0xf<<8);tcfg1 |= (0x4<<8);__raw_writel(tcfg1, S3C2410_TCFG1);clk_p = clk_get(NULL, "pclk");pclk = clk_get_rate(clk_p);tcnt = (pclk/16/16)/freq;__raw_writel(tcnt, S3C2410_TCNTB(2));__raw_writel(tcnt/2, S3C2410_TCMPB(2));//占空比为50%tcon &= ~(0xf<<12);tcon |= (0xb<<12); //disable deadzone, auto-reload, inv-off, update TCNTB0&TCMPB0, start timer 0__raw_writel(tcon, S3C2410_TCON);tcon &= ~(2<<12); //clear manual update bit__raw_writel(tcon, S3C2410_TCON);
}//停止buzzer(改为输入模式)
void PWM_Stop( void )
{//将GPD0_2设置为inputs3c_gpio_cfgpin(S5PV210_GPD0(2), S3C_GPIO_SFN(0));
}//对应open,开锁
static int x210_pwm_open(struct inode *inode, struct file *file)
{if (!down_trylock(&lock))return 0;elsereturn -EBUSY;}//对应close,上锁
static int x210_pwm_close(struct inode *inode, struct file *file)
{up(&lock);return 0;
}// PWM:GPF14->PWM0(接收cmd,设置频率,关闭buzzer)
static int x210_pwm_ioctl(struct inode *inode, struct file *file, unsigned int cmd, unsigned long arg)
{switch (cmd) {case PWM_IOCTL_SET_FREQ:printk("PWM_IOCTL_SET_FREQ:\r\n");if (arg == 0)return -EINVAL;PWM_Set_Freq(arg);break;case PWM_IOCTL_STOP:default:printk("PWM_IOCTL_STOP:\r\n");PWM_Stop();break;}return 0;
}static struct file_operations dev_fops = {.owner = THIS_MODULE,.open = x210_pwm_open,.release = x210_pwm_close, .ioctl = x210_pwm_ioctl,
};//定义msic设备
static struct miscdevice misc = {.minor = MISC_DYNAMIC_MINOR,.name = DEVICE_NAME,.fops = &dev_fops,
};//驱动装载
static int __init dev_init(void)
{int ret;init_MUTEX(&lock);ret = misc_register(&misc);/* GPD0_2 (PWMTOUT2) */ret = gpio_request(S5PV210_GPD0(2), "GPD0");if(ret)printk("buzzer-x210: request gpio GPD0(2) fail");s3c_gpio_setpull(S5PV210_GPD0(2), S3C_GPIO_PULL_UP);s3c_gpio_cfgpin(S5PV210_GPD0(2), S3C_GPIO_SFN(1));gpio_set_value(S5PV210_GPD0(2), 0);printk ("x210 "DEVICE_NAME" initialized\n");return ret;
}//驱动卸载
static void __exit dev_exit(void)
{misc_deregister(&misc);
}module_init(dev_init);
module_exit(dev_exit);
MODULE_LICENSE("GPL");
MODULE_AUTHOR("www.9tripod.com");
MODULE_DESCRIPTION("x210 PWM Driver");
buzzer.c
#include <stdio.h>
#include <sys/stat.h>
#include <fcntl.h>#define DEVNAME "/dev/buzzer"#define PWM_IOCTL_SET_FREQ 1
#define PWM_IOCTL_STOP 0int main(void)
{int fd = -1;fd = open(DEVNAME, O_RDWR);if (fd < 0){perror("open");return -1;}ioctl(fd, PWM_IOCTL_SET_FREQ, 10000);sleep(3);ioctl(fd, PWM_IOCTL_STOP);close(fd);
}
demo:
使用平台总线方式驱动led(模仿leds-s3c24xx.c)
Makefile
KERN_DIR = /root/kernelobj-m += x210-led.oall:make -C $(KERN_DIR) M=`pwd` modules cp:cp *.ko /root/rootfs/driver.PHONY: clean
clean:make -C $(KERN_DIR) M=`pwd` modules clean
x210-led.c
#include <linux/module.h>
#include <linux/init.h>
#include <linux/fs.h>
#include <linux/leds.h>
#include <mach/regs-gpio.h>
#include <mach/gpio-bank.h>
#include <linux/io.h>
#include <linux/ioport.h>
#include <mach/gpio.h>
#include <linux/platform_device.h>
#include <linux/slab.h>
#include <mach/leds_x210-gpio.h>#define LED_OFF 1
#define LED_ON 0struct s5pv210_gpio_led
{struct led_classdev cdev;struct s5pv210_led_platdata *pdata;
};static inline struct s5pv210_gpio_led *pdev_to_gpio(struct platform_device *dev)
{return platform_get_drvdata(dev);
}static inline struct s5pv210_gpio_led *to_gpio(struct led_classdev *led_cdev)
{return container_of(led_cdev, struct s5pv210_gpio_led, cdev);
}static void s5pv210_led_set(struct led_classdev *led_cdev,enum led_brightness value)
{struct s5pv210_gpio_led *p = to_gpio(led_cdev);if(value == LED_OFF){gpio_set_value(p->pdata->gpio,LED_OFF);}else{gpio_set_value(p->pdata->gpio,LED_ON);}
}int s5pv210_led_probe(struct platform_device *dev)
{int ret = -1;struct s5pv210_led_platdata *pdata = dev->dev.platform_data;struct s5pv210_gpio_led *led;led = kzalloc(sizeof(struct s5pv210_gpio_led), GFP_KERNEL);if (led == NULL) {dev_err(&dev->dev, "No memory for device\n");return -ENOMEM;}platform_set_drvdata(dev, led);ret = gpio_request(pdata->gpio, pdata->name);if (ret != 0) {printk(KERN_ERR "gpio_request failed %d\n",ret);return ret;} else {gpio_direction_output(pdata->gpio,GPIOF_OUT_INIT_HIGH);}led->cdev.name = pdata->name;led->cdev.brightness = 0;led->cdev.brightness_set = s5pv210_led_set;led->pdata = pdata;ret = led_classdev_register(&dev->dev, &led->cdev);if (ret < 0) {printk(KERN_ERR "led classdev register failed\n");kfree(led);return ret;}return 0;
}static int s5pv210_led_remove(struct platform_device *dev)
{struct s5pv210_gpio_led *p = pdev_to_gpio(dev);led_classdev_unregister(&p->cdev);gpio_free(p->pdata->gpio);kfree(p);return 0;
}struct platform_driver s5pv210_led_driver[] ={[0] = {.probe = s5pv210_led_probe,.remove = s5pv210_led_remove,.driver = {.name = "led1",.owner = THIS_MODULE,}},[1] = {.probe = s5pv210_led_probe,.remove = s5pv210_led_remove,.driver = {.name = "led2",.owner = THIS_MODULE,}},[2] = {.probe = s5pv210_led_probe,.remove = s5pv210_led_remove,.driver = {.name = "led3",.owner = THIS_MODULE,}},
};static int __init led_dev_init(void)
{platform_driver_register(&s5pv210_led_driver[0]);platform_driver_register(&s5pv210_led_driver[1]);platform_driver_register(&s5pv210_led_driver[2]);return 0;
}static void __exit led_dev_exit(void)
{platform_driver_unregister(&s5pv210_led_driver[0]);platform_driver_unregister(&s5pv210_led_driver[1]);platform_driver_unregister(&s5pv210_led_driver[2]);
}module_init(led_dev_init);
module_exit(led_dev_exit);
MODULE_LICENSE("GPL");
MODULE_AUTHOR("cxb");
MODULE_DESCRIPTION("led gpio module");
MODULE_ALIAS("led");
操作流程
vim arch/arm/mach-s5cpv210/include/mach/leds_x210-gpio.h添加设备特殊数据结构体(gpio、中断号、设备名称等)#ifndef __ASM_ARCH_LEDSGPIO_H
#define __ASM_ARCH_LEDSGPIO_H "leds-gpio.h"#define S5PV210_LEDF_ACTLOW (1<<0) /* LED is on when GPIO low */
#define S5PV210_LEDF_TRISTATE (1<<1) /* tristate to turn off */struct s5pv210_led_platdata {unsigned int gpio;unsigned int flags;char *name;char *def_trigger;
};#endif /* __ASM_ARCH_LEDSGPIO_H */vim arch/arm/mach-s5pv210/mach-x210.c添加设备特殊数据结构体#include <mach/leds_x210-gpio.h>定义如下平台总线设备到smdkc110_devices[]前static struct s5pv210_led_platdata x210_led1_pdata = {.name = "led1",.gpio = S5PV210_GPJ0(3),.flags = S5PV210_LEDF_ACTLOW | S5PV210_LEDF_TRISTATE,.def_trigger = "",
};static struct platform_device x210_led1 = {.name = "led1",.id = 0,.dev = {.platform_data = &x210_led1_pdata,},
};static struct s5pv210_led_platdata x210_led2_pdata = {.name = "led2",.gpio = S5PV210_GPJ0(4),.flags = S5PV210_LEDF_ACTLOW | S5PV210_LEDF_TRISTATE,.def_trigger = "",
};static struct platform_device x210_led2 = {.name = "led2",.id = 1,.dev = {.platform_data = &x210_led2_pdata,},
};static struct s5pv210_led_platdata x210_led3_pdata = {.name = "led3",.gpio = S5PV210_GPJ0(5),.flags = S5PV210_LEDF_ACTLOW | S5PV210_LEDF_TRISTATE,.def_trigger = "",
};static struct platform_device x210_led3 = {.name = "led3",.id = 2,.dev = {.platform_data = &x210_led3_pdata,},
};添加如下平台总线设备到smdkc110_devices[]&x210_led1
&x210_led2
&x210_led3make -j8 && cp arch/arm/boot/zImage ~/tftp -f make cp
结果示例: