一、思路整理
- 之前插入的是i2c的第四条总线,所以需要在设备树中的I2C-4节点中增加pca9685节点。
- 需要编写一个i2c_client的驱动,使得设备能够被检测到并且注册进内核。
- 需要编写一个i2c_device的驱动,使得可以对设备进行一个操作,完成各种通信指令和操作
- 需要编写一个App应用程序,用来调试和测试驱动的完整性,一个简单的demo
自己做下来发现1和2实现其中一种应该就能注册驱动设备。
二、设备树编写
设备树编写的代码:
&i2c4 { //将设备写进i2c4中
pca9685: pca9685@40 { //@40是设备的地址
compatible = "nxp,pca9685"; //这是用来匹配的字符串
reg = <0x40>; //reg存放设备树地址,不带读写
};
};
三、device_client编写
使用i2c_board_info来注册i2c设备的方式在3.0之前使用的比较多。现在可以使用设备树了更方便。
#include <linux/kernel.h>
#include <linux/init.h>
#include <linux/module.h>
#include <linux/i2c.h>
struct i2c_client *pca9685_client;
struct i2c_board_info pca9685_info = {
.type = "pca9685",
.addr = 0x40,
};
const unsigned short addr_list[] = {
0x40,
I2C_CLIENT_END
};
static int i2c_client_pca9685_init(void)
{
struct i2c_adapter *adapter;
adapter = i2c_get_adapter(4); //获取i2c4的i2c_adapter
if(!adapter) {
printk(KERN_ERR"i2c_get_adapter(4) fialed\n");
return -EINVAL;
}
pca9685_client = i2c_new_device(adapter, &pca9685_info); //把i2c_board_info注册进adapter中,返回一个i2c_client
if(!pca9685_client) {
printk(KERN_ERR"can't create i2c device %s\n", pca9685_info.type);
return -EINVAL;
}
i2c_put_adapter(adapter); //应该是更新一下adapter,因为有新设备的信息加进入去了
return 0;
}
static void i2c_client_pca9685_exit(void)
{
i2c_unregister_device(pca9685_client); //所以这里卸载的是对应的i2c_client
}
module_init(i2c_client_pca9685_init);
module_exit(i2c_client_pca9685_exit);
MODULE_AUTHOR("chentuo");
MODULE_LICENSE("GPL");
四、device_driver编写
通过之前的i2c-tool测试,驱动需要使用前需要做一下初始化
- 复位,寄存器0x00写0
i2cset -f -y I2CBUS CHIP-ADDRESS 0x00 0x0 b - 读取芯片的MODE1的内容
- 把MODE1的前7位清零,并且设置低5位为1
- 往PRE_SCALE寄存器里,写入需要输出的PWM预分频值
- 把MODE1的值恢复到睡眠之前
- 延迟5ms
- 往MODE1写入1010 0001(b),这里低5位是自增模式需要注意是否需要开启
如何修改引脚的PWM波:
- 设置LEDx_ON_L和LEDx_ON_H的值,x是第几号输出引脚,ON寄存器有高寄存器和低寄存器,组合在一起就是PWM上升的位置
- 设置LEDx_OFF_L和LEDx_OFF_H的值,x是第几号输出引脚,OFF寄存器有高寄存器和低寄存器,组合在一起就是PWM下降的位置
- 总的细分应该是4096,十六进制表示就是0x0FFF
#include <linux/kernel.h>
#include <linux/init.h>
#include <linux/module.h>
#include <linux/of.h>
#include <linux/i2c.h>
#include <linux/delay.h>
#include <asm/uaccess.h>
#define PCA9685_MODE1 0x00
#define PCA9685_PRESCALE 0xFE
#define LED0_ON_L 0x06
#define LED0_ON_H 0x07
#define LED0_OFF_L 0x08
#define LED0_OFF_H 0x09
static int pca9685_major = 0;
static struct class *pca9685_class;
static struct i2c_client *pca9685_client;
static const struct of_device_id of_match_ids_pca9685[] = {
{ .compatible = "nxp,pca9685", .data = NULL },
{ /* END OF LIST */ }
};
static const struct i2c_device_id pca9685_ids[] = {
{ "pca9685", (kernel_ulong_t)NULL },
{ /* END OF LIST */ }
};
int pca9685_i2c_write(struct i2c_client *client, uint8_t reg_addr, uint8_t data)
{
struct i2c_msg msg;
uint8_t txbuf[] = {reg_addr, data};
int ret = -1;
msg.flags = !I2C_M_RD;
msg.addr = client->addr;
msg.len = 2;
msg.buf = txbuf;
ret = i2c_transfer(client->adapter, &msg, 1);
return ret;
}
static uint8_t pca9685_i2c_read(struct i2c_client *client, uint8_t reg_addr)
{
struct i2c_msg msgs[2];
uint8_t rxbuf[1];
msgs[0].flags = !I2C_M_RD;
msgs[0].addr = client->addr;
msgs[0].len = 1;
msgs[0].buf = ®_addr;
msgs[1].flags = I2C_M_RD;
msgs[1].addr = client->addr;
msgs[1].len = 1;
msgs[1].buf = rxbuf;
i2c_transfer(client->adapter, msgs, 2);
return rxbuf[0];
}
/*
static void reset(void)
{
pca9685_i2c_write(pca9685_client, PCA9685_MODE1, 0x00);
}
*/
static void setPWMFreq(uint8_t freq)
{
float pre_scale_val;
uint8_t prescale = 0;
uint8_t old_mode = 0;
uint8_t new_mode = 0;
pre_scale_val = 25000000.0/(4096*freq*0.915);
prescale = (uint8_t)(pre_scale_val+0.5)-1;
old_mode = pca9685_i2c_read(pca9685_client, PCA9685_MODE1);
new_mode = (old_mode&0x7F) | 0x10; //sleep
pca9685_i2c_write(pca9685_client, PCA9685_MODE1, new_mode); //go to sleep
pca9685_i2c_write(pca9685_client, PCA9685_PRESCALE, prescale); //set the prescaler
old_mode = old_mode & 0xEF;
pca9685_i2c_write(pca9685_client, PCA9685_MODE1, old_mode);
mdelay(5);
pca9685_i2c_write(pca9685_client, PCA9685_MODE1, old_mode | 0xa1);
}
static void setPWM(uint8_t num, uint16_t on, uint16_t off)
{
pca9685_i2c_write(pca9685_client, LED0_ON_L+4*num, on);
pca9685_i2c_write(pca9685_client, LED0_ON_L+4*num+1, on>>8);
pca9685_i2c_write(pca9685_client, LED0_ON_L+4*num+2, off);
pca9685_i2c_write(pca9685_client, LED0_ON_L+4*num+3, off>>8);
}
int pca9685_open(struct inode *inode, struct file *file)
{
return 0;
}
ssize_t pca9685_read(struct file *file, char __user *buf, size_t size, loff_t *offset)
{
char kernel_buf[6];
int err = 0;
err = copy_to_user(buf, kernel_buf, size);
return size;
}
ssize_t pca9685_write(struct file *file, const char __user *buf, size_t size, loff_t *offset)
{
int err = -1;
int value;
err = copy_from_user(&value, buf, sizeof(int));
if(value > 2000) value = 2000;
if(value < 1000) value = 1000;
setPWM(0, 0, value/5);
return 0;
}
//int (*release) (struct inode *, struct file *);
static struct file_operations pca9685_ops = {
.owner = THIS_MODULE,
.open = pca9685_open,
// .read = pca9685_read,
.write = pca9685_write,
};
int pca9685_probe(struct i2c_client *client, const struct i2c_device_id *id)
{
printk(KERN_ERR "pca9685: probe.\n");
pca9685_client = client;
pca9685_major = register_chrdev(0, "pca9685", &pca9685_ops);
if(pca9685_major < 0) {
printk(KERN_ERR "pca9685: couldn't get a major number.\n");
return -1;
}
pca9685_class = class_create(THIS_MODULE, "pca9685_class");
if(IS_ERR(pca9685_class)) {
printk(KERN_ERR "pca9685 class: create failed.\n");
unregister_chrdev(pca9685_major, "pca9685");
return -1;
}
device_create(pca9685_class, NULL, MKDEV(pca9685_major, 0), NULL, "pca9685");
// reset();
setPWMFreq(50);
return 0;
}
int pca9685_remove(struct i2c_client *client)
{
printk(KERN_ERR "pca9685: remove.\n");
device_destroy(pca9685_class, MKDEV(pca9685_major, 0));
class_destroy(pca9685_class);
unregister_chrdev(pca9685_major, "pca9685");
return 0;
}
static struct i2c_driver i2c_driver_pca9685 = {
.driver = {
.name = "pca9685",
.of_match_table = of_match_ids_pca9685,
},
.probe = pca9685_probe,
.remove = pca9685_remove,
.id_table = pca9685_ids,
};
static int __init pca9685_init(void)
{
int ret = i2c_add_driver(&i2c_driver_pca9685);
printk(KERN_ERR "pca9685: init.\n");
return ret;
}
static void __exit pca9685_exit(void)
{
i2c_del_driver(&i2c_driver_pca9685);
printk(KERN_ERR "pca9685: exit.\n");
}
module_init(pca9685_init);
module_exit(pca9685_exit);
MODULE_AUTHOR("chentuo");
MODULE_LICENSE("GPL");
五、device_test编写
#include <stdio.h>
#include <sys/types.h>
#include <sys/stat.h>
#include <fcntl.h>
#include <unistd.h>
#include <string.h>
#include <stdlib.h>
int main(int argc, char *argv[])
{
int fd;
int on;
printf("hello world\n");
fd = open("/dev/pca9685", O_RDWR);
if(fd < 0) {
printf("can not open file\n");
return -1;
}
if(argc != 2) {
printf("usage: %s [1000~2000]\n", argv[0]);
return -1;
}
on = atoi(argv[1]);
write(fd, &on, sizeof(int));
close(fd);
return 0;
}